mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-03 06:28:27 -04:00
AP_EFI: use uint16_t to store offset
prevents infinite loop if there are exactly 255 bytes ready to read
This commit is contained in:
parent
440db27807
commit
3bc42b888f
@ -81,7 +81,7 @@ bool AP_EFI_Serial_MS::read_incoming_realtime_data()
|
||||
}
|
||||
|
||||
// Iterate over the payload bytes
|
||||
for ( uint8_t offset=RT_FIRST_OFFSET; offset < (RT_FIRST_OFFSET + message_length - 1); offset++) {
|
||||
for (uint16_t offset=RT_FIRST_OFFSET; offset < (RT_FIRST_OFFSET + message_length - 1); offset++) {
|
||||
uint8_t data = read_byte_CRC32();
|
||||
float temp_float;
|
||||
switch (offset) {
|
||||
|
Loading…
Reference in New Issue
Block a user