diff --git a/libraries/RC_Channel/RC_Channel.cpp b/libraries/RC_Channel/RC_Channel.cpp index cdfe56c36f..a7f499ef4e 100644 --- a/libraries/RC_Channel/RC_Channel.cpp +++ b/libraries/RC_Channel/RC_Channel.cpp @@ -414,7 +414,7 @@ bool RC_Channel::read_6pos_switch(int8_t& position) { // calculate position of 6 pos switch const uint16_t pulsewidth = get_radio_in(); - if (pulsewidth <= 900 || pulsewidth >= 2200) { + if (pulsewidth <= RC_MIN_LIMIT_PWM || pulsewidth >= RC_MAX_LIMIT_PWM) { return false; // This is an error condition } @@ -1195,7 +1195,7 @@ void RC_Channel::init_aux() bool RC_Channel::read_3pos_switch(RC_Channel::AuxSwitchPos &ret) const { const uint16_t in = get_radio_in(); - if (in <= 900 or in >= 2200) { + if (in <= RC_MIN_LIMIT_PWM or in >= RC_MAX_LIMIT_PWM) { return false; } diff --git a/libraries/RC_Channel/RC_Channel.h b/libraries/RC_Channel/RC_Channel.h index e26f3bff5d..8de839ee47 100644 --- a/libraries/RC_Channel/RC_Channel.h +++ b/libraries/RC_Channel/RC_Channel.h @@ -257,6 +257,11 @@ public: #if !HAL_MINIMIZE_FEATURES const char *string_for_aux_function(AUX_FUNC function) const; #endif + // pwm value under which we consider that Radio value is invalid + static const uint16_t RC_MIN_LIMIT_PWM = 900; + // pwm value above which we consider that Radio value is invalid + static const uint16_t RC_MAX_LIMIT_PWM = 2200; + // pwm value above which we condider that Radio min value is invalid static const uint16_t RC_CALIB_MIN_LIMIT_PWM = 1300; // pwm value under which we condider that Radio max value is invalid