APM:Libraries
UARTDriver.h
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  *
15  * Code by Andrew Tridgell and Siddharth Bharat Purohit
16  */
17 #pragma once
18 
20 
21 #include "AP_HAL_ChibiOS.h"
22 #include "shared_dma.h"
23 #include "Semaphores.h"
24 
25 #define RX_BOUNCE_BUFSIZE 128
26 #define TX_BOUNCE_BUFSIZE 64
27 
28 #define UART_MAX_DRIVERS 7
29 
31 public:
32  UARTDriver(uint8_t serial_num);
33 
34  void begin(uint32_t b);
35  void begin(uint32_t b, uint16_t rxS, uint16_t txS);
36  void end();
37  void flush();
38  bool is_initialized();
39  void set_blocking_writes(bool blocking);
40  bool tx_pending();
41 
42 
43  uint32_t available() override;
44  uint32_t txspace() override;
45  int16_t read() override;
46  void _timer_tick(void) override;
47 
48  size_t write(uint8_t c);
49  size_t write(const uint8_t *buffer, size_t size);
50 
51  // lock a port for exclusive use. Use a key of 0 to unlock
52  bool lock_port(uint32_t key) override;
53 
54  // write to a locked port. If port is locked and key is not correct then 0 is returned
55  // and write is discarded
56  size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
57 
58  struct SerialDef {
59  BaseSequentialStream* serial;
60  bool is_usb;
61  bool dma_rx;
64  bool dma_tx;
66  uint32_t dma_tx_channel_id;
67  ioline_t rts_line;
68  uint8_t get_index(void) const {
69  return uint8_t(this - &_serial_tab[0]);
70  }
71  };
72 
73  bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;
74 
75  void set_flow_control(enum flow_control flow_control) override;
76  enum flow_control get_flow_control(void) override { return _flow_control; }
77 
78  // allow for low latency writes
79  bool set_unbuffered_writes(bool on) override;
80 
81  void configure_parity(uint8_t v) override;
82  void set_stop_bits(int n) override;
83 
84  /*
85  return timestamp estimate in microseconds for when the start of
86  a nbytes packet arrived on the uart. This should be treated as a
87  time constraint, not an exact time. It is guaranteed that the
88  packet did not start being received after this time, but it
89  could have been in a system buffer before the returned time.
90 
91  This takes account of the baudrate of the link. For transports
92  that have no baudrate (such as USB) the time estimate may be
93  less accurate.
94 
95  A return value of zero means the HAL does not support this API
96  */
97  uint64_t receive_time_constraint_us(uint16_t nbytes) override;
98 
99 private:
101  const SerialDef &sdef;
102 
103  // thread used for all UARTs
104  static thread_t *uart_thread_ctx;
105 
106  // last time we ran the uart thread
107  static uint32_t last_thread_run_us;
108 
109  // table to find UARTDrivers from serial number, used for event handling
111 
112  // index into uart_drivers table
113  uint8_t serial_num;
114 
115  // key for a locked port
116  uint32_t lock_key;
117 
118  uint32_t _baudrate;
119  uint16_t tx_len;
120 #if HAL_USE_SERIAL == TRUE
121  SerialConfig sercfg;
122 #endif
123  const thread_t* _uart_owner_thd;
124 
125  struct {
126  // thread waiting for data
127  thread_t *thread_ctx;
128  // number of bytes needed
129  uint16_t n;
130  } _wait;
131 
132  // we use in-task ring buffers to reduce the system call cost
133  // of ::read() and ::write() in the main loop
139  const stm32_dma_stream_t* rxdma;
140  const stm32_dma_stream_t* txdma;
141  bool _in_timer;
147  static const SerialDef _serial_tab[];
148 
149  // timestamp for receiving data on the UART, avoiding a lock
150  uint64_t _receive_timestamp[2];
152 
153  // handling of flow control
154  enum flow_control _flow_control = FLOW_CONTROL_DISABLE;
158 
159  // set to true for unbuffered writes (low latency writes)
161 
162  static void rx_irq_cb(void* sd);
163  static void rxbuff_full_irq(void* self, uint32_t flags);
164  static void tx_complete(void* self, uint32_t flags);
165 
166  void dma_tx_allocate(Shared_DMA *ctx);
167  void dma_tx_deallocate(Shared_DMA *ctx);
168  void update_rts_line(void);
169 
170  void check_dma_tx_completion(void);
171  void write_pending_bytes_DMA(uint32_t n);
172  void write_pending_bytes_NODMA(uint32_t n);
173  void write_pending_bytes(void);
174 
175  void receive_timestamp_update(void);
176 
177  void thread_init();
178  static void uart_thread(void *);
179 };
static void rxbuff_full_irq(void *self, uint32_t flags)
Definition: UARTDriver.cpp:354
const thread_t * _uart_owner_thd
Definition: UARTDriver.h:123
bool wait_timeout(uint16_t n, uint32_t timeout_ms) override
Definition: UARTDriver.cpp:573
const SerialDef & sdef
Definition: UARTDriver.h:101
static void rx_irq_cb(void *sd)
Definition: UARTDriver.cpp:332
void set_stop_bits(int n) override
Definition: UARTDriver.cpp:943
void configure_parity(uint8_t v) override
Definition: UARTDriver.cpp:902
void dma_tx_allocate(Shared_DMA *ctx)
Definition: UARTDriver.cpp:284
#define on
Definition: Config.h:51
static thread_t * uart_thread_ctx
Definition: UARTDriver.h:104
Semaphore _write_mutex
Definition: UARTDriver.h:138
#define RX_BOUNCE_BUFSIZE
Definition: UARTDriver.h:25
enum flow_control _flow_control
Definition: UARTDriver.h:154
BaseSequentialStream * serial
Definition: UARTDriver.h:59
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
bool lock_port(uint32_t key) override
Definition: UARTDriver.cpp:540
enum flow_control get_flow_control(void) override
Definition: UARTDriver.h:76
const stm32_dma_stream_t * rxdma
Definition: UARTDriver.h:139
ByteBuffer _writebuf
Definition: UARTDriver.h:137
Shared_DMA * dma_handle
Definition: UARTDriver.h:146
void write_pending_bytes_DMA(uint32_t n)
Definition: UARTDriver.cpp:606
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:151
void dma_tx_deallocate(Shared_DMA *ctx)
Definition: UARTDriver.cpp:304
uint32_t _first_write_started_us
Definition: UARTDriver.h:157
uint64_t _receive_timestamp[2]
Definition: UARTDriver.h:150
struct ChibiOS::UARTDriver::@41 _wait
SerialConfig sercfg
Definition: UARTDriver.h:121
int16_t read() override
Definition: UARTDriver.cpp:459
#define TX_BOUNCE_BUFSIZE
Definition: UARTDriver.h:26
bool set_unbuffered_writes(bool on) override
Definition: UARTDriver.cpp:889
void set_blocking_writes(bool blocking)
Definition: UARTDriver.cpp:428
static const SerialDef _serial_tab[]
Definition: UARTDriver.h:147
thread_t * thread_ctx
Definition: UARTDriver.h:127
uint32_t txspace() override
Definition: UARTDriver.cpp:451
uint32_t _last_write_completed_us
Definition: UARTDriver.h:156
size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override
Definition: UARTDriver.cpp:554
void check_dma_tx_completion(void)
Definition: UARTDriver.cpp:588
static void uart_thread(void *)
Definition: UARTDriver.cpp:73
static uint32_t last_thread_run_us
Definition: UARTDriver.h:107
const stm32_dma_stream_t * txdma
Definition: UARTDriver.h:140
void receive_timestamp_update(void)
Definition: UARTDriver.cpp:972
void update_rts_line(void)
Definition: UARTDriver.cpp:871
float v
Definition: Printf.cpp:15
uint32_t available() override
Definition: UARTDriver.cpp:436
void set_flow_control(enum flow_control flow_control) override
void begin(uint32_t b)
Definition: UARTDriver.cpp:387
void write_pending_bytes(void)
Definition: UARTDriver.cpp:687
uint8_t rx_bounce_buf[RX_BOUNCE_BUFSIZE]
Definition: UARTDriver.h:134
uint8_t tx_bounce_buf[TX_BOUNCE_BUFSIZE]
Definition: UARTDriver.h:135
size_t write(uint8_t c)
Definition: UARTDriver.cpp:480
ByteBuffer _readbuf
Definition: UARTDriver.h:136
uint8_t get_index(void) const
Definition: UARTDriver.h:68
uint64_t receive_time_constraint_us(uint16_t nbytes) override
Definition: UARTDriver.cpp:991
static UARTDriver * uart_drivers[UART_MAX_DRIVERS]
Definition: UARTDriver.h:110
#define UART_MAX_DRIVERS
Definition: UARTDriver.h:28
void _timer_tick(void) override
Definition: UARTDriver.cpp:727
static void tx_complete(void *self, uint32_t flags)
Definition: UARTDriver.cpp:315
void write_pending_bytes_NODMA(uint32_t n)
Definition: UARTDriver.cpp:652