HAL_PX4: prevent read past end of buffer

This commit is contained in:
Andrew Tridgell 2014-08-19 09:30:08 +10:00
parent b4be93113c
commit 0a20d0db60

View File

@ -503,7 +503,7 @@ void PX4UARTDriver::_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);
}
}
@ -523,7 +523,7 @@ void PX4UARTDriver::_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);
}