2018-01-05 02:19:51 -04:00
|
|
|
/*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
2019-10-20 10:31:12 -03:00
|
|
|
*
|
2018-01-05 02:19:51 -04:00
|
|
|
* Code by Andrew Tridgell and Siddharth Bharat Purohit
|
|
|
|
*/
|
|
|
|
#pragma once
|
|
|
|
|
|
|
|
#include <AP_HAL/utility/RingBuffer.h>
|
|
|
|
|
|
|
|
#include "AP_HAL_ChibiOS.h"
|
|
|
|
#include "shared_dma.h"
|
2018-03-06 18:41:03 -04:00
|
|
|
#include "Semaphores.h"
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2019-12-20 23:39:01 -04:00
|
|
|
#define RX_BOUNCE_BUFSIZE 64U
|
2018-06-26 21:50:57 -03:00
|
|
|
#define TX_BOUNCE_BUFSIZE 64U
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2021-11-05 00:17:39 -03:00
|
|
|
// enough for uartA to uartJ, plus IOMCU
|
|
|
|
#define UART_MAX_DRIVERS 11
|
2018-02-05 22:40:30 -04:00
|
|
|
|
2018-01-13 00:02:05 -04:00
|
|
|
class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
|
2018-01-05 02:19:51 -04:00
|
|
|
public:
|
2018-01-13 00:02:05 -04:00
|
|
|
UARTDriver(uint8_t serial_num);
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
/* Do not allow copies */
|
2022-09-30 06:50:43 -03:00
|
|
|
CLASS_NO_COPY(UARTDriver);
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2018-11-07 06:58:46 -04:00
|
|
|
void begin(uint32_t b) override;
|
2021-07-10 15:16:24 -03:00
|
|
|
void begin_locked(uint32_t b, uint32_t write_key) override;
|
2018-11-07 06:58:46 -04:00
|
|
|
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;
|
2021-07-10 15:16:24 -03:00
|
|
|
uint32_t get_usb_baud() const override;
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2021-11-05 01:33:57 -03:00
|
|
|
// disable TX/RX pins for unusued uart
|
|
|
|
void disable_rxtx(void) const override;
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
uint32_t available() override;
|
2020-05-31 09:18:59 -03:00
|
|
|
uint32_t available_locked(uint32_t key) override;
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
uint32_t txspace() override;
|
|
|
|
int16_t read() override;
|
2020-05-21 02:19:45 -03:00
|
|
|
ssize_t read(uint8_t *buffer, uint16_t count) override;
|
2018-12-19 07:25:41 -04:00
|
|
|
int16_t read_locked(uint32_t key) override;
|
2020-12-05 15:16:27 -04:00
|
|
|
void _rx_timer_tick(void);
|
|
|
|
void _tx_timer_tick(void);
|
2018-01-05 02:19:51 -04:00
|
|
|
|
2020-05-22 21:21:58 -03:00
|
|
|
bool discard_input() override;
|
|
|
|
|
2018-11-07 06:58:46 -04:00
|
|
|
size_t write(uint8_t c) override;
|
|
|
|
size_t write(const uint8_t *buffer, size_t size) override;
|
2018-04-02 03:00:36 -03:00
|
|
|
|
|
|
|
// lock a port for exclusive use. Use a key of 0 to unlock
|
2018-12-19 07:25:41 -04:00
|
|
|
bool lock_port(uint32_t write_key, uint32_t read_key) override;
|
2018-04-02 03:00:36 -03:00
|
|
|
|
2018-11-10 05:45:31 -04:00
|
|
|
// control optional features
|
2020-01-02 21:50:42 -04:00
|
|
|
bool set_options(uint16_t options) override;
|
2021-11-28 05:44:36 -04:00
|
|
|
uint16_t get_options(void) const override;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-04-02 03:00:36 -03:00
|
|
|
// 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;
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
struct SerialDef {
|
|
|
|
BaseSequentialStream* serial;
|
2020-10-27 22:01:14 -03:00
|
|
|
uint8_t instance;
|
2018-01-05 02:19:51 -04:00
|
|
|
bool is_usb;
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-01-05 02:19:51 -04:00
|
|
|
bool dma_rx;
|
|
|
|
uint8_t dma_rx_stream_id;
|
2018-01-10 17:50:25 -04:00
|
|
|
uint32_t dma_rx_channel_id;
|
2018-01-05 02:19:51 -04:00
|
|
|
bool dma_tx;
|
|
|
|
uint8_t dma_tx_stream_id;
|
2019-05-26 22:45:30 -03:00
|
|
|
uint32_t dma_tx_channel_id;
|
|
|
|
#endif
|
2019-12-02 18:56:05 -04:00
|
|
|
ioline_t tx_line;
|
|
|
|
ioline_t rx_line;
|
2018-01-10 17:50:25 -04:00
|
|
|
ioline_t rts_line;
|
2021-02-10 18:11:44 -04:00
|
|
|
ioline_t cts_line;
|
2018-11-10 05:45:31 -04:00
|
|
|
int8_t rxinv_gpio;
|
|
|
|
uint8_t rxinv_polarity;
|
|
|
|
int8_t txinv_gpio;
|
|
|
|
uint8_t txinv_polarity;
|
2021-07-10 15:16:24 -03:00
|
|
|
uint8_t endpoint_id;
|
2018-01-10 17:50:25 -04:00
|
|
|
uint8_t get_index(void) const {
|
|
|
|
return uint8_t(this - &_serial_tab[0]);
|
|
|
|
}
|
2018-01-05 02:19:51 -04:00
|
|
|
};
|
|
|
|
|
|
|
|
bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;
|
|
|
|
|
2018-01-10 17:50:25 -04:00
|
|
|
void set_flow_control(enum flow_control flow_control) override;
|
|
|
|
enum flow_control get_flow_control(void) override { return _flow_control; }
|
2018-01-21 16:28:29 -04:00
|
|
|
|
|
|
|
// allow for low latency writes
|
|
|
|
bool set_unbuffered_writes(bool on) override;
|
2018-01-21 18:31:22 -04:00
|
|
|
|
|
|
|
void configure_parity(uint8_t v) override;
|
|
|
|
void set_stop_bits(int n) override;
|
2018-05-15 21:42:31 -03:00
|
|
|
|
2021-07-08 03:35:58 -03:00
|
|
|
/*
|
|
|
|
software control of the CTS/RTS pins if available. Return false if
|
|
|
|
not available
|
|
|
|
*/
|
|
|
|
bool set_RTS_pin(bool high) override;
|
|
|
|
bool set_CTS_pin(bool high) override;
|
|
|
|
|
2018-05-15 21:42:31 -03:00
|
|
|
/*
|
|
|
|
return timestamp estimate in microseconds for when the start of
|
|
|
|
a nbytes packet arrived on the uart. This should be treated as a
|
|
|
|
time constraint, not an exact time. It is guaranteed that the
|
|
|
|
packet did not start being received after this time, but it
|
|
|
|
could have been in a system buffer before the returned time.
|
|
|
|
|
|
|
|
This takes account of the baudrate of the link. For transports
|
|
|
|
that have no baudrate (such as USB) the time estimate may be
|
|
|
|
less accurate.
|
|
|
|
|
|
|
|
A return value of zero means the HAL does not support this API
|
|
|
|
*/
|
2018-05-16 18:01:14 -03:00
|
|
|
uint64_t receive_time_constraint_us(uint16_t nbytes) override;
|
2018-04-05 22:58:52 -03:00
|
|
|
|
|
|
|
uint32_t bw_in_kilobytes_per_second() const override {
|
|
|
|
if (sdef.is_usb) {
|
|
|
|
return 200;
|
|
|
|
}
|
|
|
|
return _baudrate/(9*1024);
|
|
|
|
}
|
2021-06-05 00:51:10 -03:00
|
|
|
|
2022-01-08 06:56:52 -04:00
|
|
|
#if HAL_UART_STATS_ENABLED
|
2021-06-05 00:51:10 -03:00
|
|
|
// request information on uart I/O for one uart
|
|
|
|
void uart_info(ExpandingString &str) override;
|
2022-01-08 06:56:52 -04:00
|
|
|
#endif
|
2018-04-05 22:58:52 -03:00
|
|
|
|
2021-05-01 09:00:59 -03:00
|
|
|
/*
|
|
|
|
return true if this UART has DMA enabled on both RX and TX
|
|
|
|
*/
|
|
|
|
bool is_dma_enabled() const override { return rx_dma_enabled && tx_dma_enabled; }
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
private:
|
2018-01-10 17:50:25 -04:00
|
|
|
const SerialDef &sdef;
|
2019-12-20 23:39:01 -04:00
|
|
|
bool rx_dma_enabled;
|
|
|
|
bool tx_dma_enabled;
|
2018-02-05 22:40:30 -04:00
|
|
|
|
2020-10-27 22:01:14 -03:00
|
|
|
/*
|
2021-09-23 15:05:18 -03:00
|
|
|
copy of rx_line, tx_line, rts_line and cts_line with alternative configs resolved
|
2020-10-27 22:01:14 -03:00
|
|
|
*/
|
|
|
|
ioline_t atx_line;
|
|
|
|
ioline_t arx_line;
|
2021-09-23 15:05:18 -03:00
|
|
|
ioline_t arts_line;
|
|
|
|
ioline_t acts_line;
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2018-02-05 22:40:30 -04:00
|
|
|
// thread used for all UARTs
|
2020-12-05 15:16:27 -04:00
|
|
|
static thread_t* volatile uart_rx_thread_ctx;
|
2018-02-05 22:40:30 -04:00
|
|
|
|
|
|
|
// table to find UARTDrivers from serial number, used for event handling
|
|
|
|
static UARTDriver *uart_drivers[UART_MAX_DRIVERS];
|
2020-12-05 15:16:27 -04:00
|
|
|
|
|
|
|
// thread used for writing and reading
|
|
|
|
thread_t* volatile uart_thread_ctx;
|
|
|
|
char uart_thread_name[6];
|
2018-02-05 22:40:30 -04:00
|
|
|
|
|
|
|
// index into uart_drivers table
|
|
|
|
uint8_t serial_num;
|
2018-04-02 03:00:36 -03:00
|
|
|
|
|
|
|
// key for a locked port
|
2018-12-19 07:25:41 -04:00
|
|
|
uint32_t lock_write_key;
|
|
|
|
uint32_t lock_read_key;
|
|
|
|
|
2018-01-05 02:19:51 -04:00
|
|
|
uint32_t _baudrate;
|
2018-03-01 20:46:30 -04:00
|
|
|
#if HAL_USE_SERIAL == TRUE
|
2018-01-05 02:19:51 -04:00
|
|
|
SerialConfig sercfg;
|
2018-03-01 20:46:30 -04:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
const thread_t* _uart_owner_thd;
|
|
|
|
|
|
|
|
struct {
|
|
|
|
// thread waiting for data
|
|
|
|
thread_t *thread_ctx;
|
|
|
|
// number of bytes needed
|
|
|
|
uint16_t n;
|
|
|
|
} _wait;
|
|
|
|
|
|
|
|
// we use in-task ring buffers to reduce the system call cost
|
|
|
|
// of ::read() and ::write() in the main loop
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2019-12-20 23:39:01 -04:00
|
|
|
volatile uint8_t rx_bounce_idx;
|
|
|
|
uint8_t *rx_bounce_buf[2];
|
2018-05-31 22:18:37 -03:00
|
|
|
uint8_t *tx_bounce_buf;
|
2020-06-16 05:28:40 -03:00
|
|
|
uint16_t contention_counter;
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
ByteBuffer _readbuf{0};
|
|
|
|
ByteBuffer _writebuf{0};
|
2020-01-18 17:57:24 -04:00
|
|
|
HAL_Semaphore _write_mutex;
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-01-05 02:19:51 -04:00
|
|
|
const stm32_dma_stream_t* rxdma;
|
|
|
|
const stm32_dma_stream_t* txdma;
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2020-12-05 15:16:27 -04:00
|
|
|
volatile bool _in_rx_timer;
|
|
|
|
volatile bool _in_tx_timer;
|
2018-03-02 06:38:11 -04:00
|
|
|
bool _blocking_writes;
|
2020-12-05 15:16:27 -04:00
|
|
|
volatile bool _rx_initialised;
|
|
|
|
volatile bool _tx_initialised;
|
|
|
|
volatile bool _device_initialised;
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-01-05 02:19:51 -04:00
|
|
|
Shared_DMA *dma_handle;
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2018-01-10 17:50:25 -04:00
|
|
|
static const SerialDef _serial_tab[];
|
|
|
|
|
2018-05-15 21:42:31 -03:00
|
|
|
// timestamp for receiving data on the UART, avoiding a lock
|
|
|
|
uint64_t _receive_timestamp[2];
|
|
|
|
uint8_t _receive_timestamp_idx;
|
|
|
|
|
2018-01-10 17:50:25 -04:00
|
|
|
// handling of flow control
|
|
|
|
enum flow_control _flow_control = FLOW_CONTROL_DISABLE;
|
|
|
|
bool _rts_is_active;
|
|
|
|
uint32_t _last_write_completed_us;
|
|
|
|
uint32_t _first_write_started_us;
|
2018-07-12 07:48:37 -03:00
|
|
|
uint32_t _total_written;
|
2018-11-14 00:55:14 -04:00
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
// statistics
|
|
|
|
uint32_t _tx_stats_bytes;
|
|
|
|
uint32_t _rx_stats_bytes;
|
2021-06-05 00:51:10 -03:00
|
|
|
uint32_t _last_stats_ms;
|
2020-12-05 15:16:27 -04:00
|
|
|
|
2019-12-27 03:27:11 -04:00
|
|
|
// we remember config options from set_options to apply on sdStart()
|
|
|
|
uint32_t _cr1_options;
|
2018-11-14 00:55:14 -04:00
|
|
|
uint32_t _cr2_options;
|
2019-12-27 03:27:11 -04:00
|
|
|
uint32_t _cr3_options;
|
2020-01-02 21:50:42 -04:00
|
|
|
uint16_t _last_options;
|
2018-11-14 00:55:14 -04:00
|
|
|
|
2018-12-19 07:25:41 -04:00
|
|
|
// half duplex control. After writing we throw away bytes for 4 byte widths to
|
|
|
|
// prevent reading our own bytes back
|
2019-12-27 03:27:11 -04:00
|
|
|
#if CH_CFG_USE_EVENTS == TRUE
|
2018-12-19 07:25:41 -04:00
|
|
|
bool half_duplex;
|
2019-12-27 03:27:11 -04:00
|
|
|
event_listener_t hd_listener;
|
2021-01-31 12:13:34 -04:00
|
|
|
eventflags_t hd_tx_active;
|
2019-12-27 03:27:11 -04:00
|
|
|
void half_duplex_setup_tx(void);
|
|
|
|
#endif
|
2018-12-19 07:25:41 -04:00
|
|
|
|
2018-01-21 16:28:29 -04:00
|
|
|
// set to true for unbuffered writes (low latency writes)
|
|
|
|
bool unbuffered_writes;
|
2019-08-27 04:42:51 -03:00
|
|
|
|
|
|
|
#if CH_CFG_USE_EVENTS == TRUE
|
|
|
|
// listener for parity error events
|
|
|
|
event_listener_t ev_listener;
|
|
|
|
bool parity_enabled;
|
|
|
|
#endif
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-01-05 02:19:51 -04:00
|
|
|
static void rx_irq_cb(void* sd);
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2018-01-05 02:19:51 -04:00
|
|
|
static void rxbuff_full_irq(void* self, uint32_t flags);
|
|
|
|
static void tx_complete(void* self, uint32_t flags);
|
|
|
|
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-03-14 03:06:30 -03:00
|
|
|
void dma_tx_allocate(Shared_DMA *ctx);
|
|
|
|
void dma_tx_deallocate(Shared_DMA *ctx);
|
2019-12-20 02:23:09 -04:00
|
|
|
void dma_rx_enable(void);
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2018-01-10 17:50:25 -04:00
|
|
|
void update_rts_line(void);
|
2018-01-21 16:28:29 -04:00
|
|
|
|
2018-03-14 05:51:04 -03:00
|
|
|
void check_dma_tx_completion(void);
|
2019-05-26 22:45:30 -03:00
|
|
|
#ifndef HAL_UART_NODMA
|
2018-01-21 16:28:29 -04:00
|
|
|
void write_pending_bytes_DMA(uint32_t n);
|
2019-05-26 22:45:30 -03:00
|
|
|
#endif
|
2018-01-21 16:28:29 -04:00
|
|
|
void write_pending_bytes_NODMA(uint32_t n);
|
|
|
|
void write_pending_bytes(void);
|
2020-12-05 15:16:27 -04:00
|
|
|
void read_bytes_NODMA();
|
2018-02-05 22:40:30 -04:00
|
|
|
|
2018-05-15 21:42:31 -03:00
|
|
|
void receive_timestamp_update(void);
|
2019-10-20 10:31:12 -03:00
|
|
|
|
2020-01-02 21:50:42 -04:00
|
|
|
// set SERIALn_OPTIONS for pullup/pulldown
|
|
|
|
void set_pushpull(uint16_t options);
|
|
|
|
|
2020-12-05 15:16:27 -04:00
|
|
|
static void thread_rx_init();
|
2018-02-05 22:40:30 -04:00
|
|
|
void thread_init();
|
2020-12-05 15:16:27 -04:00
|
|
|
void uart_thread();
|
|
|
|
static void uart_rx_thread(void* arg);
|
|
|
|
static void uart_thread_trampoline(void* p);
|
2018-01-05 02:19:51 -04:00
|
|
|
};
|
2020-02-11 18:50:18 -04:00
|
|
|
|
|
|
|
// access to usb init for stdio.cpp
|
|
|
|
void usb_initialise(void);
|