AC_AttitudeControl: move get_althold_lean_angle_max to parent class

This commit is contained in:
Randy Mackay 2016-05-26 22:11:58 +09:00
parent 3d27ecca92
commit dafc45eb26
6 changed files with 10 additions and 23 deletions

View File

@ -604,6 +604,13 @@ void AC_AttitudeControl::set_throttle_out_unstabilized(float throttle_in, bool r
_angle_boost = 0.0f;
}
// Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
float AC_AttitudeControl::get_althold_lean_angle_max() const
{
// convert to centi-degrees for public interface
return ToDeg(_althold_lean_angle_max) * 100.0f;
}
float AC_AttitudeControl::sqrt_controller(float error, float p, float second_ord_lim)
{
if (second_ord_lim < 0.0f || is_zero(second_ord_lim) || is_zero(p)) {

View File

@ -214,7 +214,7 @@ public:
float angle_boost() const { return _angle_boost; }
// Return tilt angle limit for pilot input that prioritises altitude hold over lean angle
virtual float get_althold_lean_angle_max() const = 0;
float get_althold_lean_angle_max() const;
// Return configured tilt angle limit in centidegrees
float lean_angle_max() const { return _aparm.angle_max; }
@ -354,7 +354,7 @@ protected:
bool _att_ctrl_use_accel_limit;
// Filtered Alt_Hold lean angle max - used to limit lean angle when throttle is saturated using Alt_Hold
float _althold_lean_angle_max;
float _althold_lean_angle_max = 0.0f;
float _throttle_rpy_mix_desired; // desired throttle_low_comp value, actual throttle_low_comp is slewed towards this value over 1~2 seconds
float _throttle_rpy_mix; // mix between throttle and hover throttle for 0 to 1 and ratio above hover throttle for >1

View File

@ -232,13 +232,6 @@ void AC_AttitudeControl_Heli::rate_controller_run()
}
}
// get lean angle max for pilot input that prioritises altitude hold over lean angle
float AC_AttitudeControl_Heli::get_althold_lean_angle_max() const
{
// TEMP: convert to centi-degrees for public interface
return degrees(_althold_lean_angle_max) * 100.0f;
}
// Update Alt_Hold angle maximum
void AC_AttitudeControl_Heli::update_althold_lean_angle_max(float throttle_in)
{

View File

@ -75,10 +75,6 @@ public:
// should be called at 100hz or more
virtual void rate_controller_run();
// get lean angle max for pilot input that prioritises altitude hold over lean angle
// NOTE: returns centi-degrees
float get_althold_lean_angle_max() const;
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;

View File

@ -147,12 +147,6 @@ AC_AttitudeControl_Multi::AC_AttitudeControl_Multi(AP_AHRS &ahrs, const AP_Vehic
AP_Param::setup_object_defaults(this, var_info);
}
// get lean angle max for pilot input that prioritises altitude hold over lean angle
float AC_AttitudeControl_Multi::get_althold_lean_angle_max() const
{
return ToDeg(_althold_lean_angle_max) * 100.0f;
}
// Update Alt_Hold angle maximum
void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)
{
@ -166,7 +160,7 @@ void AC_AttitudeControl_Multi::update_althold_lean_angle_max(float throttle_in)
}
float althold_lean_angle_max = acos(constrain_float(_throttle_in/(AC_ATTITUDE_CONTROL_ALTHOLD_LEAN_ANGLE_THROTTLE_MAX * thr_max), 0.0f, 1.0f));
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+AC_ATTITUDE_CONTROL_ALTHOLD_LEAN_ANGLE_TC_DEFAULT))*(_throttle_in-_althold_lean_angle_max);
_althold_lean_angle_max = _althold_lean_angle_max + (_dt/(_dt+AC_ATTITUDE_CONTROL_ALTHOLD_LEAN_ANGLE_TC_DEFAULT))*(althold_lean_angle_max-_althold_lean_angle_max);
}
void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)

View File

@ -52,9 +52,6 @@ public:
AC_PID& get_rate_pitch_pid() { return _pid_rate_pitch; }
AC_PID& get_rate_yaw_pid() { return _pid_rate_yaw; }
// get lean angle max for pilot input that prioritizes altitude hold over lean angle
float get_althold_lean_angle_max() const;
// Update Alt_Hold angle maximum
void update_althold_lean_angle_max(float throttle_in) override;