RC_Channel: prevent floating exception on bad MIN/MAX/TRIM values

This commit is contained in:
Andrew Tridgell 2015-07-27 10:05:33 +10:00 committed by Randy Mackay
parent ffe1561f31
commit 1b1bc9f3b1

View File

@ -428,10 +428,16 @@ RC_Channel::norm_output()
{ {
int16_t mid = (radio_max + radio_min) / 2; int16_t mid = (radio_max + radio_min) / 2;
float ret; float ret;
if(radio_out < mid) if (mid <= radio_min) {
return 0;
}
if (radio_out < mid) {
ret = (float)(radio_out - mid) / (float)(mid - radio_min); ret = (float)(radio_out - mid) / (float)(mid - radio_min);
else } else if (radio_out > mid) {
ret = (float)(radio_out - mid) / (float)(radio_max - mid); ret = (float)(radio_out - mid) / (float)(radio_max - mid);
} else {
ret = 0;
}
if (_reverse == -1) { if (_reverse == -1) {
ret = -ret; ret = -ret;
} }