diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp index 806947a3b4..0d21e4614f 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.cpp @@ -179,7 +179,7 @@ bool AP_Proximity_RPLidarA2::make_first_byte_in_payload(uint8_t desired_byte) if (_payload[0] == desired_byte) { return true; } - for (uint8_t i=1; i<_byte_count; i++) { + for (auto i=1; i<_byte_count; i++) { if (_payload[i] == desired_byte) { consume_bytes(i); return true; diff --git a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h index 5f44ba0e33..30da07b52e 100644 --- a/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h +++ b/libraries/AP_Proximity/AP_Proximity_RPLidarA2.h @@ -143,7 +143,7 @@ private: _descriptor descriptor; _rpi_information information; _device_info device_info; - uint8_t forced_buffer_size[128]; // just so we read(...) efficiently + uint8_t forced_buffer_size[256]; // just so we read(...) efficiently } _payload; static_assert(sizeof(_payload) >= 63, "Needed for parsing out reboot data");