mirror of https://github.com/ArduPilot/ardupilot
AP_Proximity: increase RPLidar read buffer size
128 bytes at 50Hz is not enough to read all data from device
This commit is contained in:
parent
206f663e38
commit
36b494a057
|
@ -179,7 +179,7 @@ bool AP_Proximity_RPLidarA2::make_first_byte_in_payload(uint8_t desired_byte)
|
||||||
if (_payload[0] == desired_byte) {
|
if (_payload[0] == desired_byte) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
for (uint8_t i=1; i<_byte_count; i++) {
|
for (auto i=1; i<_byte_count; i++) {
|
||||||
if (_payload[i] == desired_byte) {
|
if (_payload[i] == desired_byte) {
|
||||||
consume_bytes(i);
|
consume_bytes(i);
|
||||||
return true;
|
return true;
|
||||||
|
|
|
@ -143,7 +143,7 @@ private:
|
||||||
_descriptor descriptor;
|
_descriptor descriptor;
|
||||||
_rpi_information information;
|
_rpi_information information;
|
||||||
_device_info device_info;
|
_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;
|
} _payload;
|
||||||
static_assert(sizeof(_payload) >= 63, "Needed for parsing out reboot data");
|
static_assert(sizeof(_payload) >= 63, "Needed for parsing out reboot data");
|
||||||
|
|
||||||
|
|
Loading…
Reference in New Issue