mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
Plane:reset in landing seq on mode change while disarmed
This commit is contained in:
parent
a98def0b6d
commit
410fbb998b
@ -125,6 +125,13 @@ bool Mode::enter()
|
||||
// but it should be harmless to disable the fence temporarily in these situations as well
|
||||
plane.fence.manual_recovery_start();
|
||||
#endif
|
||||
//reset mission if in landing sequence, disarmed, not flying, and have changed to a non-autothrottle mode to clear prearm
|
||||
if (plane.mission.get_in_landing_sequence_flag() &&
|
||||
!plane.is_flying() && !plane.arming.is_armed_and_safety_off() &&
|
||||
!plane.control_mode->does_auto_navigation()) {
|
||||
GCS_SEND_TEXT(MAV_SEVERITY_INFO, "In landing sequence: mission reset");
|
||||
plane.mission.reset();
|
||||
}
|
||||
}
|
||||
|
||||
return enter_result;
|
||||
|
Loading…
Reference in New Issue
Block a user