Browse Source

Mission: add support for MAV_CMD_DO_PARACHUTE

master
Randy Mackay 11 years ago
parent
commit
d8f9a1c6c6
  1. 8
      libraries/AP_Mission/AP_Mission.cpp

8
libraries/AP_Mission/AP_Mission.cpp

@ -548,6 +548,10 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP @@ -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, @@ -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;

Loading…
Cancel
Save