AC_AttControl: rename set_throttle_out parameter

No functional change
This commit is contained in:
Leonard Hall 2015-06-23 22:39:26 +09:00 committed by Randy Mackay
parent 0eaf815411
commit c8872e082d
2 changed files with 5 additions and 5 deletions

View File

@ -700,15 +700,15 @@ void AC_AttitudeControl::accel_limiting(bool enable_limits)
// set_throttle_out - to be called by upper throttle controllers when they wish to provide throttle output directly to motors
// provide 0 to cut motors
void AC_AttitudeControl::set_throttle_out(float throttle_out, bool apply_angle_boost, float filter_cutoff)
void AC_AttitudeControl::set_throttle_out(float throttle_in, bool apply_angle_boost, float filter_cutoff)
{
_throttle_in_filt.apply(throttle_out, _dt);
_throttle_in_filt.apply(throttle_in, _dt);
_motors.set_stabilizing(true);
_motors.set_throttle_filter_cutoff(filter_cutoff);
if (apply_angle_boost) {
_motors.set_throttle(get_boosted_throttle(throttle_out));
_motors.set_throttle(get_boosted_throttle(throttle_in));
}else{
_motors.set_throttle(throttle_out);
_motors.set_throttle(throttle_in);
// clear angle_boost for logging purposes
_angle_boost = 0;
}

View File

@ -206,7 +206,7 @@ public:
//
// set_throttle_out - to be called by upper throttle controllers when they wish to provide throttle output directly to motors
void set_throttle_out(float throttle_pwm, bool apply_angle_boost, float filt_cutoff);
void set_throttle_out(float throttle_in, bool apply_angle_boost, float filt_cutoff);
// outputs a throttle to all motors evenly with no stabilization
void set_throttle_out_unstabilized(float throttle_in, bool reset_attitude_control, float filt_cutoff);