From 5981e8bbaac2478dc012eac02f3e2eb87faacf44 Mon Sep 17 00:00:00 2001 From: Randy Mackay Date: Fri, 6 Jan 2023 16:56:49 +0900 Subject: [PATCH] AC_AttitudeControl: add get_rate_ef_targets accessor --- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 3 +++ 1 file changed, 3 insertions(+) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index b2d3a87e3c..0c9729f997 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -272,6 +272,9 @@ public: // Return angular velocity in radians used in the angular velocity controller Vector3f rate_bf_targets() const { return _ang_vel_body + _sysid_ang_vel_body; } + // return the angular velocity of the target (setpoint) attitude rad/s + const Vector3f& get_rate_ef_targets() const { return _euler_rate_target; } + // Enable or disable body-frame feed forward void bf_feedforward(bool enable_or_disable) { _rate_bf_ff_enabled.set(enable_or_disable); }