mirror of https://github.com/ArduPilot/ardupilot
Plane: reset mission on disarm
this makes repeated missions easier
This commit is contained in:
parent
89366a1ee1
commit
43a56151d7
|
@ -1267,10 +1267,12 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
|
||||||
}
|
}
|
||||||
} else if (packet.param1 == 0.0f) {
|
} else if (packet.param1 == 0.0f) {
|
||||||
if (arming.disarm()) {
|
if (arming.disarm()) {
|
||||||
//only log if disarming was successful
|
|
||||||
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
|
if (arming.arming_required() != AP_Arming::YES_ZERO_PWM) {
|
||||||
channel_throttle->disable_out();
|
channel_throttle->disable_out();
|
||||||
}
|
}
|
||||||
|
// reset the mission on disarm
|
||||||
|
change_command(0);
|
||||||
|
//only log if disarming was successful
|
||||||
Log_Arm_Disarm();
|
Log_Arm_Disarm();
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
} else {
|
} else {
|
||||||
|
|
Loading…
Reference in New Issue