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:
Peter Barker 2023-03-15 17:19:07 +11:00 committed by Andrew Tridgell
parent 578ebcc5f3
commit 29b4bbb58f
1 changed files with 1 additions and 1 deletions

View File

@ -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) {