@@ -817,10 +817,44 @@ void AP_Mount_Backend::update_angle_target_from_rate(const MountTarget& rate_rad
817817// helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message
818818uint16_t AP_Mount_Backend::get_gimbal_device_flags () const
819819{
820+ // get yaw lock state by mode
821+ bool yaw_lock_state = false ;
822+ switch (_mode) {
823+ case MAV_MOUNT_MODE_RETRACT:
824+ case MAV_MOUNT_MODE_NEUTRAL:
825+ // these modes always use body-frame yaw (aka follow)
826+ yaw_lock_state = false ;
827+ break ;
828+ case MAV_MOUNT_MODE_MAVLINK_TARGETING:
829+ switch (mnt_target.target_type ) {
830+ case MountTargetType::RATE:
831+ yaw_lock_state = mnt_target.rate_rads .yaw_is_ef ;
832+ break ;
833+ case MountTargetType::ANGLE:
834+ yaw_lock_state = mnt_target.angle_rad .yaw_is_ef ;
835+ break ;
836+ }
837+ break ;
838+ case MAV_MOUNT_MODE_RC_TARGETING:
839+ yaw_lock_state = _yaw_lock;
840+ break ;
841+ case MAV_MOUNT_MODE_GPS_POINT:
842+ case MAV_MOUNT_MODE_SYSID_TARGET:
843+ case MAV_MOUNT_MODE_HOME_LOCATION:
844+ // these modes always use earth-frame yaw (aka lock)
845+ yaw_lock_state = true ;
846+ break ;
847+ case MAV_MOUNT_MODE_ENUM_END:
848+ // unsupported
849+ yaw_lock_state = false ;
850+ break ;
851+ }
852+
820853 const uint16_t flags = (get_mode () == MAV_MOUNT_MODE_RETRACT ? GIMBAL_DEVICE_FLAGS_RETRACT : 0 ) |
821854 (get_mode () == MAV_MOUNT_MODE_NEUTRAL ? GIMBAL_DEVICE_FLAGS_NEUTRAL : 0 ) |
822855 GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame
823- GIMBAL_DEVICE_FLAGS_PITCH_LOCK; // pitch angle is always earth-frame, yaw_angle is always body-frame
856+ GIMBAL_DEVICE_FLAGS_PITCH_LOCK| // pitch angle is always earth-frame, yaw_angle is always body-frame
857+ (yaw_lock_state ? GIMBAL_DEVICE_FLAGS_YAW_LOCK : 0 );
824858 return flags;
825859}
826860
0 commit comments