Browse Source

Copter: fix do-mount-control yaw scaling

master_rangefinder
Randy Mackay 2 years ago committed by Andrew Tridgell
parent
commit
38665a7935
  1. 4
      ArduCopter/GCS_Mavlink.cpp

4
ArduCopter/GCS_Mavlink.cpp

@ -737,9 +737,7 @@ MAV_RESULT GCS_MAVLINK_Copter::handle_command_mount(const mavlink_command_long_t
// if vehicle has a camera mount but it 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) && if ((copter.camera_mount.get_mount_type() != copter.camera_mount.MountType::Mount_Type_None) &&
!copter.camera_mount.has_pan_control()) { !copter.camera_mount.has_pan_control()) {
copter.flightmode->auto_yaw.set_yaw_angle_rate( copter.flightmode->auto_yaw.set_yaw_angle_rate((float)packet.param3, 0.0f);
(float)packet.param3 * 0.01f,
0.0f);
} }
break; break;
default: default:

Loading…
Cancel
Save