mirror of https://github.com/ArduPilot/ardupilot
AP_Mission: Set DO_MOUNT_CONTROL.mode when converting command to MAVLink
This commit is contained in:
parent
03db86427a
commit
77f1efac5e
|
@ -1251,6 +1251,7 @@ MAV_MISSION_RESULT AP_Mission::mavlink_int_to_mission_cmd(const mavlink_mission_
|
|||
break;
|
||||
|
||||
case MAV_CMD_DO_MOUNT_CONTROL: // MAV ID: 205
|
||||
// TODO: this is only valid if packet.z == MAV_MOUNT_MODE_MAVLINK_TARGETING
|
||||
cmd.content.mount_control.pitch = packet.param1;
|
||||
cmd.content.mount_control.roll = packet.param2;
|
||||
cmd.content.mount_control.yaw = packet.param3;
|
||||
|
@ -1767,6 +1768,7 @@ bool AP_Mission::mission_cmd_to_mavlink_int(const AP_Mission::Mission_Command& c
|
|||
packet.param1 = cmd.content.mount_control.pitch;
|
||||
packet.param2 = cmd.content.mount_control.roll;
|
||||
packet.param3 = cmd.content.mount_control.yaw;
|
||||
packet.z = MAV_MOUNT_MODE_MAVLINK_TARGETING;
|
||||
break;
|
||||
|
||||
case MAV_CMD_DO_SET_CAM_TRIGG_DIST: // MAV ID: 206
|
||||
|
|
Loading…
Reference in New Issue