From 24dcbe1b0eed38926bc4766c453afb93b138f41a Mon Sep 17 00:00:00 2001 From: Pat Hickey Date: Tue, 9 Oct 2012 18:48:05 -0700 Subject: [PATCH] ArduCopter GCS_MAVLink: COMMAND_LONG for arm/disarm motors Date: Wed, 26 Sep 2012 15:56:43 -0700 Subject: ArduCopter arm/disarm command consensus From: Pat Hickey To: Michael Oborne Cc: "Craig J. Elder", arducopter , mavelous Michael, Per our discussion today, In a MAVLINK_MSG_ID_COMMAND_LONG A MAV_CMD of type MAV_CMD_COMPONENT_ARM_DISARM with component id MAV_COMP_ID_SYSTEM_CONTROL = 250, uses param index 1 to specify an arm/disarm motors event: 1 to arm, 0 to disarm Thanks for working this out with me. Sorry to get it so completely wrong the first time around! Best Pat --- ArduCopter/GCS_Mavlink.pde | 16 +++++++++++++++- 1 file changed, 15 insertions(+), 1 deletion(-) diff --git a/ArduCopter/GCS_Mavlink.pde b/ArduCopter/GCS_Mavlink.pde index ea69ad80f7..4049c42c59 100644 --- a/ArduCopter/GCS_Mavlink.pde +++ b/ArduCopter/GCS_Mavlink.pde @@ -1074,7 +1074,21 @@ void GCS_MAVLINK::handleMessage(mavlink_message_t* msg) result = MAV_RESULT_ACCEPTED; break; - + case MAV_CMD_COMPONENT_ARM_DISARM: + if (packet.target_component == MAV_COMP_ID_SYSTEM_CONTROL) { + if (packet.param1 == 1.0f) { + init_arm_motors(); + result = MAV_RESULT_ACCEPTED; + } else if (packet.param1 == 0.0f) { + init_disarm_motors(); + result = MAV_RESULT_ACCEPTED; + } else { + result = MAV_RESULT_UNSUPPORTED; + } + } else { + result = MAV_RESULT_UNSUPPORTED; + } + break; default: result = MAV_RESULT_UNSUPPORTED; break;