Copter: allow forcing disarm via mavlink using magic number

Based on change by Jon Challinger but using new is_equal function
This commit is contained in:
Randy Mackay 2015-05-22 16:46:16 +09:00
parent 4486ddc53e
commit 15fe925974

View File

@ -1223,7 +1223,7 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg)
if (init_arm_motors(true)) {
result = MAV_RESULT_ACCEPTED;
}
} else if (is_zero(packet.param1) && (mode_has_manual_throttle(control_mode) || ap.land_complete)) {
} else if (is_zero(packet.param1) && (mode_has_manual_throttle(control_mode) || ap.land_complete || is_equal(packet.param2,21196.0f))) {
init_disarm_motors();
result = MAV_RESULT_ACCEPTED;
} else {