SITL: correct buffer size in SIM_FETtecOneWireESC read

no need to subtract one here; read enough bytes to fill the buffer
This commit is contained in:
Peter Barker 2025-01-13 15:49:14 +11:00 committed by Peter Barker
parent ca4ffb58a1
commit 61eea7e11c

View File

@ -384,7 +384,7 @@ void FETtecOneWireESC::consume_bytes(uint8_t count)
void FETtecOneWireESC::update_input()
{
const ssize_t n = read_from_autopilot((char*)&u.buffer[buflen], ARRAY_SIZE(u.buffer) - buflen - 1);
const ssize_t n = read_from_autopilot((char*)&u.buffer[buflen], ARRAY_SIZE(u.buffer) - buflen);
if (n < 0) {
// TODO: do better here
if (errno != EAGAIN && errno != EWOULDBLOCK && errno != 0) {