diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl.h b/libraries/AC_AttitudeControl/AC_AttitudeControl.h index 9cc8a9177f..e4e51a856a 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl.h @@ -264,7 +264,7 @@ protected: virtual float rate_bf_to_motor_yaw(float rate_target_rads); // Compute a throttle value that is adjusted for the tilt angle of the vehicle - virtual float get_boosted_throttle(float throttle_in) = 0; + virtual float get_throttle_boosted(float throttle_in) = 0; // Return angle in radians to be added to roll angle. Used by heli to counteract // tail rotor thrust in hover. Overloaded by AC_Attitude_Heli to return angle. diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h index 1212442690..51c6d2fc64 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Heli.h @@ -125,9 +125,6 @@ private: // // throttle methods // - - // calculate total body frame throttle required to produce the given earth frame throttle - float get_boosted_throttle(float throttle_in); // pass through for roll and pitch int16_t _passthrough_roll; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp index 41b44c18a4..6a05558900 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.cpp @@ -153,7 +153,7 @@ void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_an _throttle_in_filt.apply(throttle_in, _dt); _motors.set_throttle_filter_cutoff(filter_cutoff); if (apply_angle_boost) { - _motors.set_throttle(get_boosted_throttle(throttle_in)); + _motors.set_throttle(get_throttle_boosted(throttle_in)); }else{ _motors.set_throttle(throttle_in); // Clear angle_boost for logging purposes @@ -163,7 +163,7 @@ void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_an // returns a throttle including compensation for roll/pitch angle // throttle value should be 0 ~ 1 -float AC_AttitudeControl_Multi::get_boosted_throttle(float throttle_in) +float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in) { if (!_angle_boost_enabled) { _angle_boost = 0; diff --git a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h index cf9fa1409b..a47ab3751f 100644 --- a/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h +++ b/libraries/AC_AttitudeControl/AC_AttitudeControl_Multi.h @@ -59,7 +59,7 @@ public: void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) override; // calculate total body frame throttle required to produce the given earth frame throttle - float get_boosted_throttle(float throttle_in); + float get_throttle_boosted(float throttle_in); // user settable parameters static const struct AP_Param::GroupInfo var_info[];