RC_Channel: update RC_MIN_LIMIT_PWM from 900 to 800

This commit is contained in:
Iampete1 2022-02-15 00:35:51 +00:00 committed by Andrew Tridgell
parent c26ffed47f
commit a47445bde9

View File

@ -274,7 +274,7 @@ public:
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;
static const uint16_t RC_MIN_LIMIT_PWM = 800;
// pwm value above which we consider that Radio value is invalid
static const uint16_t RC_MAX_LIMIT_PWM = 2200;