CoCalc Logo Icon
StoreFeaturesDocsShareSupportNewsAboutSign UpSign In
Ardupilot

Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.

GitHub Repository: Ardupilot/ardupilot
Path: blob/master/ArduPlane/mode_autoland.cpp
Views: 1798
1
#include "mode.h"
2
#include "Plane.h"
3
#include <GCS_MAVLink/GCS.h>
4
5
#if MODE_AUTOLAND_ENABLED
6
7
/*
8
mode AutoLand parameters
9
*/
10
const AP_Param::GroupInfo ModeAutoLand::var_info[] = {
11
// @Param: WP_ALT
12
// @DisplayName: Final approach WP altitude
13
// @Description: This is the target altitude above HOME for final approach waypoint
14
// @Range: 0 200
15
// @Increment: 1
16
// @Units: m
17
// @User: Standard
18
AP_GROUPINFO("WP_ALT", 1, ModeAutoLand, final_wp_alt, 55),
19
20
// @Param: WP_DIST
21
// @DisplayName: Final approach WP distance
22
// @Description: This is the distance from Home that the final approach waypoint is set. The waypoint point will be in the opposite direction of takeoff (the direction the plane is facing when the plane sets its takeoff heading)
23
// @Range: 0 700
24
// @Increment: 1
25
// @Units: m
26
// @User: Standard
27
AP_GROUPINFO("WP_DIST", 2, ModeAutoLand, final_wp_dist, 400),
28
29
// @Param: DIR_OFF
30
// @DisplayName: Landing direction offset from takeoff
31
// @Description: The captured takeoff direction (at arming,if TKOFF_OPTION bit1 is set, or after ground course is established in autotakeoffs)is offset by this amount to create a different landing direction and approach.
32
// @Range: -360 360
33
// @Increment: 1
34
// @Units: deg
35
// @User: Standard
36
AP_GROUPINFO("DIR_OFF", 3, ModeAutoLand, landing_dir_off, 0),
37
38
AP_GROUPEND
39
};
40
41
ModeAutoLand::ModeAutoLand() :
42
Mode()
43
{
44
AP_Param::setup_object_defaults(this, var_info);
45
}
46
47
bool ModeAutoLand::_enter()
48
{
49
//must be flying to enter
50
if (!plane.is_flying()) {
51
gcs().send_text(MAV_SEVERITY_WARNING, "Must already be flying!");
52
return false;
53
}
54
55
//takeoff direction must be set and must not be a quadplane, otherwise since flying switch to RTL so this can be used as FS action
56
#if HAL_QUADPLANE_ENABLED
57
if (quadplane.available() && !quadplane.option_is_set(QuadPlane::OPTION::ALLOW_FW_LAND)) {
58
gcs().send_text(MAV_SEVERITY_WARNING, "Option not set to allow fixed wing autoland");
59
return false;
60
}
61
#endif
62
if (!plane.takeoff_state.initial_direction.initialized) {
63
gcs().send_text(MAV_SEVERITY_WARNING, "Takeoff initial direction not set,must use autotakeoff");
64
return false;
65
}
66
67
plane.prev_WP_loc = plane.current_loc;
68
plane.set_target_altitude_current();
69
70
/*
71
landing is in 3 steps:
72
1) a base leg waypoint
73
2) a land start WP, with crosstrack
74
3) the landing WP, with crosstrack
75
76
the base leg point is 90 degrees off from the landing leg
77
*/
78
const Location &home = ahrs.get_home();
79
80
/*
81
first calculate the starting waypoint we will use when doing the
82
NAV_LAND. This is offset by final_wp_dist from home, in a
83
direction 180 degrees from takeoff direction
84
*/
85
Location land_start_WP = home;
86
land_start_WP.offset_bearing(wrap_360(plane.takeoff_state.initial_direction.heading + 180), final_wp_dist);
87
land_start_WP.set_alt_m(final_wp_alt, Location::AltFrame::ABOVE_HOME);
88
land_start_WP.change_alt_frame(Location::AltFrame::ABSOLUTE);
89
90
/*
91
now create the initial target waypoint for the base leg. We
92
choose if we will do a right or left turn onto the landing based
93
on where we are when we enter the landing mode
94
*/
95
const float bearing_to_current_deg = wrap_180(degrees(land_start_WP.get_bearing(plane.current_loc)));
96
const float bearing_err_deg = wrap_180(wrap_180(plane.takeoff_state.initial_direction.heading) - bearing_to_current_deg);
97
const float bearing_offset_deg = bearing_err_deg > 0? -90 : 90;
98
const float base_leg_length = final_wp_dist * 0.333;
99
cmd[0].id = MAV_CMD_NAV_WAYPOINT;
100
cmd[0].content.location = land_start_WP;
101
cmd[0].content.location.offset_bearing(plane.takeoff_state.initial_direction.heading + bearing_offset_deg, base_leg_length);
102
// set a 1m acceptance radius, we want to fly all the way to this waypoint
103
cmd[0].p1 = 1;
104
105
/*
106
create the WP for the start of the landing
107
*/
108
cmd[1].content.location = land_start_WP;
109
cmd[1].id = MAV_CMD_NAV_WAYPOINT;
110
111
// and the land WP
112
cmd[2].id = MAV_CMD_NAV_LAND;
113
cmd[2].content.location = home;
114
115
// start first leg
116
stage = 0;
117
plane.start_command(cmd[0]);
118
119
// don't crosstrack initially
120
plane.auto_state.crosstrack = false;
121
plane.auto_state.next_wp_crosstrack = true;
122
123
return true;
124
}
125
126
void ModeAutoLand::update()
127
{
128
plane.calc_nav_roll();
129
plane.calc_nav_pitch();
130
plane.set_offset_altitude_location(plane.prev_WP_loc, plane.next_WP_loc);
131
if (plane.landing.is_throttle_suppressed()) {
132
// if landing is considered complete throttle is never allowed, regardless of landing type
133
SRV_Channels::set_output_scaled(SRV_Channel::k_throttle, 0.0);
134
} else {
135
plane.calc_throttle();
136
}
137
}
138
139
void ModeAutoLand::navigate()
140
{
141
if (stage == 2) {
142
// we are on final landing leg
143
plane.set_flight_stage(AP_FixedWing::FlightStage::LAND);
144
plane.verify_command(cmd[stage]);
145
return;
146
}
147
148
// see if we have completed the leg
149
if (plane.verify_nav_wp(cmd[stage])) {
150
stage++;
151
plane.prev_WP_loc = plane.next_WP_loc;
152
plane.auto_state.next_turn_angle = 90;
153
plane.start_command(cmd[stage]);
154
plane.auto_state.crosstrack = true;
155
plane.auto_state.next_wp_crosstrack = true;
156
}
157
}
158
#endif
159
160