From b3e693daa4f0ebcb33543b11ec017b9c6395bc87 Mon Sep 17 00:00:00 2001 From: Michael Day <mday299@yahoo.com> Date: Sat, 25 Oct 2014 14:19:21 -0700 Subject: [PATCH] AP_Mission: Support MAV_CMD_DO_FENCE_ENABLE as a mission item. --- 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 2703dbf16..9f8d3f6b9 100644 --- a/libraries/AP_Mission/AP_Mission.cpp +++ b/libraries/AP_Mission/AP_Mission.cpp @@ -611,6 +611,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_FENCE_ENABLE: // MAV ID: 207 + cmd.p1 = packet.param1; // action 0=disable, 1=enable + 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; @@ -880,6 +884,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_FENCE_ENABLE: // MAV ID: 207 + packet.param1 = cmd.p1; // action 0=disable, 1=enable + 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; -- GitLab