diff --git a/libraries/AP_Mount/AP_Mount_Backend.cpp b/libraries/AP_Mount/AP_Mount_Backend.cpp index 5fc2a3cff0339..de45386f1668a 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.cpp +++ b/libraries/AP_Mount/AP_Mount_Backend.cpp @@ -857,12 +857,14 @@ uint16_t AP_Mount_Backend::get_gimbal_device_flags() const break; } + const uint16_t yaw_ef_flags = GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME | GIMBAL_DEVICE_FLAGS_YAW_LOCK; + const uint16_t yaw_bf_flags = GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME; + const uint16_t flags = (get_mode() == MAV_MOUNT_MODE_RETRACT ? GIMBAL_DEVICE_FLAGS_RETRACT : 0) | (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); + GIMBAL_DEVICE_FLAGS_ROLL_LOCK | // roll angle is always earth-frame + GIMBAL_DEVICE_FLAGS_PITCH_LOCK | // pitch angle is always earth-frame + (yaw_lock_state ? yaw_ef_flags : yaw_bf_flags); // yaw angle can be either earth-frame or body-frame return flags; } diff --git a/libraries/AP_Mount/AP_Mount_Backend.h b/libraries/AP_Mount/AP_Mount_Backend.h index 56706d7463c98..d64a0e2bbed92 100644 --- a/libraries/AP_Mount/AP_Mount_Backend.h +++ b/libraries/AP_Mount/AP_Mount_Backend.h @@ -288,7 +288,7 @@ class AP_Mount_Backend void update_angle_target_from_rate(const MountTarget& rate_rad, MountTarget& angle_rad) const; // helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message - uint16_t get_gimbal_device_flags() const; + virtual uint16_t get_gimbal_device_flags() const; // sent warning to GCS void send_warning_to_GCS(const char* warning_str); diff --git a/libraries/AP_Mount/AP_Mount_Servo.cpp b/libraries/AP_Mount/AP_Mount_Servo.cpp index 2f926c7d848a3..384364d5761a3 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.cpp +++ b/libraries/AP_Mount/AP_Mount_Servo.cpp @@ -139,6 +139,22 @@ bool AP_Mount_Servo::get_attitude_quaternion(Quaternion& att_quat) return true; } +// helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message +uint16_t AP_Mount_Servo::get_gimbal_device_flags() const +{ + uint16_t flags = AP_Mount_Backend::get_gimbal_device_flags(); + // per get_attitude_quaternion() above, angles are all body frame, so clear all the LOCK flags... + const uint16_t mask = ~(GIMBAL_DEVICE_FLAGS_ROLL_LOCK | + GIMBAL_DEVICE_FLAGS_PITCH_LOCK | + GIMBAL_DEVICE_FLAGS_YAW_LOCK | + GIMBAL_DEVICE_FLAGS_YAW_IN_EARTH_FRAME); + flags &= mask; + // and set the YAW_IN_VEHICLE_FRAME flag + flags |= GIMBAL_DEVICE_FLAGS_YAW_IN_VEHICLE_FRAME; + + return flags; +} + // private methods // update body-frame angle outputs from earth-frame angle targets diff --git a/libraries/AP_Mount/AP_Mount_Servo.h b/libraries/AP_Mount/AP_Mount_Servo.h index 529a97bd7341c..7bef2a1cd2cb7 100644 --- a/libraries/AP_Mount/AP_Mount_Servo.h +++ b/libraries/AP_Mount/AP_Mount_Servo.h @@ -39,6 +39,9 @@ class AP_Mount_Servo : public AP_Mount_Backend // get attitude as a quaternion. returns true on success bool get_attitude_quaternion(Quaternion& att_quat) override; + // helper function to provide GIMBAL_DEVICE_FLAGS for use in GIMBAL_DEVICE_ATTITUDE_STATUS message + uint16_t get_gimbal_device_flags() const override; + private: // update body-frame angle outputs from earth-frame targets