mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-22 00:28:30 -04:00
AP_HAL_SITL: add and use a "bool read(c)" method to AP_HAL
this is much less likely to not work vs the int16_t equivalent
This commit is contained in:
parent
a10f5dbd0a
commit
d626197c0b
@ -219,13 +219,12 @@ uint32_t UARTDriver::txspace(void)
|
||||
return _writebuffer.space();
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read(void)
|
||||
bool UARTDriver::read(uint8_t &c)
|
||||
{
|
||||
uint8_t c;
|
||||
if (read(&c, 1) == 0) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
return c;
|
||||
return true;
|
||||
}
|
||||
|
||||
ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
|
||||
|
@ -50,7 +50,7 @@ public:
|
||||
/* Implementations of Stream virtual methods */
|
||||
uint32_t available() override;
|
||||
uint32_t txspace() override;
|
||||
int16_t read() override;
|
||||
bool read(uint8_t &b) override WARN_IF_UNUSED;
|
||||
ssize_t read(uint8_t *buffer, uint16_t count) override;
|
||||
|
||||
bool discard_input() override;
|
||||
|
Loading…
Reference in New Issue
Block a user