AC_AttitudeControl: add get_rate_ef_targets accessor

This commit is contained in:
Randy Mackay 2023-01-06 16:56:49 +09:00 committed by Andrew Tridgell
parent 9d69374bd7
commit 11af0ea147
1 changed files with 3 additions and 0 deletions

View File

@ -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); }