mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_RCProtocol: correctly process bytes from standalone UART
This commit is contained in:
parent
cca292f222
commit
d7ae8b8bb3
@ -299,7 +299,7 @@ void AP_RCProtocol_CRSF::update(void)
|
||||
for (uint8_t i = 0; i < n; i++) {
|
||||
int16_t b = _uart->read();
|
||||
if (b >= 0) {
|
||||
process_byte(AP_HAL::micros(), uint8_t(b));
|
||||
_process_byte(AP_HAL::micros(), uint8_t(b));
|
||||
}
|
||||
}
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user