mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_Empty: 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
130f2c3bc8
commit
d601d83b4b
|
@ -15,7 +15,7 @@ bool Empty::UARTDriver::tx_pending() { return false; }
|
|||
/* Empty implementations of Stream virtual methods */
|
||||
uint32_t Empty::UARTDriver::available() { return 0; }
|
||||
uint32_t Empty::UARTDriver::txspace() { return 1; }
|
||||
int16_t Empty::UARTDriver::read() { return -1; }
|
||||
bool Empty::UARTDriver::read(uint8_t &b) { return false; }
|
||||
bool Empty::UARTDriver::discard_input() { return false; }
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
|
|
|
@ -17,7 +17,7 @@ public:
|
|||
/* Empty 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;
|
||||
|
||||
/* Empty implementations of Print virtual methods */
|
||||
|
|
Loading…
Reference in New Issue