AC_AttitudeControl: remove unused set_throttle_out_unstabilized

This commit is contained in:
Leonard Hall 2018-12-28 17:02:31 +10:30 committed by Randy Mackay
parent 2daa5ffb9e
commit 6e76dff930
2 changed files with 0 additions and 15 deletions

View File

@ -147,18 +147,6 @@ const AP_Param::GroupInfo AC_AttitudeControl::var_info[] = {
AP_GROUPEND
};
// Set output throttle and disable stabilization
void AC_AttitudeControl::set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filter_cutoff)
{
_throttle_in = throttle_in;
_motors.set_throttle_filter_cutoff(filter_cutoff);
if (reset_attitude_control) {
relax_attitude_controllers();
}
_motors.set_throttle(throttle_in);
_angle_boost = 0.0f;
}
// Ensure attitude controller have zero errors to relax rate controller output
void AC_AttitudeControl::relax_attitude_controllers()
{

View File

@ -228,9 +228,6 @@ public:
// Set output throttle
virtual void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff) = 0;
// Set output throttle and disable stabilization
void set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filt_cutoff);
// get throttle passed into attitude controller (i.e. throttle_in provided to set_throttle_out)
float get_throttle_in() const { return _throttle_in; }