|
|
|
@ -685,15 +685,17 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
@@ -685,15 +685,17 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_int_packet(const mavlink_command_i
|
|
|
|
|
|
|
|
|
|
MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t &packet) |
|
|
|
|
{ |
|
|
|
|
// if the mount doesn't do pan control then yaw the entire vehicle instead:
|
|
|
|
|
switch (packet.command) { |
|
|
|
|
#if HAL_MOUNT_ENABLED |
|
|
|
|
case MAV_CMD_DO_MOUNT_CONTROL: |
|
|
|
|
if (!copter.camera_mount.has_pan_control()) { |
|
|
|
|
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
|
|
|
|
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && |
|
|
|
|
!copter.camera_mount.has_pan_control()) { |
|
|
|
|
copter.flightmode->auto_yaw.set_fixed_yaw( |
|
|
|
|
(float)packet.param3 * 0.01f, |
|
|
|
|
0.0f, |
|
|
|
|
0,0); |
|
|
|
|
0, |
|
|
|
|
false); |
|
|
|
|
} |
|
|
|
|
break; |
|
|
|
|
#endif |
|
|
|
@ -955,13 +957,14 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
@@ -955,13 +957,14 @@ void GCS_MAVLINK_Copter::handle_mount_message(const mavlink_message_t &msg)
|
|
|
|
|
switch (msg.msgid) { |
|
|
|
|
#if HAL_MOUNT_ENABLED |
|
|
|
|
case MAVLINK_MSG_ID_MOUNT_CONTROL: |
|
|
|
|
if (!copter.camera_mount.has_pan_control()) { |
|
|
|
|
// if the mount doesn't do pan control then yaw the entire vehicle instead:
|
|
|
|
|
// if vehicle has a camera mount but it doesn't do pan control then yaw the entire vehicle instead
|
|
|
|
|
if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) && |
|
|
|
|
!copter.camera_mount.has_pan_control()) { |
|
|
|
|
copter.flightmode->auto_yaw.set_fixed_yaw( |
|
|
|
|
mavlink_msg_mount_control_get_input_c(&msg) * 0.01f, |
|
|
|
|
0.0f, |
|
|
|
|
0, |
|
|
|
|
0); |
|
|
|
|
false); |
|
|
|
|
|
|
|
|
|
break; |
|
|
|
|
} |
|
|
|
|