mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-02-21 23:33:57 -04:00
HAL_Linux: prevent read past end of buffer
This commit is contained in:
parent
7286e7acd2
commit
b4be93113c
@ -193,7 +193,7 @@ void LinuxUARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
|
||||
if (_writebuf != NULL) {
|
||||
free(_writebuf);
|
||||
}
|
||||
_writebuf = (uint8_t *)malloc(_writebuf_size+16);
|
||||
_writebuf = (uint8_t *)malloc(_writebuf_size);
|
||||
_writebuf_head = 0;
|
||||
_writebuf_tail = 0;
|
||||
}
|
||||
@ -565,7 +565,7 @@ void LinuxUARTDriver::_timer_tick(void)
|
||||
// split into two writes
|
||||
uint16_t n1 = _writebuf_size - _writebuf_head;
|
||||
int ret = _write_fd(&_writebuf[_writebuf_head], n1);
|
||||
if (ret == n1 && n != n1) {
|
||||
if (ret == n1 && n > n1) {
|
||||
_write_fd(&_writebuf[_writebuf_head], n - n1);
|
||||
}
|
||||
}
|
||||
@ -583,7 +583,7 @@ void LinuxUARTDriver::_timer_tick(void)
|
||||
uint16_t n1 = _readbuf_size - _readbuf_tail;
|
||||
assert(_readbuf_tail+n1 <= _readbuf_size);
|
||||
int ret = _read_fd(&_readbuf[_readbuf_tail], n1);
|
||||
if (ret == n1 && n != n1) {
|
||||
if (ret == n1 && n > n1) {
|
||||
assert(_readbuf_tail+(n-n1) <= _readbuf_size);
|
||||
_read_fd(&_readbuf[_readbuf_tail], n - n1);
|
||||
}
|
||||
|
Loading…
Reference in New Issue
Block a user