mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-04 23:18:29 -04:00
AP_Mission: Support MAV_CMD_DO_FENCE_ENABLE as a mission item.
This commit is contained in:
parent
77958f8fd4
commit
b3e693daa4
@ -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;
|
||||
|
Loading…
Reference in New Issue
Block a user