AP_Scripting: ahrs/ekf origin script promoted to an applet
[ardupilot.git] / ArduCopter / mode_rtl.cpp
blob8d7bba2dd332aebe7fefef9d88a9ab8f539896dc
1 #include "Copter.h"
3 #if MODE_RTL_ENABLED
5 /*
6 * Init and run calls for RTL flight mode
8 * There are two parts to RTL, the high level decision making which controls which state we are in
9 * and the lower implementation of the waypoint or landing controllers within those states
12 // rtl_init - initialise rtl controller
13 bool ModeRTL::init(bool ignore_checks)
15 if (!ignore_checks) {
16 if (!AP::ahrs().home_is_set()) {
17 return false;
20 // initialise waypoint and spline controller
21 wp_nav->wp_and_spline_init(g.rtl_speed_cms);
22 _state = SubMode::STARTING;
23 _state_complete = true; // see run() method below
24 terrain_following_allowed = !copter.failsafe.terrain;
25 // reset flag indicating if pilot has applied roll or pitch inputs during landing
26 copter.ap.land_repo_active = false;
28 // this will be set true if prec land is later active
29 copter.ap.prec_land_active = false;
31 #if AC_PRECLAND_ENABLED
32 // initialise precland state machine
33 copter.precland_statemachine.init();
34 #endif
36 return true;
39 // re-start RTL with terrain following disabled
40 void ModeRTL::restart_without_terrain()
42 #if HAL_LOGGING_ENABLED
43 LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RESTARTED_RTL);
44 #endif
45 terrain_following_allowed = false;
46 _state = SubMode::STARTING;
47 _state_complete = true;
48 gcs().send_text(MAV_SEVERITY_CRITICAL,"Restarting RTL - Terrain data missing");
51 ModeRTL::RTLAltType ModeRTL::get_alt_type() const
53 // sanity check parameter
54 switch ((ModeRTL::RTLAltType)g.rtl_alt_type) {
55 case RTLAltType::RELATIVE ... RTLAltType::TERRAIN:
56 return g.rtl_alt_type;
58 // user has an invalid value
59 return RTLAltType::RELATIVE;
62 // rtl_run - runs the return-to-launch controller
63 // should be called at 100hz or more
64 void ModeRTL::run(bool disarm_on_land)
66 if (!motors->armed()) {
67 return;
70 // check if we need to move to next state
71 if (_state_complete) {
72 switch (_state) {
73 case SubMode::STARTING:
74 build_path();
75 climb_start();
76 break;
77 case SubMode::INITIAL_CLIMB:
78 return_start();
79 break;
80 case SubMode::RETURN_HOME:
81 loiterathome_start();
82 break;
83 case SubMode::LOITER_AT_HOME:
84 if (rtl_path.land || copter.failsafe.radio) {
85 land_start();
86 } else {
87 descent_start();
89 break;
90 case SubMode::FINAL_DESCENT:
91 // do nothing
92 break;
93 case SubMode::LAND:
94 // do nothing - rtl_land_run will take care of disarming motors
95 break;
99 // call the correct run function
100 switch (_state) {
102 case SubMode::STARTING:
103 // should not be reached:
104 _state = SubMode::INITIAL_CLIMB;
105 FALLTHROUGH;
107 case SubMode::INITIAL_CLIMB:
108 climb_return_run();
109 break;
111 case SubMode::RETURN_HOME:
112 climb_return_run();
113 break;
115 case SubMode::LOITER_AT_HOME:
116 loiterathome_run();
117 break;
119 case SubMode::FINAL_DESCENT:
120 descent_run();
121 break;
123 case SubMode::LAND:
124 land_run(disarm_on_land);
125 break;
129 // rtl_climb_start - initialise climb to RTL altitude
130 void ModeRTL::climb_start()
132 _state = SubMode::INITIAL_CLIMB;
133 _state_complete = false;
135 // set the destination
136 if (!wp_nav->set_wp_destination_loc(rtl_path.climb_target) || !wp_nav->set_wp_destination_next_loc(rtl_path.return_target)) {
137 // this should not happen because rtl_build_path will have checked terrain data was available
138 gcs().send_text(MAV_SEVERITY_CRITICAL,"RTL: unexpected error setting climb target");
139 LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::FAILED_TO_SET_DESTINATION);
140 copter.set_mode(Mode::Number::LAND, ModeReason::TERRAIN_FAILSAFE);
141 return;
144 // hold current yaw during initial climb
145 auto_yaw.set_mode(AutoYaw::Mode::HOLD);
148 // rtl_return_start - initialise return to home
149 void ModeRTL::return_start()
151 _state = SubMode::RETURN_HOME;
152 _state_complete = false;
154 if (!wp_nav->set_wp_destination_loc(rtl_path.return_target)) {
155 // failure must be caused by missing terrain data, restart RTL
156 restart_without_terrain();
159 // initialise yaw to point home (maybe)
160 auto_yaw.set_mode_to_default(true);
163 // rtl_climb_return_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
164 // called by rtl_run at 100hz or more
165 void ModeRTL::climb_return_run()
167 // if not armed set throttle to zero and exit immediately
168 if (is_disarmed_or_landed()) {
169 make_safe_ground_handling();
170 return;
173 // set motors to full range
174 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
176 // run waypoint controller
177 copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
179 // WP_Nav has set the vertical position control targets
180 // run the vertical position controller and set output throttle
181 pos_control->update_z_controller();
183 // call attitude controller with auto yaw
184 attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
186 // check if we've completed this stage of RTL
187 _state_complete = wp_nav->reached_wp_destination();
190 // loiterathome_start - initialise return to home
191 void ModeRTL::loiterathome_start()
193 _state = SubMode::LOITER_AT_HOME;
194 _state_complete = false;
195 _loiter_start_time = millis();
197 // yaw back to initial take-off heading yaw unless pilot has already overridden yaw
198 if (auto_yaw.default_mode(true) != AutoYaw::Mode::HOLD) {
199 auto_yaw.set_mode(AutoYaw::Mode::RESETTOARMEDYAW);
200 } else {
201 auto_yaw.set_mode(AutoYaw::Mode::HOLD);
205 // rtl_climb_return_descent_run - implements the initial climb, return home and descent portions of RTL which all rely on the wp controller
206 // called by rtl_run at 100hz or more
207 void ModeRTL::loiterathome_run()
209 // if not armed set throttle to zero and exit immediately
210 if (is_disarmed_or_landed()) {
211 make_safe_ground_handling();
212 return;
215 // set motors to full range
216 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
218 // run waypoint controller
219 copter.failsafe_terrain_set_status(wp_nav->update_wpnav());
221 // WP_Nav has set the vertical position control targets
222 // run the vertical position controller and set output throttle
223 pos_control->update_z_controller();
225 // call attitude controller with auto yaw
226 attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
228 // check if we've completed this stage of RTL
229 if ((millis() - _loiter_start_time) >= (uint32_t)g.rtl_loiter_time.get()) {
230 if (auto_yaw.mode() == AutoYaw::Mode::RESETTOARMEDYAW) {
231 // check if heading is within 2 degrees of heading when vehicle was armed
232 if (abs(wrap_180_cd(ahrs.yaw_sensor-copter.initial_armed_bearing)) <= 200) {
233 _state_complete = true;
235 } else {
236 // we have loitered long enough
237 _state_complete = true;
242 // rtl_descent_start - initialise descent to final alt
243 void ModeRTL::descent_start()
245 _state = SubMode::FINAL_DESCENT;
246 _state_complete = false;
248 // initialise altitude target to stopping point
249 pos_control->init_z_controller_stopping_point();
251 // initialise yaw
252 auto_yaw.set_mode(AutoYaw::Mode::HOLD);
254 #if AP_LANDINGGEAR_ENABLED
255 // optionally deploy landing gear
256 copter.landinggear.deploy_for_landing();
257 #endif
260 // rtl_descent_run - implements the final descent to the RTL_ALT
261 // called by rtl_run at 100hz or more
262 void ModeRTL::descent_run()
264 Vector2f vel_correction;
266 // if not armed set throttle to zero and exit immediately
267 if (is_disarmed_or_landed()) {
268 make_safe_ground_handling();
269 return;
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){
275 LOGGER_WRITE_EVENT(LogEvent::LAND_CANCELLED_BY_PILOT);
276 // exit land if throttle is high
277 if (!copter.set_mode(Mode::Number::LOITER, ModeReason::THROTTLE_LAND_ESCAPE)) {
278 copter.set_mode(Mode::Number::ALT_HOLD, ModeReason::THROTTLE_LAND_ESCAPE);
282 if (g.land_repositioning) {
283 // apply SIMPLE mode transform to pilot inputs
284 update_simple_mode();
286 // convert pilot input to reposition velocity
287 vel_correction = get_pilot_desired_velocity(wp_nav->get_wp_acceleration() * 0.5);
289 // record if pilot has overridden roll or pitch
290 if (!vel_correction.is_zero()) {
291 if (!copter.ap.land_repo_active) {
292 LOGGER_WRITE_EVENT(LogEvent::LAND_REPO_ACTIVE);
294 copter.ap.land_repo_active = true;
299 // set motors to full range
300 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
302 Vector2f accel;
303 pos_control->input_vel_accel_xy(vel_correction, accel);
304 pos_control->update_xy_controller();
306 // WP_Nav has set the vertical position control targets
307 // run the vertical position controller and set output throttle
308 pos_control->set_alt_target_with_slew(rtl_path.descent_target.alt);
309 pos_control->update_z_controller();
311 // roll & pitch from waypoint controller, yaw rate from pilot
312 attitude_control->input_thrust_vector_heading(pos_control->get_thrust_vector(), auto_yaw.get_heading());
314 // check if we've reached within 20cm of final altitude
315 _state_complete = labs(rtl_path.descent_target.alt - copter.current_loc.alt) < 20;
318 // land_start - initialise controllers to loiter over home
319 void ModeRTL::land_start()
321 _state = SubMode::LAND;
322 _state_complete = false;
324 // set horizontal speed and acceleration limits
325 pos_control->set_max_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
326 pos_control->set_correction_speed_accel_xy(wp_nav->get_default_speed_xy(), wp_nav->get_wp_acceleration());
328 // initialise loiter target destination
329 if (!pos_control->is_active_xy()) {
330 pos_control->init_xy_controller();
333 // initialise the vertical position controller
334 if (!pos_control->is_active_z()) {
335 pos_control->init_z_controller();
338 // initialise yaw
339 auto_yaw.set_mode(AutoYaw::Mode::HOLD);
341 #if AP_LANDINGGEAR_ENABLED
342 // optionally deploy landing gear
343 copter.landinggear.deploy_for_landing();
344 #endif
347 bool ModeRTL::is_landing() const
349 return _state == SubMode::LAND;
352 // land_run - run the landing controllers to put the aircraft on the ground
353 // called by rtl_run at 100hz or more
354 void ModeRTL::land_run(bool disarm_on_land)
356 // check if we've completed this stage of RTL
357 _state_complete = copter.ap.land_complete;
359 // disarm when the landing detector says we've landed
360 if (disarm_on_land && copter.ap.land_complete && motors->get_spool_state() == AP_Motors::SpoolState::GROUND_IDLE) {
361 copter.arming.disarm(AP_Arming::Method::LANDED);
364 // if not armed set throttle to zero and exit immediately
365 if (is_disarmed_or_landed()) {
366 make_safe_ground_handling();
367 return;
370 // set motors to full range
371 motors->set_desired_spool_state(AP_Motors::DesiredSpoolState::THROTTLE_UNLIMITED);
373 // run normal landing or precision landing (if enabled)
374 land_run_normal_or_precland();
377 void ModeRTL::build_path()
379 // origin point is our stopping point
380 rtl_path.origin_point = get_stopping_point();
381 rtl_path.origin_point.change_alt_frame(Location::AltFrame::ABOVE_HOME);
383 // compute return target
384 compute_return_target();
386 // climb target is above our origin point at the return altitude
387 rtl_path.climb_target = Location(rtl_path.origin_point.lat, rtl_path.origin_point.lng, rtl_path.return_target.alt, rtl_path.return_target.get_alt_frame());
389 // descent target is below return target at rtl_alt_final
390 rtl_path.descent_target = Location(rtl_path.return_target.lat, rtl_path.return_target.lng, g.rtl_alt_final, Location::AltFrame::ABOVE_HOME);
392 // set land flag
393 rtl_path.land = g.rtl_alt_final <= 0;
396 // compute the return target - home or rally point
397 // return target's altitude is updated to a higher altitude that the vehicle can safely return at (frame may also be set)
398 void ModeRTL::compute_return_target()
400 // set return target to nearest rally point or home position
401 #if HAL_RALLY_ENABLED
402 rtl_path.return_target = copter.rally.calc_best_rally_or_home_location(copter.current_loc, ahrs.get_home().alt);
403 rtl_path.return_target.change_alt_frame(Location::AltFrame::ABSOLUTE);
404 #else
405 rtl_path.return_target = ahrs.get_home();
406 #endif
408 // get position controller Z-axis offset in cm above EKF origin
409 int32_t pos_offset_z = pos_control->get_pos_offset_z_cm();
411 // curr_alt is current altitude above home or above terrain depending upon use_terrain
412 int32_t curr_alt = copter.current_loc.alt - pos_offset_z;
414 // determine altitude type of return journey (alt-above-home, alt-above-terrain using range finder or alt-above-terrain using terrain database)
415 ReturnTargetAltType alt_type = ReturnTargetAltType::RELATIVE;
416 if (terrain_following_allowed && (get_alt_type() == RTLAltType::TERRAIN)) {
417 // convert RTL_ALT_TYPE and WPNAV_RFNG_USE parameters to ReturnTargetAltType
418 switch (wp_nav->get_terrain_source()) {
419 case AC_WPNav::TerrainSource::TERRAIN_UNAVAILABLE:
420 alt_type = ReturnTargetAltType::RELATIVE;
421 LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND);
422 gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home");
423 break;
424 case AC_WPNav::TerrainSource::TERRAIN_FROM_RANGEFINDER:
425 alt_type = ReturnTargetAltType::RANGEFINDER;
426 break;
427 case AC_WPNav::TerrainSource::TERRAIN_FROM_TERRAINDATABASE:
428 alt_type = ReturnTargetAltType::TERRAINDATABASE;
429 break;
433 // set curr_alt and return_target.alt from range finder
434 if (alt_type == ReturnTargetAltType::RANGEFINDER) {
435 if (copter.get_rangefinder_height_interpolated_cm(curr_alt)) {
436 // subtract position controller offset
437 curr_alt -= pos_offset_z;
438 // set return_target.alt
439 rtl_path.return_target.set_alt_cm(MAX(curr_alt + MAX(0, g.rtl_climb_min), MAX(g.rtl_altitude, RTL_ALT_MIN)), Location::AltFrame::ABOVE_TERRAIN);
440 } else {
441 // fallback to relative alt and warn user
442 alt_type = ReturnTargetAltType::RELATIVE;
443 gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: rangefinder unhealthy, using alt-above-home");
444 LOGGER_WRITE_ERROR(LogErrorSubsystem::NAVIGATION, LogErrorCode::RTL_MISSING_RNGFND);
448 // set curr_alt and return_target.alt from terrain database
449 if (alt_type == ReturnTargetAltType::TERRAINDATABASE) {
450 // set curr_alt to current altitude above terrain
451 // convert return_target.alt from an abs (above MSL) to altitude above terrain
452 // Note: the return_target may be a rally point with the alt set above the terrain alt (like the top of a building)
453 int32_t curr_terr_alt;
454 if (copter.current_loc.get_alt_cm(Location::AltFrame::ABOVE_TERRAIN, curr_terr_alt) &&
455 rtl_path.return_target.change_alt_frame(Location::AltFrame::ABOVE_TERRAIN)) {
456 curr_alt = curr_terr_alt - pos_offset_z;
457 } else {
458 // fallback to relative alt and warn user
459 alt_type = ReturnTargetAltType::RELATIVE;
460 LOGGER_WRITE_ERROR(LogErrorSubsystem::TERRAIN, LogErrorCode::MISSING_TERRAIN_DATA);
461 gcs().send_text(MAV_SEVERITY_CRITICAL, "RTL: no terrain data, using alt-above-home");
465 // for the default case we must convert return-target alt (which is an absolute alt) to alt-above-home
466 if (alt_type == ReturnTargetAltType::RELATIVE) {
467 if (!rtl_path.return_target.change_alt_frame(Location::AltFrame::ABOVE_HOME)) {
468 // this should never happen but just in case
469 rtl_path.return_target.set_alt_cm(0, Location::AltFrame::ABOVE_HOME);
470 gcs().send_text(MAV_SEVERITY_WARNING, "RTL: unexpected error calculating target alt");
474 // set new target altitude to return target altitude
475 // Note: this is alt-above-home or terrain-alt depending upon rtl_alt_type
476 // 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
477 int32_t target_alt = MAX(rtl_path.return_target.alt, 0);
479 // increase target to maximum of current altitude + climb_min and rtl altitude
480 const float min_rtl_alt = MAX(RTL_ALT_MIN, curr_alt + MAX(0, g.rtl_climb_min));
481 target_alt = MAX(target_alt, MAX(g.rtl_altitude, min_rtl_alt));
483 // reduce climb if close to return target
484 float rtl_return_dist_cm = rtl_path.return_target.get_distance(rtl_path.origin_point) * 100.0f;
485 // don't allow really shallow slopes
486 if (g.rtl_cone_slope >= RTL_MIN_CONE_SLOPE) {
487 target_alt = MIN(target_alt, MAX(rtl_return_dist_cm * g.rtl_cone_slope, min_rtl_alt));
490 // set returned target alt to new target_alt (don't change altitude type)
491 rtl_path.return_target.set_alt_cm(target_alt, (alt_type == ReturnTargetAltType::RELATIVE) ? Location::AltFrame::ABOVE_HOME : Location::AltFrame::ABOVE_TERRAIN);
493 #if AP_FENCE_ENABLED
494 // ensure not above fence altitude if alt fence is enabled
495 // Note: because the rtl_path.climb_target's altitude is simply copied from the return_target's altitude,
496 // if terrain altitudes are being used, the code below which reduces the return_target's altitude can lead to
497 // the vehicle not climbing at all as RTL begins. This can be overly conservative and it might be better
498 // to apply the fence alt limit independently on the origin_point and return_target
499 if ((copter.fence.get_enabled_fences() & AC_FENCE_TYPE_ALT_MAX) != 0) {
500 // get return target as alt-above-home so it can be compared to fence's alt
501 if (rtl_path.return_target.get_alt_cm(Location::AltFrame::ABOVE_HOME, target_alt)) {
502 float fence_alt = copter.fence.get_safe_alt_max()*100.0f;
503 if (target_alt > fence_alt) {
504 // reduce target alt to the fence alt
505 rtl_path.return_target.alt -= (target_alt - fence_alt);
509 #endif
511 // ensure we do not descend
512 rtl_path.return_target.alt = MAX(rtl_path.return_target.alt, curr_alt);
515 bool ModeRTL::get_wp(Location& destination) const
517 // provide target in states which use wp_nav
518 switch (_state) {
519 case SubMode::STARTING:
520 case SubMode::INITIAL_CLIMB:
521 case SubMode::RETURN_HOME:
522 case SubMode::LOITER_AT_HOME:
523 case SubMode::FINAL_DESCENT:
524 return wp_nav->get_oa_wp_destination(destination);
525 case SubMode::LAND:
526 return false;
529 // we should never get here but just in case
530 return false;
533 uint32_t ModeRTL::wp_distance() const
535 return wp_nav->get_wp_distance_to_destination();
538 int32_t ModeRTL::wp_bearing() const
540 return wp_nav->get_wp_bearing_to_destination();
543 // returns true if pilot's yaw input should be used to adjust vehicle's heading
544 bool ModeRTL::use_pilot_yaw(void) const
546 const bool allow_yaw_option = (copter.g2.rtl_options.get() & uint32_t(Options::IgnorePilotYaw)) == 0;
547 const bool land_repositioning = g.land_repositioning && (_state == SubMode::FINAL_DESCENT);
548 const bool final_landing = _state == SubMode::LAND;
549 return allow_yaw_option || land_repositioning || final_landing;
552 bool ModeRTL::set_speed_xy(float speed_xy_cms)
554 copter.wp_nav->set_speed_xy(speed_xy_cms);
555 return true;
558 bool ModeRTL::set_speed_up(float speed_up_cms)
560 copter.wp_nav->set_speed_up(speed_up_cms);
561 return true;
564 bool ModeRTL::set_speed_down(float speed_down_cms)
566 copter.wp_nav->set_speed_down(speed_down_cms);
567 return true;
570 #endif