mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Linux: 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
394d70abe0
commit
a10f5dbd0a
|
@ -281,18 +281,17 @@ uint32_t UARTDriver::txspace()
|
|||
return _writebuf.space();
|
||||
}
|
||||
|
||||
int16_t UARTDriver::read()
|
||||
bool UARTDriver::read(uint8_t &byte)
|
||||
{
|
||||
if (!_initialised) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t byte;
|
||||
if (!_readbuf.read_byte(&byte)) {
|
||||
return -1;
|
||||
return false;
|
||||
}
|
||||
|
||||
return byte;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool UARTDriver::discard_input()
|
||||
|
|
|
@ -29,7 +29,7 @@ public:
|
|||
/* Linux 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;
|
||||
|
||||
bool discard_input() override;
|
||||
|
||||
|
|
Loading…
Reference in New Issue