diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index 8ed3a2d63c..c0c660adf7 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1240,22 +1240,18 @@ 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 - pre_arm_checks(true); - if(ap.pre_arm_check && arm_checks(true)) { - init_arm_motors(); - result = MAV_RESULT_ACCEPTED; - }else{ - result = MAV_RESULT_UNSUPPORTED; - } - } else if (packet.param1 == 0.0f) { - init_disarm_motors(); + if (packet.param1 == 1.0f) { + // run pre_arm_checks and arm_checks and display failures + pre_arm_checks(true); + if(ap.pre_arm_check && arm_checks(true)) { + init_arm_motors(); result = MAV_RESULT_ACCEPTED; - } else { + }else{ result = MAV_RESULT_UNSUPPORTED; } + } else if (packet.param1 == 0.0f) { + init_disarm_motors(); + result = MAV_RESULT_ACCEPTED; } else { result = MAV_RESULT_UNSUPPORTED; }