AP_HAL_SITL: implement read(buf, length)

This commit is contained in:
Peter Barker 2021-07-08 17:10:23 +10:00 committed by Peter Barker
parent 40ec8c723b
commit a52e823967
2 changed files with 8 additions and 3 deletions

View File

@ -180,14 +180,18 @@ uint32_t UARTDriver::txspace(void)
int16_t UARTDriver::read(void)
{
if (available() <= 0) {
uint8_t c;
if (read(&c, 1) == 0) {
return -1;
}
uint8_t c;
_readbuffer.read(&c, 1);
return c;
}
ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
{
return _readbuffer.read(buffer, count);
}
bool UARTDriver::discard_input(void)
{
_readbuffer.clear();

View File

@ -48,6 +48,7 @@ public:
uint32_t available() override;
uint32_t txspace() override;
int16_t read() override;
ssize_t read(uint8_t *buffer, uint16_t count) override;
bool discard_input() override;