From 4257d8365c86d6ea0455e705ac3f7b69ebcb3c26 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 20 Mar 2014 09:06:48 +1100 Subject: [PATCH] Plane: removed check on target_component in ARM/DISARM Thanks to DonLakeFlyer for finding this, see https://github.com/diydrones/ardupilot/pull/909 --- ArduPlane/GCS_Mavlink.pde | 46 ++++++++++++++++++--------------------- 1 file changed, 21 insertions(+), 25 deletions(-) diff --git a/ArduPlane/GCS_Mavlink.pde b/ArduPlane/GCS_Mavlink.pde index 3f65815603..cc9c08eec7 100644 --- a/ArduPlane/GCS_Mavlink.pde +++ b/ArduPlane/GCS_Mavlink.pde @@ -1160,32 +1160,28 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) break; case MAV_CMD_COMPONENT_ARM_DISARM: - if (packet.target_component == MAV_COMP_ID_SYSTEM_CONTROL) { - if (packet.param1 == 1.0f) { - // run pre_arm_checks and arm_checks and display failures - if (arming.arm(AP_Arming::MAVLINK)) { - //only log if arming was successful - channel_throttle->enable_out(); - Log_Arm_Disarm(); - result = MAV_RESULT_ACCEPTED; - } else { - result = MAV_RESULT_FAILED; - } - } else if (packet.param1 == 0.0f) { - if (arming.disarm()) { - if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) { - channel_throttle->disable_out(); - } - // reset the mission on disarm - mission.stop(); - //only log if disarming was successful - Log_Arm_Disarm(); - result = MAV_RESULT_ACCEPTED; - } else { - result = MAV_RESULT_FAILED; - } + if (packet.param1 == 1.0f) { + // run pre_arm_checks and arm_checks and display failures + if (arming.arm(AP_Arming::MAVLINK)) { + //only log if arming was successful + channel_throttle->enable_out(); + Log_Arm_Disarm(); + result = MAV_RESULT_ACCEPTED; } else { - result = MAV_RESULT_UNSUPPORTED; + result = MAV_RESULT_FAILED; + } + } else if (packet.param1 == 0.0f) { + if (arming.disarm()) { + if (arming.arming_required() == AP_Arming::YES_ZERO_PWM) { + channel_throttle->disable_out(); + } + // reset the mission on disarm + mission.stop(); + //only log if disarming was successful + Log_Arm_Disarm(); + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_FAILED; } } else { result = MAV_RESULT_UNSUPPORTED;