mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-23 16:23:56 -04:00
Copter: return appropriate response to failed disarm
This commit is contained in:
parent
6e2076a3f1
commit
4d6408857f
@ -964,10 +964,14 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
if (copter.init_arm_motors(true)) {
|
if (copter.init_arm_motors(true)) {
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
}
|
}
|
||||||
} else if (is_zero(packet.param1) && (copter.ap.land_complete || is_equal(packet.param2,21196.0f))) {
|
} else if (is_zero(packet.param1)) {
|
||||||
// force disarming by setting param2 = 21196 is deprecated
|
if (copter.ap.land_complete || is_equal(packet.param2,21196.0f)) {
|
||||||
copter.init_disarm_motors();
|
// force disarming by setting param2 = 21196 is deprecated
|
||||||
result = MAV_RESULT_ACCEPTED;
|
copter.init_disarm_motors();
|
||||||
|
result = MAV_RESULT_ACCEPTED;
|
||||||
|
} else {
|
||||||
|
result = MAV_RESULT_FAILED;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
result = MAV_RESULT_UNSUPPORTED;
|
result = MAV_RESULT_UNSUPPORTED;
|
||||||
}
|
}
|
||||||
|
Loading…
Reference in New Issue
Block a user