From 05f21d766567c2339df8b6ac8ec5ea81cbd95e02 Mon Sep 17 00:00:00 2001 From: Leonard Hall Date: Fri, 9 Jul 2021 18:13:33 +0930 Subject: [PATCH] AC_AttitudeControl: Add accessor for yaw slew limit --- libraries/AC_AttitudeControl/AC_AttitudeControl.h | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 49f7002d02..4cc87fd7fc 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -111,6 +111,9 @@ public: // get the pitch angular velocity limit in radians/s float get_ang_vel_pitch_max_radss() const { return _ang_vel_pitch_max; } + // get the yaw slew limit + float get_slew_yaw_cds() const { return _slew_yaw; } + // get the rate control input smoothing time constant float get_input_tc() const { return _input_tc; } @@ -120,7 +123,7 @@ public: // Ensure attitude controller have zero errors to relax rate controller output void relax_attitude_controllers(); - // Used by child class AC_AttitudeControl_TS to change behavior for tailsitter quadplanes + // Used by child class AC_AttitudeControl_TS to change behaviour for tailsitter quadplanes virtual void relax_attitude_controllers(bool exclude_pitch) { relax_attitude_controllers(); } // reset rate controller I terms