|
|
|
@ -625,6 +625,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
@@ -625,6 +625,11 @@ bool AP_Mission::mavlink_to_mission_cmd(const mavlink_mission_item_t& packet, AP
|
|
|
|
|
cmd.p1 = packet.param1; // normal=0 inverted=1
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_GRIPPER: // MAV ID: 211
|
|
|
|
|
cmd.content.gripper.num = packet.param1; // gripper number
|
|
|
|
|
cmd.content.gripper.action = packet.param2; // action 0=release, 1=grab. See GRIPPER_ACTION enum
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
// unrecognised command
|
|
|
|
|
return false; |
|
|
|
@ -888,6 +893,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
@@ -888,6 +893,11 @@ bool AP_Mission::mission_cmd_to_mavlink(const AP_Mission::Mission_Command& cmd,
|
|
|
|
|
packet.param1 = cmd.p1; // normal=0 inverted=1
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
case MAV_CMD_DO_GRIPPER: // MAV ID: 211
|
|
|
|
|
packet.param1 = cmd.content.gripper.num; // gripper number
|
|
|
|
|
packet.param2 = cmd.content.gripper.action; // action 0=release, 1=grab. See GRIPPER_ACTION enum
|
|
|
|
|
break; |
|
|
|
|
|
|
|
|
|
default: |
|
|
|
|
// unrecognised command
|
|
|
|
|
return false; |
|
|
|
|