AC_AttitudeControl: add const get_rate_pid accessors

This commit is contained in:
Randy Mackay 2023-08-29 09:03:18 +09:00 committed by Peter Barker
parent 11ddf9f7c7
commit ed7ca580c2
4 changed files with 12 additions and 0 deletions

View File

@ -83,6 +83,9 @@ public:
virtual AC_PID& get_rate_roll_pid() = 0;
virtual AC_PID& get_rate_pitch_pid() = 0;
virtual AC_PID& get_rate_yaw_pid() = 0;
virtual const AC_PID& get_rate_roll_pid() const = 0;
virtual const AC_PID& get_rate_pitch_pid() const = 0;
virtual const AC_PID& get_rate_yaw_pid() const = 0;
// get the roll acceleration limit in centidegrees/s/s or radians/s/s
float get_accel_roll_max_cdss() const { return _accel_roll_max; }

View File

@ -51,6 +51,9 @@ public:
AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; }
const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; }
const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; }
// passthrough_bf_roll_pitch_rate_yaw - roll and pitch are passed through directly, body-frame rate target for yaw
void passthrough_bf_roll_pitch_rate_yaw(float roll_passthrough, float pitch_passthrough, float yaw_rate_bf_cds) override;

View File

@ -50,6 +50,9 @@ public:
AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; }
const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; }
const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; }
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;

View File

@ -36,6 +36,9 @@ public:
AC_PID& get_rate_roll_pid() override { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() override { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() override { return _pid_rate_yaw; }
const AC_PID& get_rate_roll_pid() const override { return _pid_rate_roll; }
const AC_PID& get_rate_pitch_pid() const override { return _pid_rate_pitch; }
const AC_PID& get_rate_yaw_pid() const override { return _pid_rate_yaw; }
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;