mirror of https://github.com/ArduPilot/ardupilot
Mission: add support for MAV_CMD_DO_PARACHUTE
This commit is contained in:
parent
a682f652d0
commit
d8f9a1c6c6
|
@ -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;
|
||||
|
|
Loading…
Reference in New Issue