HAL_ChibiOS: moved uart locking up to AP_HAL

and removed set_blocking_writes
This commit is contained in:
Andrew Tridgell 2023-07-10 06:56:59 +10:00
parent 4f81a40066
commit 8fd5341b5b
2 changed files with 20 additions and 171 deletions

View File

@ -229,7 +229,7 @@ static int hal_console_vprintf(const char *fmt, va_list arg)
}
#endif
void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
void UARTDriver::_begin(uint32_t b, uint16_t rxS, uint16_t txS)
{
thread_rx_init();
@ -599,23 +599,7 @@ __RAMFUNC__ void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
}
#endif // HAL_UART_NODMA
void UARTDriver::begin(uint32_t b)
{
if (lock_write_key != 0) {
return;
}
begin(b, 0, 0);
}
void UARTDriver::begin_locked(uint32_t b, uint32_t key)
{
if (lock_write_key != 0 && key != lock_write_key) {
return;
}
begin(b, 0, 0);
}
void UARTDriver::end()
void UARTDriver::_end()
{
while (_in_rx_timer) hal.scheduler->delay(1);
_rx_initialised = false;
@ -637,7 +621,7 @@ void UARTDriver::end()
_writebuf.set_size(0);
}
void UARTDriver::flush()
void UARTDriver::_flush()
{
if (sdef.is_usb) {
#ifdef HAVE_USB_SERIAL
@ -654,11 +638,6 @@ bool UARTDriver::is_initialized()
return _tx_initialised && _rx_initialised;
}
void UARTDriver::set_blocking_writes(bool blocking)
{
_blocking_writes = blocking;
}
bool UARTDriver::tx_pending() { return _writebuf.available() > 0; }
@ -675,19 +654,11 @@ uint32_t UARTDriver::get_usb_baud() const
return 0;
}
uint32_t UARTDriver::available() {
uint32_t UARTDriver::_available()
{
if (!_rx_initialised || _uart_owner_thd != chThdGetSelfX()) {
return 0;
}
return UARTDriver::available_locked(0);
}
uint32_t UARTDriver::available_locked(uint32_t key)
{
if (lock_read_key != 0 && key != lock_read_key) {
return -1;
}
if (sdef.is_usb) {
#ifdef HAVE_USB_SERIAL
@ -707,9 +678,9 @@ uint32_t UARTDriver::txspace()
return _writebuf.space();
}
bool UARTDriver::discard_input()
bool UARTDriver::_discard_input()
{
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
if (_uart_owner_thd != chThdGetSelfX()){
return false;
}
if (!_rx_initialised) {
@ -725,9 +696,9 @@ bool UARTDriver::discard_input()
return true;
}
ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
ssize_t UARTDriver::_read(uint8_t *buffer, uint16_t count)
{
if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
if (_uart_owner_thd != chThdGetSelfX()){
return -1;
}
if (!_rx_initialised) {
@ -746,84 +717,13 @@ ssize_t UARTDriver::read(uint8_t *buffer, uint16_t count)
return ret;
}
bool UARTDriver::read(uint8_t &b)
{
if (_uart_owner_thd != chThdGetSelfX()) {
return false;
}
return UARTDriver::read_locked(0, b);
}
bool UARTDriver::read_locked(uint32_t key, uint8_t &b)
{
if (lock_read_key != 0 && key != lock_read_key) {
return false;
}
if (!_rx_initialised) {
return false;
}
uint8_t byte;
if (!_readbuf.read_byte(&byte)) {
return false;
}
if (!_rts_is_active) {
update_rts_line();
}
b = byte;
return true;
}
/* write one byte to the port */
size_t UARTDriver::write(uint8_t c)
{
if (lock_write_key != 0) {
return 0;
}
_write_mutex.take_blocking();
if (!_tx_initialised) {
_write_mutex.give();
return 0;
}
while (_writebuf.space() == 0) {
if (!_blocking_writes || unbuffered_writes) {
_write_mutex.give();
return 0;
}
// release the semaphore while sleeping
_write_mutex.give();
hal.scheduler->delay(1);
_write_mutex.take_blocking();
}
size_t ret = _writebuf.write(&c, 1);
if (unbuffered_writes) {
chEvtSignal(uart_thread_ctx, EVT_TRANSMIT_DATA_READY);
}
_write_mutex.give();
return ret;
}
/* write a block of bytes to the port */
size_t UARTDriver::write(const uint8_t *buffer, size_t size)
size_t UARTDriver::_write(const uint8_t *buffer, size_t size)
{
if (!_tx_initialised || lock_write_key != 0) {
if (!_tx_initialised) {
return 0;
}
if (_blocking_writes && !unbuffered_writes) {
/*
use the per-byte delay loop in write() above for blocking writes
*/
size_t ret = 0;
while (size--) {
if (write(*buffer++) != 1) break;
ret++;
}
return ret;
}
WITH_SEMAPHORE(_write_mutex);
size_t ret = _writebuf.write(buffer, size);
@ -833,37 +733,6 @@ size_t UARTDriver::write(const uint8_t *buffer, size_t size)
return ret;
}
/*
lock the uart for exclusive use by write_locked() and read_locked() with the right key
*/
bool UARTDriver::lock_port(uint32_t write_key, uint32_t read_key)
{
if (lock_write_key && write_key != lock_write_key && read_key != 0) {
// someone else is using it
return false;
}
if (lock_read_key && read_key != lock_read_key && read_key != 0) {
// someone else is using it
return false;
}
lock_write_key = write_key;
lock_read_key = read_key;
return true;
}
/*
write to a locked port. If port is locked and key is not correct then 0 is returned
and write is discarded. All writes are non-blocking
*/
size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key)
{
if (lock_write_key != 0 && key != lock_write_key) {
return 0;
}
WITH_SEMAPHORE(_write_mutex);
return _writebuf.write(buffer, size);
}
/*
wait for data to arrive, or a timeout. Return true if data has
arrived, false on timeout

View File

@ -35,48 +35,24 @@ public:
/* Do not allow copies */
CLASS_NO_COPY(UARTDriver);
void begin(uint32_t b) override;
void begin_locked(uint32_t b, uint32_t write_key) override;
void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void end() override;
void flush() override;
bool is_initialized() override;
void set_blocking_writes(bool blocking) override;
bool tx_pending() override;
uint32_t get_usb_baud() const override;
// disable TX/RX pins for unusued uart
void disable_rxtx(void) const override;
uint32_t available() override;
uint32_t available_locked(uint32_t key) override;
uint32_t txspace() override;
bool read(uint8_t &data) override WARN_IF_UNUSED;
ssize_t read(uint8_t *buffer, uint16_t count) override;
bool read_locked(uint32_t key, uint8_t &b) override WARN_IF_UNUSED;
void _rx_timer_tick(void);
void _tx_timer_tick(void);
#if HAL_FORWARD_OTG2_SERIAL
void fwd_otg2_serial(void);
#endif
bool discard_input() override;
size_t write(uint8_t c) override;
size_t write(const uint8_t *buffer, size_t size) override;
// lock a port for exclusive use. Use a key of 0 to unlock
bool lock_port(uint32_t write_key, uint32_t read_key) override;
// control optional features
bool set_options(uint16_t options) override;
uint16_t get_options(void) const override;
// write to a locked port. If port is locked and key is not correct then 0 is returned
// and write is discarded
size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
struct SerialDef {
BaseSequentialStream* serial;
uint8_t instance;
@ -181,10 +157,6 @@ private:
// index into uart_drivers table
uint8_t serial_num;
// key for a locked port
uint32_t lock_write_key;
uint32_t lock_read_key;
uint32_t _baudrate;
#if HAL_USE_SERIAL == TRUE
SerialConfig sercfg;
@ -215,7 +187,6 @@ private:
#endif
volatile bool _in_rx_timer;
volatile bool _in_tx_timer;
bool _blocking_writes;
volatile bool _rx_initialised;
volatile bool _tx_initialised;
volatile bool _device_initialised;
@ -295,6 +266,15 @@ private:
void uart_thread();
static void uart_rx_thread(void* arg);
static void uart_thread_trampoline(void* p);
protected:
void _begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
void _end() override;
void _flush() override;
size_t _write(const uint8_t *buffer, size_t size) override;
ssize_t _read(uint8_t *buffer, uint16_t count) override;
uint32_t _available() override;
bool _discard_input() override;
};
// access to usb init for stdio.cpp