mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 16:48:29 -04:00
Plane: only reset mission on disarm if not in AUTO mode
disarming while in a mission should leave the plane still flying the mission, but with motor stopped. The user may do this during a landing for example, but we want to keep gliding
This commit is contained in:
parent
a172d898c5
commit
2ae412d513
@ -1094,8 +1094,14 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||
if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) {
|
||||
channel_throttle->disable_out();
|
||||
}
|
||||
// reset the mission on disarm
|
||||
mission.stop();
|
||||
if (control_mode != AUTO) {
|
||||
// reset the mission on disarm if we are not in auto
|
||||
mission.reset();
|
||||
}
|
||||
|
||||
// suppress the throttle in auto-throttle modes
|
||||
throttle_suppressed = auto_throttle_mode;
|
||||
|
||||
//only log if disarming was successful
|
||||
Log_Arm_Disarm();
|
||||
result = MAV_RESULT_ACCEPTED;
|
||||
|
Loading…
Reference in New Issue
Block a user