mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 14:38:30 -04:00
Copter: fix do-mount-control yaw scaling
This commit is contained in:
parent
7244cd361d
commit
38665a7935
@ -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…
Reference in New Issue
Block a user