mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-05 07:28:29 -04:00
COPTER: Fix MOUNT_CONTROL yaw in guided
If the mount instance does not support yaw/pan, the copter needs to yaw in response to MSG_MOUNT_CONTROL and MAV_COMMAND_DO_MOUNT_CONTROL commands from a GCS or co-computer. There was no checking for mount pan in the GCS_Mavlink logic. As such, no yaw takes place when a mount control command calls for it. This patch impliments copter yaw control for both MSG_MOUNT_CONTROL and MAV_COMMAND_DO_MOUNT_CONTROL in copter GCS_Mavlink.
This commit is contained in:
parent
0e6fc54a0e
commit
c0f0e3eca3
@ -1016,6 +1016,9 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
|
|
||||||
case MAV_CMD_DO_MOUNT_CONTROL:
|
case MAV_CMD_DO_MOUNT_CONTROL:
|
||||||
#if MOUNT == ENABLED
|
#if MOUNT == ENABLED
|
||||||
|
if(!copter.camera_mount.has_pan_control()) {
|
||||||
|
copter.set_auto_yaw_look_at_heading((float)packet.param3 / 100.0f,0.0f,0,0);
|
||||||
|
}
|
||||||
copter.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
|
copter.camera_mount.control(packet.param1, packet.param2, packet.param3, (MAV_MOUNT_MODE) packet.param7);
|
||||||
result = MAV_RESULT_ACCEPTED;
|
result = MAV_RESULT_ACCEPTED;
|
||||||
#endif
|
#endif
|
||||||
@ -1655,6 +1658,9 @@ void GCS_MAVLINK_Copter::handleMessage(mavlink_message_t* msg)
|
|||||||
break;
|
break;
|
||||||
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
//deprecated. Use MAV_CMD_DO_MOUNT_CONTROL
|
||||||
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
case MAVLINK_MSG_ID_MOUNT_CONTROL:
|
||||||
|
if(!copter.camera_mount.has_pan_control()) {
|
||||||
|
copter.set_auto_yaw_look_at_heading(mavlink_msg_mount_control_get_input_c(msg)/100.0f, 0.0f, 0, 0);
|
||||||
|
}
|
||||||
copter.camera_mount.control_msg(msg);
|
copter.camera_mount.control_msg(msg);
|
||||||
break;
|
break;
|
||||||
#endif // MOUNT == ENABLED
|
#endif // MOUNT == ENABLED
|
||||||
|
Loading…
Reference in New Issue
Block a user