From 708124183dc20ea3ade13332ac3d67a11e129337 Mon Sep 17 00:00:00 2001 From: Peter Barker Date: Wed, 15 Mar 2023 17:19:07 +1100 Subject: [PATCH] AP_EFI: use uint16_t to store offset prevents infinite loop if there are exactly 255 bytes ready to read --- libraries/AP_EFI/AP_EFI_Serial_MS.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp index 1d8d40f067..d5e144e654 100644 --- a/libraries/AP_EFI/AP_EFI_Serial_MS.cpp +++ b/libraries/AP_EFI/AP_EFI_Serial_MS.cpp @@ -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) {