mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-03-13 10:03:57 -03:00
AP_HAL_SITL: implement read(buf, length)
This commit is contained in:
parent
40ec8c723b
commit
a52e823967
@ -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();
|
||||
|
@ -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;
|
||||
|
||||
|
Loading…
Reference in New Issue
Block a user