AP_HAL_ESP32: moved UART port locking up to AP_HAL

This commit is contained in:
Andrew Tridgell 2023-07-07 18:46:52 +10:00
parent 66e5ea0b1b
commit 3caf52a841
6 changed files with 53 additions and 136 deletions

View File

@ -36,13 +36,7 @@ void UARTDriver::vprintf(const char *fmt, va_list ap)
} }
} }
void UARTDriver::begin(uint32_t b) void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
begin(b, 0, 0);
}
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{ {
if (uart_num < ARRAY_SIZE(uart_desc)) { if (uart_num < ARRAY_SIZE(uart_desc)) {
uart_port_t p = uart_desc[uart_num].port; uart_port_t p = uart_desc[uart_num].port;
@ -75,7 +69,7 @@ void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
_baudrate = b; _baudrate = b;
} }
void UARTDriver::end() void UARTDriver::_end()
{ {
if (_initialized) { if (_initialized) {
uart_driver_delete(uart_desc[uart_num].port); uart_driver_delete(uart_desc[uart_num].port);
@ -85,7 +79,7 @@ void UARTDriver::end()
_initialized = false; _initialized = false;
} }
void UARTDriver::flush() void UARTDriver::_flush()
{ {
uart_port_t p = uart_desc[uart_num].port; uart_port_t p = uart_desc[uart_num].port;
uart_flush(p); uart_flush(p);
@ -96,18 +90,13 @@ bool UARTDriver::is_initialized()
return _initialized; return _initialized;
} }
void UARTDriver::set_blocking_writes(bool blocking)
{
//blocking writes do not used anywhere
}
bool UARTDriver::tx_pending() bool UARTDriver::tx_pending()
{ {
return (_writebuf.available() > 0); return (_writebuf.available() > 0);
} }
uint32_t UARTDriver::available() uint32_t UARTDriver::_available()
{ {
if (!_initialized) { if (!_initialized) {
return 0; return 0;
@ -126,7 +115,7 @@ uint32_t UARTDriver::txspace()
} }
ssize_t IRAM_ATTR UARTDriver::read(uint8_t *buffer, uint16_t count) ssize_t IRAM_ATTR UARTDriver::_read(uint8_t *buffer, uint16_t count)
{ {
if (!_initialized) { if (!_initialized) {
return -1; return -1;
@ -143,22 +132,6 @@ ssize_t IRAM_ATTR UARTDriver::read(uint8_t *buffer, uint16_t count)
return ret; return ret;
} }
bool IRAM_ATTR UARTDriver::read(uint8_t &byte)
{
if (!_initialized) {
return false;
}
if (!_readbuf.read_byte(&byte)) {
return false;
}
_receive_timestamp_update();
return true;
}
void IRAM_ATTR UARTDriver::_timer_tick(void) void IRAM_ATTR UARTDriver::_timer_tick(void)
{ {
if (!_initialized) { if (!_initialized) {
@ -195,12 +168,7 @@ void IRAM_ATTR UARTDriver::write_data()
_write_mutex.give(); _write_mutex.give();
} }
size_t IRAM_ATTR UARTDriver::write(uint8_t c) size_t IRAM_ATTR UARTDriver::_write(const uint8_t *buffer, size_t size)
{
return write(&c,1);
}
size_t IRAM_ATTR UARTDriver::write(const uint8_t *buffer, size_t size)
{ {
if (!_initialized) { if (!_initialized) {
return 0; return 0;
@ -214,7 +182,7 @@ size_t IRAM_ATTR UARTDriver::write(const uint8_t *buffer, size_t size)
return ret; return ret;
} }
bool UARTDriver::discard_input() bool UARTDriver::_discard_input()
{ {
//uart_port_t p = uart_desc[uart_num].port; //uart_port_t p = uart_desc[uart_num].port;
//return uart_flush_input(p) == ESP_OK; //return uart_flush_input(p) == ESP_OK;

View File

@ -47,39 +47,18 @@ public:
void vprintf(const char *fmt, va_list ap) override; void vprintf(const char *fmt, va_list ap) override;
void begin(uint32_t b) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override; bool is_initialized() override;
void set_blocking_writes(bool blocking) override;
bool tx_pending() override; bool tx_pending() override;
uint32_t available() override;
//uint32_t available_locked(uint32_t key) override;
uint32_t txspace() override; uint32_t txspace() override;
ssize_t read(uint8_t *buffer, uint16_t count) 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;
void _timer_tick(void) override; void _timer_tick(void) override;
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;
bool discard_input() override; // discard all bytes available for reading
uint32_t bw_in_bytes_per_second() const override uint32_t bw_in_bytes_per_second() const override
{ {
return 10*1024; return 10*1024;
} }
//bool lock_port(uint32_t write_key, uint32_t read_key) override;
//size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
//
/* /*
return timestamp estimate in microseconds for when the start of return timestamp estimate in microseconds for when the start of
a nbytes packet arrived on the uart. This should be treated as a a nbytes packet arrived on the uart. This should be treated as a
@ -111,6 +90,15 @@ private:
uint32_t _baudrate; uint32_t _baudrate;
void _receive_timestamp_update(void); void _receive_timestamp_update(void);
protected:
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void _end() override;
void _flush() override;
uint32_t _available() override;
ssize_t _read(uint8_t *buffer, uint16_t count) override;
size_t _write(const uint8_t *buffer, size_t size) override;
bool _discard_input() override; // discard all bytes available for reading
}; };
} }

View File

@ -45,12 +45,7 @@ WiFiDriver::WiFiDriver()
} }
} }
void WiFiDriver::begin(uint32_t b) void WiFiDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
begin(b, 0, 0);
}
void WiFiDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{ {
if (_state == NOT_INITIALIZED) { if (_state == NOT_INITIALIZED) {
initialize_wifi(); initialize_wifi();
@ -67,12 +62,12 @@ void WiFiDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
} }
} }
void WiFiDriver::end() void WiFiDriver::_end()
{ {
//TODO //TODO
} }
void WiFiDriver::flush() void WiFiDriver::_flush()
{ {
} }
@ -81,17 +76,12 @@ bool WiFiDriver::is_initialized()
return _state != NOT_INITIALIZED; return _state != NOT_INITIALIZED;
} }
void WiFiDriver::set_blocking_writes(bool blocking)
{
//blocking writes do not used anywhere
}
bool WiFiDriver::tx_pending() bool WiFiDriver::tx_pending()
{ {
return (_writebuf.available() > 0); return (_writebuf.available() > 0);
} }
uint32_t WiFiDriver::available() uint32_t WiFiDriver::_available()
{ {
if (_state != CONNECTED) { if (_state != CONNECTED) {
return 0; return 0;
@ -109,15 +99,12 @@ uint32_t WiFiDriver::txspace()
return MAX(result, 0); return MAX(result, 0);
} }
bool WiFiDriver::read(uint8_t &byte) ssize_t WiFiDriver::_read(uint8_t *buf, uint16_t count)
{ {
if (_state != CONNECTED) { if (_state != CONNECTED) {
return false; return 0;
} }
if (!_readbuf.read_byte(&byte)) { return _readbuf.read(buf, count);
return false;
}
return true;
} }
bool WiFiDriver::start_listen() bool WiFiDriver::start_listen()
@ -243,12 +230,7 @@ void WiFiDriver::initialize_wifi()
esp_wifi_start(); esp_wifi_start();
} }
size_t WiFiDriver::write(uint8_t c) size_t WiFiDriver::_write(const uint8_t *buffer, size_t size)
{
return write(&c,1);
}
size_t WiFiDriver::write(const uint8_t *buffer, size_t size)
{ {
if (_state != CONNECTED) { if (_state != CONNECTED) {
return 0; return 0;
@ -290,7 +272,7 @@ void WiFiDriver::_wifi_thread(void *arg)
} }
} }
bool WiFiDriver::discard_input() bool WiFiDriver::_discard_input()
{ {
return false; return false;
} }

View File

@ -33,30 +33,18 @@ class ESP32::WiFiDriver : public AP_HAL::UARTDriver
public: public:
WiFiDriver(); WiFiDriver();
void begin(uint32_t b) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override; bool is_initialized() override;
void set_blocking_writes(bool blocking) override;
bool tx_pending() override; bool tx_pending() override;
uint32_t available() override;
uint32_t txspace() override; uint32_t txspace() 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;
uint32_t bw_in_bytes_per_second() const override uint32_t bw_in_bytes_per_second() const override
{ {
return 1000*1024; return 1000*1024;
} }
bool discard_input() override;
bool _more_data; bool _more_data;
private: private:
enum ConnectionState { enum ConnectionState {
NOT_INITIALIZED, NOT_INITIALIZED,
@ -80,4 +68,13 @@ private:
bool try_accept(); bool try_accept();
static void _wifi_thread(void* arg); static void _wifi_thread(void* arg);
unsigned short available_socket(); unsigned short available_socket();
protected:
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
size_t _write(const uint8_t *buffer, size_t size) override;
ssize_t _read(uint8_t *buffer, uint16_t size) override;
void _end() override;
void _flush() override;
bool _discard_input() override;
uint32_t _available() override;
}; };

View File

@ -44,12 +44,7 @@ WiFiUdpDriver::WiFiUdpDriver()
accept_socket = -1; accept_socket = -1;
} }
void WiFiUdpDriver::begin(uint32_t b) void WiFiUdpDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
begin(b, 0, 0);
}
void WiFiUdpDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
{ {
if (_state == NOT_INITIALIZED) { if (_state == NOT_INITIALIZED) {
initialize_wifi(); initialize_wifi();
@ -69,12 +64,12 @@ void WiFiUdpDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
} }
} }
void WiFiUdpDriver::end() void WiFiUdpDriver::_end()
{ {
//TODO //TODO
} }
void WiFiUdpDriver::flush() void WiFiUdpDriver::_flush()
{ {
} }
@ -83,17 +78,12 @@ bool WiFiUdpDriver::is_initialized()
return true; return true;
} }
void WiFiUdpDriver::set_blocking_writes(bool blocking)
{
//blocking writes do not used anywhere
}
bool WiFiUdpDriver::tx_pending() bool WiFiUdpDriver::tx_pending()
{ {
return (_writebuf.available() > 0); return (_writebuf.available() > 0);
} }
uint32_t WiFiUdpDriver::available() uint32_t WiFiUdpDriver::_available()
{ {
return _readbuf.available(); return _readbuf.available();
} }
@ -105,18 +95,16 @@ uint32_t WiFiUdpDriver::txspace()
return MAX(result, 0); return MAX(result, 0);
} }
bool WiFiUdpDriver::read(uint8_t &c) ssize_t WiFiUdpDriver::_read(uint8_t *buf, uint16_t count)
{ {
if (!_read_mutex.take_nonblocking()) { if (!_read_mutex.take_nonblocking()) {
return false; return false;
} }
if (!_readbuf.read_byte(&c)) { auto ret = _readbuf.read(buf, count);
return false;
}
_read_mutex.give(); _read_mutex.give();
return true; return ret;
} }
bool WiFiUdpDriver::start_listen() bool WiFiUdpDriver::start_listen()
@ -212,12 +200,7 @@ void WiFiUdpDriver::initialize_wifi()
esp_wifi_start(); esp_wifi_start();
} }
size_t WiFiUdpDriver::write(uint8_t c) size_t WiFiUdpDriver::_write(const uint8_t *buffer, size_t size)
{
return write(&c,1);
}
size_t WiFiUdpDriver::write(const uint8_t *buffer, size_t size)
{ {
if (!_write_mutex.take_nonblocking()) { if (!_write_mutex.take_nonblocking()) {
return 0; return 0;
@ -247,7 +230,7 @@ void WiFiUdpDriver::_wifi_thread2(void *arg)
} }
} }
bool WiFiUdpDriver::discard_input() bool WiFiUdpDriver::_discard_input()
{ {
return false; return false;
} }

View File

@ -28,20 +28,11 @@ class ESP32::WiFiUdpDriver : public AP_HAL::UARTDriver
public: public:
WiFiUdpDriver(); WiFiUdpDriver();
void begin(uint32_t b) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override; bool is_initialized() override;
void set_blocking_writes(bool blocking) override;
bool tx_pending() override; bool tx_pending() override;
uint32_t available() override;
uint32_t txspace() override; uint32_t txspace() 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;
uint32_t bw_in_bytes_per_second() const override uint32_t bw_in_bytes_per_second() const override
{ {
@ -49,7 +40,6 @@ public:
} }
bool discard_input() override;
private: private:
enum ConnectionState { enum ConnectionState {
NOT_INITIALIZED, NOT_INITIALIZED,
@ -74,4 +64,13 @@ private:
bool start_listen(); bool start_listen();
bool try_accept(); bool try_accept();
static void _wifi_thread2(void* arg); static void _wifi_thread2(void* arg);
protected:
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
size_t _write(const uint8_t *buffer, size_t size) override;
ssize_t _read(uint8_t *buf, uint16_t count) override;
uint32_t _available() override;
bool _discard_input() override;
void _end() override;
void _flush() override;
}; };