mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-02 05:58:30 -04:00
AP_HAL_AVR: fixed bounds check for rc input
This commit is contained in:
parent
a79adcb7f4
commit
31bb300f81
@ -84,7 +84,7 @@ static inline uint16_t constrain_pulse(uint16_t p) {
|
||||
|
||||
uint16_t APM1RCInput::read(uint8_t ch) {
|
||||
/* constrain ch */
|
||||
if (ch < AVR_RC_INPUT_NUM_CHANNELS) return 0;
|
||||
if (ch >= AVR_RC_INPUT_NUM_CHANNELS) return 0;
|
||||
/* grab channel from isr's memory in critical section*/
|
||||
cli();
|
||||
uint16_t capt = _pulse_capt[ch];
|
||||
|
@ -84,7 +84,7 @@ static inline uint16_t constrain_pulse(uint16_t p) {
|
||||
|
||||
uint16_t APM2RCInput::read(uint8_t ch) {
|
||||
/* constrain ch */
|
||||
if (ch < AVR_RC_INPUT_NUM_CHANNELS) return 0;
|
||||
if (ch >= AVR_RC_INPUT_NUM_CHANNELS) return 0;
|
||||
/* grab channel from isr's memory in critical section*/
|
||||
cli();
|
||||
uint16_t capt = _pulse_capt[ch];
|
||||
|
Loading…
Reference in New Issue
Block a user