Skip to content

Commit

Permalink
Plane: Support added for DO_LAND_START FS fix
Browse files Browse the repository at this point in the history
  • Loading branch information
MattKear committed Feb 4, 2020
1 parent 560c757 commit f40386d
Showing 1 changed file with 5 additions and 1 deletion.
6 changes: 5 additions & 1 deletion ArduPlane/events.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -162,7 +162,7 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
}
FALLTHROUGH;
case Failsafe_Action_Land:
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland) {
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland && !plane.mission.is_best_land_sequence()) {
// never stop a landing if we were already committed
if (plane.mission.jump_to_landing_sequence()) {
plane.set_mode(mode_auto, ModeReason::BATTERY_FAILSAFE);
Expand All @@ -172,6 +172,10 @@ void Plane::handle_battery_failsafe(const char *type_str, const int8_t action)
FALLTHROUGH;
case Failsafe_Action_RTL:
if (flight_stage != AP_Vehicle::FixedWing::FLIGHT_LAND && control_mode != &mode_qland && !quadplane.in_vtol_land_sequence()) {
if (g.rtl_autoland == 2 && plane.mission.is_best_land_sequence()) {
// continue mission reaches a land in less distance
break;
}
// never stop a landing if we were already committed
set_mode(mode_rtl, ModeReason::BATTERY_FAILSAFE);
aparm.throttle_cruise.load();
Expand Down

0 comments on commit f40386d

Please sign in to comment.