AC_AttitudeControl: rename throttle_ave_max to throttle_avg_max

This commit is contained in:
Randy Mackay 2016-06-08 17:49:05 +09:00
parent 570920c7d7
commit da946288a2
2 changed files with 3 additions and 3 deletions

View File

@ -176,7 +176,7 @@ void AC_AttitudeControl_Multi::set_throttle_out(float throttle_in, bool apply_an
_angle_boost = 0.0f;
}
_motors.set_throttle(throttle_in);
_motors.set_throttle_ave_max(get_throttle_ave_max(MAX(throttle_in, _throttle_in)));
_motors.set_throttle_avg_max(get_throttle_avg_max(MAX(throttle_in, _throttle_in)));
}
// returns a throttle including compensation for roll/pitch angle
@ -201,7 +201,7 @@ float AC_AttitudeControl_Multi::get_throttle_boosted(float throttle_in)
// returns a throttle including compensation for roll/pitch angle
// throttle value should be 0 ~ 1
float AC_AttitudeControl_Multi::get_throttle_ave_max(float throttle_in)
float AC_AttitudeControl_Multi::get_throttle_avg_max(float throttle_in)
{
return MAX(throttle_in, throttle_in*MAX(0.0f,1.0f-_throttle_rpy_mix)+_motors.get_throttle_hover()*_throttle_rpy_mix);
}

View File

@ -62,7 +62,7 @@ public:
float get_throttle_boosted(float throttle_in);
// calculate total body frame throttle required to produce the given earth frame throttle
float get_throttle_ave_max(float throttle_in);
float get_throttle_avg_max(float throttle_in);
// set desired throttle vs attitude mixing (actual mix is slewed towards this value over 1~2 seconds)
// low values favour pilot/autopilot throttle over attitude control, high values favour attitude control over throttle