mirror of https://github.com/ArduPilot/ardupilot
RC_Channel: fixed bug in manual with TRIM == MIN
This fixes the bug described here: https://discuss.ardupilot.org/t/arduplane-reverse-thrust-setup/18324/5 which otherwise would prevent output with TRIM == MIN or TRIM == MAX
This commit is contained in:
parent
1b6d20db7f
commit
992baa7026
|
@ -187,14 +187,10 @@ RC_Channel::pwm_to_angle_dz_trim(uint16_t _dead_zone, uint16_t _trim)
|
|||
int16_t radio_trim_high = _trim + _dead_zone;
|
||||
int16_t radio_trim_low = _trim - _dead_zone;
|
||||
|
||||
// prevent div by 0
|
||||
if ((radio_trim_low - radio_min) == 0 || (radio_max - radio_trim_high) == 0)
|
||||
return 0;
|
||||
|
||||
int16_t reverse_mul = (reversed?-1:1);
|
||||
if (radio_in > radio_trim_high) {
|
||||
if (radio_in > radio_trim_high && radio_max != radio_trim_high) {
|
||||
return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_high)) / (int32_t)(radio_max - radio_trim_high);
|
||||
} else if (radio_in < radio_trim_low) {
|
||||
} else if (radio_in < radio_trim_low && radio_trim_low != radio_min) {
|
||||
return reverse_mul * ((int32_t)high_in * (int32_t)(radio_in - radio_trim_low)) / (int32_t)(radio_trim_low - radio_min);
|
||||
} else {
|
||||
return 0;
|
||||
|
|
Loading…
Reference in New Issue