Plane: use magic force arm/disarm definitions

This commit is contained in:
Peter Barker 2017-06-07 11:38:40 +10:00
parent ca8a1ae488
commit f984e5e31d
1 changed files with 1 additions and 1 deletions

View File

@ -975,7 +975,7 @@ void GCS_MAVLINK_Plane::handleMessage(mavlink_message_t* msg)
case MAV_CMD_COMPONENT_ARM_DISARM:
if (is_equal(packet.param1,1.0f)) {
// run pre_arm_checks and arm_checks and display failures
const bool do_arming_checks = !is_equal(packet.param2,2989.0f);
const bool do_arming_checks = !is_equal(packet.param2,magic_force_arm_value);
if (plane.arm_motors(AP_Arming::MAVLINK, do_arming_checks)) {
result = MAV_RESULT_ACCEPTED;
} else {