AC_AttitudeControl: add override keyword in many places

This commit is contained in:
Peter Barker 2018-11-07 21:57:10 +11:00 committed by Andrew Tridgell
parent f00636e794
commit 7e3ca19308
3 changed files with 15 additions and 15 deletions

View File

@ -57,9 +57,9 @@ public:
}
// pid accessors
AC_PID& get_rate_roll_pid() { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() { return _pid_rate_yaw; }
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; }
// 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;
@ -72,7 +72,7 @@ public:
// rate_controller_run - run lowest level body-frame rate controller and send outputs to the motors
// should be called at 100hz or more
virtual void rate_controller_run();
virtual void rate_controller_run() override;
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;
@ -143,7 +143,7 @@ private:
int16_t _passthrough_yaw;
// get_roll_trim - angle in centi-degrees to be added to roll angle. Used by helicopter to counter tail rotor thrust in hover
float get_roll_trim_rad() { return constrain_float(radians(_hover_roll_trim_scalar * _hover_roll_trim * 0.01f), -radians(10.0f),radians(10.0f));}
float get_roll_trim_rad() override { return constrain_float(radians(_hover_roll_trim_scalar * _hover_roll_trim * 0.01f), -radians(10.0f),radians(10.0f));}
// internal variables
float _hover_roll_trim_scalar = 0; // scalar used to suppress Hover Roll Trim

View File

@ -47,9 +47,9 @@ public:
virtual ~AC_AttitudeControl_Multi() {}
// pid accessors
AC_PID& get_rate_roll_pid() { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() { return _pid_rate_yaw; }
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; }
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;
@ -73,10 +73,10 @@ public:
bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
// run lowest level body-frame rate controller and send outputs to the motors
void rate_controller_run();
void rate_controller_run() override;
// sanity check parameters. should be called once before take-off
void parameter_sanity_check();
void parameter_sanity_check() override;
// user settable parameters
static const struct AP_Param::GroupInfo var_info[];

View File

@ -31,9 +31,9 @@ public:
virtual ~AC_AttitudeControl_Sub() {}
// pid accessors
AC_PID& get_rate_roll_pid() { return _pid_rate_roll; }
AC_PID& get_rate_pitch_pid() { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() { return _pid_rate_yaw; }
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; }
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;
@ -55,10 +55,10 @@ public:
bool is_throttle_mix_min() const override { return (_throttle_rpy_mix < 1.25f*_thr_mix_min); }
// run lowest level body-frame rate controller and send outputs to the motors
void rate_controller_run();
void rate_controller_run() override;
// sanity check parameters. should be called once before take-off
void parameter_sanity_check();
void parameter_sanity_check() override;
// user settable parameters
static const struct AP_Param::GroupInfo var_info[];