AC_AttitudeControl: add get_accel_roll/pitch/yaw_max_radss methods
Also constify existing get_accel_roll/pitch/yaw_max methods
This commit is contained in:
parent
185f41d5bd
commit
213f7a4061
@ -74,8 +74,9 @@ public:
|
||||
virtual AC_PID& get_rate_pitch_pid() = 0;
|
||||
virtual AC_PID& get_rate_yaw_pid() = 0;
|
||||
|
||||
// Gets the roll acceleration limit in centidegrees/s/s
|
||||
float get_accel_roll_max() { return _accel_roll_max; }
|
||||
// get the roll acceleration limit in centidegrees/s/s or radians/s/s
|
||||
float get_accel_roll_max() const { return _accel_roll_max; }
|
||||
float get_accel_roll_max_radss() const { return radians(_accel_roll_max*0.01f); }
|
||||
|
||||
// Sets the roll acceleration limit in centidegrees/s/s
|
||||
void set_accel_roll_max(float accel_roll_max) { _accel_roll_max = accel_roll_max; }
|
||||
@ -83,8 +84,9 @@ public:
|
||||
// Sets and saves the roll acceleration limit in centidegrees/s/s
|
||||
void save_accel_roll_max(float accel_roll_max) { _accel_roll_max.set_and_save(accel_roll_max); }
|
||||
|
||||
// Sets the pitch acceleration limit in centidegrees/s/s
|
||||
float get_accel_pitch_max() { return _accel_pitch_max; }
|
||||
// get the pitch acceleration limit in centidegrees/s/s or radians/s/s
|
||||
float get_accel_pitch_max() const { return _accel_pitch_max; }
|
||||
float get_accel_pitch_max_radss() const { return radians(_accel_pitch_max*0.01f); }
|
||||
|
||||
// Sets the pitch acceleration limit in centidegrees/s/s
|
||||
void set_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max = accel_pitch_max; }
|
||||
@ -92,8 +94,9 @@ public:
|
||||
// Sets and saves the pitch acceleration limit in centidegrees/s/s
|
||||
void save_accel_pitch_max(float accel_pitch_max) { _accel_pitch_max.set_and_save(accel_pitch_max); }
|
||||
|
||||
// Gets the yaw acceleration limit in centidegrees/s/s
|
||||
float get_accel_yaw_max() { return _accel_yaw_max; }
|
||||
// get the yaw acceleration limit in centidegrees/s/s or radians/s/s
|
||||
float get_accel_yaw_max() const { return _accel_yaw_max; }
|
||||
float get_accel_yaw_max_radss() const { return radians(_accel_yaw_max*0.01f); }
|
||||
|
||||
// Sets the yaw acceleration limit in centidegrees/s/s
|
||||
void set_accel_yaw_max(float accel_yaw_max) { _accel_yaw_max = accel_yaw_max; }
|
||||
@ -291,15 +294,6 @@ protected:
|
||||
// tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle.
|
||||
virtual float get_roll_trim_rad() { return 0;}
|
||||
|
||||
// Return the roll axis acceleration limit in radians/s/s
|
||||
float get_accel_roll_max_radss() { return radians(_accel_roll_max*0.01f); }
|
||||
|
||||
// Return the pitch axis acceleration limit in radians/s/s
|
||||
float get_accel_pitch_max_radss() { return radians(_accel_pitch_max*0.01f); }
|
||||
|
||||
// Return the yaw axis acceleration limit in radians/s/s
|
||||
float get_accel_yaw_max_radss() { return radians(_accel_yaw_max*0.01f); }
|
||||
|
||||
// Return the yaw slew rate limit in radians/s
|
||||
float get_slew_yaw_rads() { return radians(_slew_yaw*0.01f); }
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user