MotorsTri: fix output_armed_stabilized min thr limit

_min_throttle is in the pwm range but was being used as if in the 0 to
1000 range
This commit is contained in:
Randy Mackay 2015-07-20 17:06:09 +09:00
parent e53c46bd8f
commit bd9a605086
1 changed files with 6 additions and 6 deletions

View File

@ -150,10 +150,9 @@ void AP_MotorsTri::output_armed_not_stabilizing()
limit.throttle_lower = false;
limit.throttle_upper = false;
int16_t min_thr = rel_pwm_to_thr_range(_spin_when_armed_ramped);
if (_throttle_control_input <= min_thr) {
_throttle_control_input = min_thr;
int16_t thr_in_min = rel_pwm_to_thr_range(_spin_when_armed_ramped);
if (_throttle_control_input <= thr_in_min) {
_throttle_control_input = thr_in_min;
limit.throttle_lower = true;
}
@ -203,8 +202,9 @@ void AP_MotorsTri::output_armed_stabilizing()
limit.throttle_upper = false;
// Throttle is 0 to 1000 only
if (_throttle_control_input <= 0) {
_throttle_control_input = 0;
int16_t thr_in_min = rel_pwm_to_thr_range(_min_throttle);
if (_throttle_control_input <= thr_in_min) {
_throttle_control_input = thr_in_min;
limit.throttle_lower = true;
}
if (_throttle_control_input >= _max_throttle) {