APM:Copter
mode_rtl.cpp
Go to the documentation of this file.
1 #include "Copter.h"
2 
3 /*
4  * Init and run calls for RTL flight mode
5  *
6  * There are two parts to RTL, the high level decision making which controls which state we are in
7  * and the lower implementation of the waypoint or landing controllers within those states
8  */
9 
10 // rtl_init - initialise rtl controller
11 bool Copter::ModeRTL::init(bool ignore_checks)
12 {
13  if (copter.position_ok() || ignore_checks) {
14  // initialise waypoint and spline controller
16  build_path(!copter.failsafe.terrain);
17  climb_start();
18  return true;
19  }else{
20  return false;
21  }
22 }
23 
24 // re-start RTL with terrain following disabled
26 {
27  // log an error
29  if (rtl_path.terrain_used) {
30  build_path(false);
31  climb_start();
32  gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing");
33  }
34 }
35 
36 // rtl_run - runs the return-to-launch controller
37 // should be called at 100hz or more
38 void Copter::ModeRTL::run(bool disarm_on_land)
39 {
40  // check if we need to move to next state
41  if (_state_complete) {
42  switch (_state) {
43  case RTL_InitialClimb:
44  return_start();
45  break;
46  case RTL_ReturnHome:
48  break;
49  case RTL_LoiterAtHome:
50  if (rtl_path.land || copter.failsafe.radio) {
51  land_start();
52  }else{
53  descent_start();
54  }
55  break;
56  case RTL_FinalDescent:
57  // do nothing
58  break;
59  case RTL_Land:
60  // do nothing - rtl_land_run will take care of disarming motors
61  break;
62  }
63  }
64 
65  // call the correct run function
66  switch (_state) {
67 
68  case RTL_InitialClimb:
70  break;
71 
72  case RTL_ReturnHome:
74  break;
75 
76  case RTL_LoiterAtHome:
78  break;
79 
80  case RTL_FinalDescent:
81  descent_run();
82  break;
83 
84  case RTL_Land:
85  land_run(disarm_on_land);
86  break;
87  }
88 }
89 
90 // rtl_climb_start - initialise climb to RTL altitude
92 {
94  _state_complete = false;
95 
96  // RTL_SPEED == 0 means use WPNAV_SPEED
97  if (g.rtl_speed_cms != 0) {
99  }
100 
101  // set the destination
102  if (!wp_nav->set_wp_destination(rtl_path.climb_target)) {
103  // this should not happen because rtl_build_path will have checked terrain data was available
106  return;
107  }
108  wp_nav->set_fast_waypoint(true);
109 
110  // hold current yaw during initial climb
112 }
113 
114 // rtl_return_start - initialise return to home
116 {
118  _state_complete = false;
119 
120  if (!wp_nav->set_wp_destination(rtl_path.return_target)) {
121  // failure must be caused by missing terrain data, restart RTL
123  }
124 
125  // initialise yaw to point home (maybe)
127 }
128 
129 // rtl_climb_return_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
130 // called by rtl_run at 100hz or more
132 {
133  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
134  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
136  // To-Do: re-initialise wpnav targets
137  return;
138  }
139 
140  // process pilot's yaw input
141  float target_yaw_rate = 0;
142  if (!copter.failsafe.radio) {
143  // get pilot's desired yaw rate
145  if (!is_zero(target_yaw_rate)) {
147  }
148  }
149 
150  // set motors to full range
151  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
152 
153  // run waypoint controller
154  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
155 
156  // call z-axis position controller (wpnav should have already updated it's alt target)
158 
159  // call attitude controller
160  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
161  // roll & pitch from waypoint controller, yaw rate from pilot
162  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
163  }else{
164  // roll, pitch from waypoint controller, yaw heading from auto_heading()
165  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(),true);
166  }
167 
168  // check if we've completed this stage of RTL
170 }
171 
172 // rtl_loiterathome_start - initialise return to home
174 {
176  _state_complete = false;
178 
179  // yaw back to initial take-off heading yaw unless pilot has already overridden yaw
180  if(auto_yaw.default_mode(true) != AUTO_YAW_HOLD) {
182  } else {
184  }
185 }
186 
187 // rtl_climb_return_descent_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
188 // called by rtl_run at 100hz or more
190 {
191  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
192  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
194  // To-Do: re-initialise wpnav targets
195  return;
196  }
197 
198  // process pilot's yaw input
199  float target_yaw_rate = 0;
200  if (!copter.failsafe.radio) {
201  // get pilot's desired yaw rate
203  if (!is_zero(target_yaw_rate)) {
205  }
206  }
207 
208  // set motors to full range
209  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
210 
211  // run waypoint controller
212  copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
213 
214  // call z-axis position controller (wpnav should have already updated it's alt target)
216 
217  // call attitude controller
218  if (auto_yaw.mode() == AUTO_YAW_HOLD) {
219  // roll & pitch from waypoint controller, yaw rate from pilot
220  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), target_yaw_rate);
221  }else{
222  // roll, pitch from waypoint controller, yaw heading from auto_heading()
223  attitude_control->input_euler_angle_roll_pitch_yaw(wp_nav->get_roll(), wp_nav->get_pitch(), auto_yaw.yaw(),true);
224  }
225 
226  // check if we've completed this stage of RTL
227  if ((millis() - _loiter_start_time) >= (uint32_t)g.rtl_loiter_time.get()) {
229  // check if heading is within 2 degrees of heading when vehicle was armed
230  if (labs(wrap_180_cd(ahrs.yaw_sensor-copter.initial_armed_bearing)) <= 200) {
231  _state_complete = true;
232  }
233  } else {
234  // we have loitered long enough
235  _state_complete = true;
236  }
237  }
238 }
239 
240 // rtl_descent_start - initialise descent to final alt
242 {
244  _state_complete = false;
245 
246  // Set wp navigation target to above home
248 
249  // initialise altitude target to stopping point
251 
252  // initialise yaw
254 }
255 
256 // rtl_descent_run - implements the final descent to the RTL_ALT
257 // called by rtl_run at 100hz or more
259 {
260  float target_roll = 0.0f;
261  float target_pitch = 0.0f;
262  float target_yaw_rate = 0.0f;
263 
264  // if not auto armed or motor interlock not enabled set throttle to zero and exit immediately
265  if (!motors->armed() || !ap.auto_armed || !motors->get_interlock()) {
267  // set target to current position
269  return;
270  }
271 
272  // process pilot's input
273  if (!copter.failsafe.radio) {
274  if ((g.throttle_behavior & THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND) != 0 && copter.rc_throttle_control_in_filter.get() > LAND_CANCEL_TRIGGER_THR){
276  // exit land if throttle is high
279  }
280  }
281 
282  if (g.land_repositioning) {
283  // apply SIMPLE mode transform to pilot inputs
285 
286  // convert pilot input to lean angles
287  get_pilot_desired_lean_angles(target_roll, target_pitch, loiter_nav->get_angle_max_cd(), attitude_control->get_althold_lean_angle_max());
288 
289  // record if pilot has overriden roll or pitch
290  if (!is_zero(target_roll) || !is_zero(target_pitch)) {
291  ap.land_repo_active = true;
292  }
293  }
294 
295  // get pilot's desired yaw rate
297  }
298 
299  // set motors to full range
300  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
301 
302  // process roll, pitch inputs
303  loiter_nav->set_pilot_desired_acceleration(target_roll, target_pitch, G_Dt);
304 
305  // run loiter controller
307 
308  // call z-axis position controller
309  pos_control->set_alt_target_with_slew(rtl_path.descent_target.alt, G_Dt);
311 
312  // roll & pitch from waypoint controller, yaw rate from pilot
313  attitude_control->input_euler_angle_roll_pitch_euler_rate_yaw(loiter_nav->get_roll(), loiter_nav->get_pitch(), target_yaw_rate);
314 
315  // check if we've reached within 20cm of final altitude
316  _state_complete = labs(rtl_path.descent_target.alt - copter.current_loc.alt) < 20;
317 }
318 
319 // rtl_loiterathome_start - initialise controllers to loiter over home
321 {
322  _state = RTL_Land;
323  _state_complete = false;
324 
325  // Set wp navigation target to above home
327 
328  // initialise position and desired velocity
329  if (!pos_control->is_active_z()) {
332  }
333 
334  // initialise yaw
336 }
337 
339 {
340  switch(_state) {
341  case RTL_LoiterAtHome:
342  case RTL_Land:
343  case RTL_FinalDescent:
344  return true;
345  default:
346  return false;
347  }
348  return false;
349 }
350 
351 // rtl_returnhome_run - return home
352 // called by rtl_run at 100hz or more
353 void Copter::ModeRTL::land_run(bool disarm_on_land)
354 {
355  // if not auto armed or landing completed or motor interlock not enabled set throttle to zero and exit immediately
356  if (!motors->armed() || !ap.auto_armed || ap.land_complete || !motors->get_interlock()) {
358  // set target to current position
360 
361  // disarm when the landing detector says we've landed
362  if (ap.land_complete && disarm_on_land) {
363  copter.init_disarm_motors();
364  }
365 
366  // check if we've completed this stage of RTL
367  _state_complete = ap.land_complete;
368  return;
369  }
370 
371  // set motors to full range
372  motors->set_desired_spool_state(AP_Motors::DESIRED_THROTTLE_UNLIMITED);
373 
376 
377  // check if we've completed this stage of RTL
378  _state_complete = ap.land_complete;
379 }
380 
381 void Copter::ModeRTL::build_path(bool terrain_following_allowed)
382 {
383  // origin point is our stopping point
384  Vector3f stopping_point;
385  pos_control->get_stopping_point_xy(stopping_point);
386  pos_control->get_stopping_point_z(stopping_point);
387  rtl_path.origin_point = Location_Class(stopping_point);
388  rtl_path.origin_point.change_alt_frame(Location_Class::ALT_FRAME_ABOVE_HOME);
389 
390  // compute return target
391  compute_return_target(terrain_following_allowed);
392 
393  // climb target is above our origin point at the return altitude
394  rtl_path.climb_target = Location_Class(rtl_path.origin_point.lat, rtl_path.origin_point.lng, rtl_path.return_target.alt, rtl_path.return_target.get_alt_frame());
395 
396  // descent target is below return target at rtl_alt_final
397  rtl_path.descent_target = Location_Class(rtl_path.return_target.lat, rtl_path.return_target.lng, g.rtl_alt_final, Location_Class::ALT_FRAME_ABOVE_HOME);
398 
399  // set land flag
400  rtl_path.land = g.rtl_alt_final <= 0;
401 }
402 
403 // compute the return target - home or rally point
404 // return altitude in cm above home at which vehicle should return home
405 // return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
406 void Copter::ModeRTL::compute_return_target(bool terrain_following_allowed)
407 {
408  // set return target to nearest rally point or home position (Note: alt is absolute)
409 #if AC_RALLY == ENABLED
410  rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt);
411 #else
412  rtl_path.return_target = ahrs.get_home();
413 #endif
414 
415  // curr_alt is current altitude above home or above terrain depending upon use_terrain
416  int32_t curr_alt = copter.current_loc.alt;
417 
418  // decide if we should use terrain altitudes
419  rtl_path.terrain_used = copter.terrain_use() && terrain_following_allowed;
420  if (rtl_path.terrain_used) {
421  // attempt to retrieve terrain alt for current location, stopping point and origin
422  int32_t origin_terr_alt, return_target_terr_alt;
423  if (!rtl_path.origin_point.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, origin_terr_alt) ||
424  !rtl_path.return_target.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, return_target_terr_alt) ||
425  !copter.current_loc.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_TERRAIN, curr_alt)) {
426  rtl_path.terrain_used = false;
428  }
429  }
430 
431  // convert return-target alt (which is an absolute alt) to alt-above-home or alt-above-terrain
432  if (!rtl_path.terrain_used || !rtl_path.return_target.change_alt_frame(Location_Class::ALT_FRAME_ABOVE_TERRAIN)) {
433  if (!rtl_path.return_target.change_alt_frame(Location_Class::ALT_FRAME_ABOVE_HOME)) {
434  // this should never happen but just in case
435  rtl_path.return_target.set_alt_cm(0, Location_Class::ALT_FRAME_ABOVE_HOME);
436  }
437  rtl_path.terrain_used = false;
438  }
439 
440  // set new target altitude to return target altitude
441  // Note: this is alt-above-home or terrain-alt depending upon use_terrain
442  // Note: ignore negative altitudes which could happen if user enters negative altitude for rally point or terrain is higher at rally point compared to home
443  int32_t target_alt = MAX(rtl_path.return_target.alt, 0);
444 
445  // increase target to maximum of current altitude + climb_min and rtl altitude
446  target_alt = MAX(target_alt, curr_alt + MAX(0, g.rtl_climb_min));
447  target_alt = MAX(target_alt, MAX(g.rtl_altitude, RTL_ALT_MIN));
448 
449  // reduce climb if close to return target
450  float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f;
451  // don't allow really shallow slopes
453  target_alt = MAX(curr_alt, MIN(target_alt, MAX(rtl_return_dist_cm*g.rtl_cone_slope, curr_alt+RTL_ABS_MIN_CLIMB)));
454  }
455 
456  // set returned target alt to new target_alt
457  rtl_path.return_target.set_alt_cm(target_alt, rtl_path.terrain_used ? Location_Class::ALT_FRAME_ABOVE_TERRAIN : Location_Class::ALT_FRAME_ABOVE_HOME);
458 
459 #if AC_FENCE == ENABLED
460  // ensure not above fence altitude if alt fence is enabled
461  // Note: because the rtl_path.climb_target's altitude is simply copied from the return_target's altitude,
462  // if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to
463  // the vehicle not climbing at all as RTL begins. This can be overly conservative and it might be better
464  // to apply the fence alt limit independently on the origin_point and return_target
465  if ((copter.fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
466  // get return target as alt-above-home so it can be compared to fence's alt
467  if (rtl_path.return_target.get_alt_cm(Location_Class::ALT_FRAME_ABOVE_HOME, target_alt)) {
468  float fence_alt = copter.fence.get_safe_alt_max()*100.0f;
469  if (target_alt > fence_alt) {
470  // reduce target alt to the fence alt
471  rtl_path.return_target.alt -= (target_alt - fence_alt);
472  }
473  }
474  }
475 #endif
476 
477  // ensure we do not descend
478  rtl_path.return_target.alt = MAX(rtl_path.return_target.alt, curr_alt);
479 }
480 
482 {
484 }
485 
487 {
489 }
void set_speed_xy(float speed_cms)
void get_stopping_point_xy(Vector3f &stopping_point) const
void zero_throttle_and_relax_ac()
Definition: mode.cpp:373
virtual float get_velocity_z() const=0
bool reached_wp_destination() const
void land_run(bool disarm_on_land)
Definition: mode_rtl.cpp:353
void set_mode_to_default(bool rtl)
Definition: autoyaw.cpp:28
void set_alt_target_with_slew(float alt_cm, float dt)
void land_start()
Definition: mode_rtl.cpp:320
int32_t get_pitch() const
AP_Int16 rtl_climb_min
Definition: Parameters.h:404
AP_Int16 throttle_behavior
Definition: Parameters.h:387
AP_Float rtl_cone_slope
Definition: Parameters.h:393
void get_stopping_point_z(Vector3f &stopping_point) const
void update_z_controller()
const struct Location & get_home(void) const
GCS_Copter & gcs()
Definition: mode.cpp:587
void Log_Write_Event(uint8_t id)
Definition: mode.cpp:592
void loiterathome_run()
Definition: mode_rtl.cpp:189
void update_simple_mode(void)
Definition: mode.cpp:573
autopilot_yaw_mode default_mode(bool rtl) const
Definition: autoyaw.cpp:35
Definition: defines.h:100
AC_AttitudeControl_t *& attitude_control
Definition: Copter.h:123
void init_target(const Vector3f &position)
auto wrap_180_cd(const T angle) -> decltype(wrap_180(angle, 100.f))
void descent_run()
Definition: mode_rtl.cpp:258
float get_pilot_desired_yaw_rate(int16_t stick_angle)
Definition: mode.cpp:553
int32_t get_roll() const
void return_start()
Definition: mode_rtl.cpp:115
struct Copter::ModeRTL::@9 rtl_path
AP_Int8 land_repositioning
Definition: Parameters.h:452
void land_run_horizontal_control()
Definition: mode.cpp:449
bool set_wp_destination(const Location_Class &destination)
#define MIN(a, b)
autopilot_yaw_mode mode() const
Definition: Copter.h:26
void land_run_vertical_control(bool pause_descent=false)
Definition: mode.cpp:403
int32_t get_wp_bearing_to_destination() const
void build_path(bool terrain_following_allowed)
Definition: mode_rtl.cpp:381
bool _state_complete
Definition: Copter.h:981
AP_Int16 rtl_alt_final
Definition: Parameters.h:403
bool landing_gear_should_be_deployed() const override
Definition: mode_rtl.cpp:338
bool update_wpnav()
#define THR_BEHAVE_HIGH_THROTTLE_CANCELS_LAND
Definition: defines.h:484
void set_mode(autopilot_yaw_mode new_mode)
Definition: autoyaw.cpp:59
#define RTL_ABS_MIN_CLIMB
Definition: config.h:508
bool is_active_z() const
void update(float ekfGndSpdLimit, float ekfNavVelGainScaler)
int16_t get_control_in() const
#define ERROR_CODE_FAILED_TO_SET_DESTINATION
Definition: defines.h:438
const Vector3f & get_wp_destination() const
int32_t alt
#define RTL_ALT_MIN
Definition: config.h:500
bool is_zero(const T fVal1)
void set_desired_velocity_z(float vel_z_cms)
void set_fast_waypoint(bool fast)
void loiterathome_start()
Definition: mode_rtl.cpp:173
float get_wp_distance_to_destination() const
uint32_t millis()
AC_WPNav *& wp_nav
Definition: Copter.h:118
#define ERROR_CODE_MISSING_TERRAIN_DATA
Definition: defines.h:436
void climb_start()
Definition: mode_rtl.cpp:91
void wp_and_spline_init()
#define RTL_MIN_CONE_SLOPE
Definition: config.h:516
Definition: defines.h:97
#define DATA_LAND_CANCELLED_BY_PILOT
Definition: defines.h:381
void send_text(MAV_SEVERITY severity, const char *fmt,...)
void get_pilot_desired_lean_angles(float &roll_out, float &pitch_out, float angle_max, float angle_limit) const
Definition: mode.cpp:326
DESIRED_THROTTLE_UNLIMITED
void run() override
Definition: Copter.h:935
AC_PosControl *& pos_control
Definition: Copter.h:120
AP_Int16 rtl_altitude
Definition: Parameters.h:391
bool init(bool ignore_checks) override
Definition: mode_rtl.cpp:11
MOTOR_CLASS *& motors
Definition: Copter.h:124
void compute_return_target(bool terrain_following_allowed)
Definition: mode_rtl.cpp:406
AP_HAL_MAIN_CALLBACKS & copter
Definition: ArduCopter.cpp:581
float & G_Dt
Definition: Copter.h:129
#define ERROR_CODE_RESTARTED_RTL
Definition: defines.h:439
uint32_t _loiter_start_time
Definition: Copter.h:994
#define LAND_CANCEL_TRIGGER_THR
Definition: config.h:416
#define ERROR_SUBSYSTEM_TERRAIN
Definition: defines.h:413
void set_pilot_desired_acceleration(float euler_roll_angle_cd, float euler_pitch_angle_cd, float dt)
int32_t wp_bearing() const override
Definition: mode_rtl.cpp:486
float & ekfNavVelGainScaler
Definition: Copter.h:137
void set_target_to_stopping_point_z()
AP_InertialNav & inertial_nav
Definition: Copter.h:121
void climb_return_run()
Definition: mode_rtl.cpp:131
AP_Int16 rtl_speed_cms
Definition: Parameters.h:392
AP_AHRS & ahrs
Definition: Copter.h:122
static AutoYaw auto_yaw
Definition: Copter.h:73
RC_Channel *& channel_yaw
Definition: Copter.h:128
uint32_t wp_distance() const override
Definition: mode_rtl.cpp:481
AP_Int32 rtl_loiter_time
Definition: Parameters.h:413
int32_t yaw_sensor
int32_t get_pitch() const
Parameters & g
Definition: Copter.h:116
int32_t get_roll() const
float & ekfGndSpdLimit
Definition: Copter.h:134
#define ERROR_SUBSYSTEM_NAVIGATION
Definition: defines.h:414
#define AC_FENCE_TYPE_ALT_MAX
void descent_start()
Definition: mode_rtl.cpp:241
RTLState _state
Definition: Copter.h:980
void restart_without_terrain()
Definition: mode_rtl.cpp:25
AC_Loiter *& loiter_nav
Definition: Copter.h:119
void set_alt_target_to_current_alt()
float get_angle_max_cd() const