From 52f2fce1d5354f267fcd638c698243987bfadc62 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 30 Nov 2015 21:53:54 +1100 Subject: [PATCH] RC_Channel: prevent float exception with bad RCn_MIN/MAX/TRIM thanks to Michael for finding this --- libraries/RC_Channel/RC_Channel.cpp | 6 ++++++ 1 file changed, 6 insertions(+) diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index 37de7a2913..11b620b403 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -370,8 +370,14 @@ RC_Channel::norm_input() float ret; int16_t reverse_mul = (_reverse==-1?-1:1); if (radio_in < radio_trim) { + if (radio_min >= radio_trim) { + return 0.0f; + } ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_trim - radio_min); } else { + if (radio_max <= radio_trim) { + return 0.0f; + } ret = reverse_mul * (float)(radio_in - radio_trim) / (float)(radio_max - radio_trim); } return constrain_float(ret, -1.0f, 1.0f);