AP_HAL_ESP32: 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:
Peter Barker 2023-02-21 20:35:57 +11:00 committed by Peter Barker
parent d601d83b4b
commit ec40a9641b
6 changed files with 16 additions and 19 deletions

View File

@ -139,16 +139,15 @@ ssize_t IRAM_ATTR UARTDriver::read(uint8_t *buffer, uint16_t count)
return ret;
}
int16_t IRAM_ATTR UARTDriver::read()
bool IRAM_ATTR UARTDriver::read(uint8_t &byte)
{
if (!_initialized) {
return -1;
return false;
}
uint8_t byte;
if (!_readbuf.read_byte(&byte)) {
return -1;
return false;
}
return byte;
return true;
}
void IRAM_ATTR UARTDriver::_timer_tick(void)

View File

@ -61,7 +61,7 @@ public:
uint32_t txspace() override;
ssize_t read(uint8_t *buffer, uint16_t count) override;
int16_t read() override;
bool read(uint8_t &b) override WARN_IF_UNUSED;
//ssize_t read(uint8_t *buffer, uint16_t count) override;
//int16_t read_locked(uint32_t key) override;

View File

@ -103,16 +103,15 @@ uint32_t WiFiDriver::txspace()
return MAX(result, 0);
}
int16_t WiFiDriver::read()
bool WiFiDriver::read(uint8_t &byte)
{
if (_state != CONNECTED) {
return -1;
return false;
}
uint8_t byte;
if (!_readbuf.read_byte(&byte)) {
return -1;
return false;
}
return byte;
return true;
}
bool WiFiDriver::start_listen()

View File

@ -39,7 +39,7 @@ public:
uint32_t available() override;
uint32_t txspace() override;
int16_t read() override;
bool read(uint8_t &c) override;
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;

View File

@ -101,19 +101,18 @@ uint32_t WiFiUdpDriver::txspace()
return MAX(result, 0);
}
int16_t WiFiUdpDriver::read()
bool WiFiUdpDriver::read(uint8_t &c)
{
if (!_read_mutex.take_nonblocking()) {
return 0;
return false;
}
uint8_t byte;
if (!_readbuf.read_byte(&byte)) {
return -1;
if (!_readbuf.read_byte(&c)) {
return false;
}
_read_mutex.give();
return byte;
return true;
}
bool WiFiUdpDriver::start_listen()

View File

@ -38,7 +38,7 @@ public:
uint32_t available() override;
uint32_t txspace() override;
int16_t read() override;
bool read(uint8_t &c) override;
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;