mirror of https://github.com/ArduPilot/ardupilot
AP_Mount: fix gimbal-device-attitude-status yaw frame flag
This commit is contained in:
parent
06a79ad4f5
commit
efd832425c
|
@ -854,6 +854,7 @@ uint16_t AP_Mount_Backend::get_gimbal_device_flags() const
|
|||
(get_mode() == MAV_MOUNT_MODE_NEUTRAL ? GIMBAL_DEVICE_FLAGS_NEUTRAL : 0) |
|
||||
GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame
|
||||
GIMBAL_DEVICE_FLAGS_PITCH_LOCK| // pitch angle is always earth-frame, yaw_angle is always body-frame
|
||||
GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME | // yaw angle is always in vehicle-frame
|
||||
(yaw_lock_state ? GIMBAL_DEVICE_FLAGS_YAW_LOCK : 0);
|
||||
return flags;
|
||||
}
|
||||
|
|
Loading…
Reference in New Issue