Copter: add voltage compensation to _throttle_thrust_max

This commit is contained in:
Leonard Hall 2019-10-10 11:41:53 +10:30 committed by Andrew Tridgell
parent e3cbb3a6b4
commit 92402da5ef
1 changed files with 2 additions and 2 deletions

View File

@ -152,7 +152,7 @@ void AP_MotorsMatrix::output_armed_stabilizing()
yaw_thrust = (_yaw_in + _yaw_in_ff) * compensation_gain;
throttle_thrust = get_throttle() * compensation_gain;
throttle_avg_max = _throttle_avg_max * compensation_gain;
throttle_thrust_max = _thrust_boost_ratio + (1.0f - _thrust_boost_ratio) * _throttle_thrust_max;
throttle_thrust_max = _thrust_boost_ratio + (1.0f - _thrust_boost_ratio) * _throttle_thrust_max * compensation_gain;
// sanity check throttle is above zero and below current limited throttle
if (throttle_thrust <= 0.0f) {
@ -360,7 +360,7 @@ void AP_MotorsMatrix::check_for_failed_motor(float throttle_thrust_best_plus_adj
}
// check to see if thrust boost is using more throttle than _throttle_thrust_max
if (_throttle_thrust_max > throttle_thrust_best_plus_adj && rpyt_high < 0.9f && _thrust_balanced) {
if ((_throttle_thrust_max * get_compensation_gain() > throttle_thrust_best_plus_adj) && (rpyt_high < 0.9f) && _thrust_balanced) {
_thrust_boost = false;
}
}