From d8f9a1c6c63af8454d87771fc608ea0a6b4532e8 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Thu, 3 Apr 2014 17:49:04 +0900 Subject: [PATCH] Mission: add support for MAV_CMD_DO_PARACHUTE --- libraries/AP_Mission/AP_Mission.cpp | 8 ++++++++ 1 file changed, 8 insertions(+) diff --git a/libraries/AP_Mission/AP_Mission.cpp b/libraries/AP_Mission/AP_Mission.cpp index 41dfc121a5..b2b928749f 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -548,6 +548,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP cmd.content.cam_trigg_dist.meters = packet.param1; // distance between camera shots in meters break; + case MAV_CMD_DO_PARACHUTE: // MAV ID: 208 + cmd.p1 = packet.param1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum + break; + default: // unrecognised command return false; @@ -767,6 +771,10 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd, packet.param1 = cmd.content.cam_trigg_dist.meters; // distance between camera shots in meters break; + case MAV_CMD_DO_PARACHUTE: // MAV ID: 208 + packet.param1 = cmd.p1; // action 0=disable, 1=enable, 2=release. See PARACHUTE_ACTION enum + break; + default: // unrecognised command return false;