UARTDriver.h 6.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229
  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. #include <AP_HAL/utility/RingBuffer.h>
  19. #include "AP_HAL_ChibiOS.h"
  20. #include "shared_dma.h"
  21. #include "Semaphores.h"
  22. #define RX_BOUNCE_BUFSIZE 128U
  23. #define TX_BOUNCE_BUFSIZE 64U
  24. // enough for uartA to uartH, plus IOMCU
  25. #define UART_MAX_DRIVERS 9
  26. class ChibiOS::UARTDriver : public AP_HAL::UARTDriver {
  27. public:
  28. UARTDriver(uint8_t serial_num);
  29. void begin(uint32_t b) override;
  30. void begin(uint32_t b, uint16_t rxS, uint16_t txS) override;
  31. void end() override;
  32. void flush() override;
  33. bool is_initialized() override;
  34. void set_blocking_writes(bool blocking) override;
  35. bool tx_pending() override;
  36. uint32_t available() override;
  37. uint32_t txspace() override;
  38. int16_t read() override;
  39. int16_t read_locked(uint32_t key) override;
  40. void _timer_tick(void) override;
  41. size_t write(uint8_t c) override;
  42. size_t write(const uint8_t *buffer, size_t size) override;
  43. // lock a port for exclusive use. Use a key of 0 to unlock
  44. bool lock_port(uint32_t write_key, uint32_t read_key) override;
  45. // control optional features
  46. bool set_options(uint8_t options) override;
  47. uint8_t get_options(void) const override;
  48. // write to a locked port. If port is locked and key is not correct then 0 is returned
  49. // and write is discarded
  50. size_t write_locked(const uint8_t *buffer, size_t size, uint32_t key) override;
  51. struct SerialDef {
  52. BaseSequentialStream* serial;
  53. bool is_usb;
  54. #ifndef HAL_UART_NODMA
  55. bool dma_rx;
  56. uint8_t dma_rx_stream_id;
  57. uint32_t dma_rx_channel_id;
  58. bool dma_tx;
  59. uint8_t dma_tx_stream_id;
  60. uint32_t dma_tx_channel_id;
  61. #endif
  62. ioline_t rts_line;
  63. int8_t rxinv_gpio;
  64. uint8_t rxinv_polarity;
  65. int8_t txinv_gpio;
  66. uint8_t txinv_polarity;
  67. uint8_t get_index(void) const {
  68. return uint8_t(this - &_serial_tab[0]);
  69. }
  70. };
  71. bool wait_timeout(uint16_t n, uint32_t timeout_ms) override;
  72. void set_flow_control(enum flow_control flow_control) override;
  73. enum flow_control get_flow_control(void) override { return _flow_control; }
  74. // allow for low latency writes
  75. bool set_unbuffered_writes(bool on) override;
  76. void configure_parity(uint8_t v) override;
  77. void set_stop_bits(int n) override;
  78. /*
  79. return timestamp estimate in microseconds for when the start of
  80. a nbytes packet arrived on the uart. This should be treated as a
  81. time constraint, not an exact time. It is guaranteed that the
  82. packet did not start being received after this time, but it
  83. could have been in a system buffer before the returned time.
  84. This takes account of the baudrate of the link. For transports
  85. that have no baudrate (such as USB) the time estimate may be
  86. less accurate.
  87. A return value of zero means the HAL does not support this API
  88. */
  89. uint64_t receive_time_constraint_us(uint16_t nbytes) override;
  90. uint32_t bw_in_kilobytes_per_second() const override {
  91. if (sdef.is_usb) {
  92. return 200;
  93. }
  94. return _baudrate/(9*1024);
  95. }
  96. private:
  97. const SerialDef &sdef;
  98. // thread used for all UARTs
  99. static thread_t *uart_thread_ctx;
  100. // table to find UARTDrivers from serial number, used for event handling
  101. static UARTDriver *uart_drivers[UART_MAX_DRIVERS];
  102. // index into uart_drivers table
  103. uint8_t serial_num;
  104. // key for a locked port
  105. uint32_t lock_write_key;
  106. uint32_t lock_read_key;
  107. uint32_t _baudrate;
  108. uint16_t tx_len;
  109. #if HAL_USE_SERIAL == TRUE
  110. SerialConfig sercfg;
  111. #endif
  112. const thread_t* _uart_owner_thd;
  113. struct {
  114. // thread waiting for data
  115. thread_t *thread_ctx;
  116. // number of bytes needed
  117. uint16_t n;
  118. } _wait;
  119. // we use in-task ring buffers to reduce the system call cost
  120. // of ::read() and ::write() in the main loop
  121. #ifndef HAL_UART_NODMA
  122. bool tx_bounce_buf_ready;
  123. uint8_t *rx_bounce_buf;
  124. uint8_t *tx_bounce_buf;
  125. #endif
  126. ByteBuffer _readbuf{0};
  127. ByteBuffer _writebuf{0};
  128. Semaphore _write_mutex;
  129. #ifndef HAL_UART_NODMA
  130. const stm32_dma_stream_t* rxdma;
  131. const stm32_dma_stream_t* txdma;
  132. #endif
  133. virtual_timer_t tx_timeout;
  134. bool _in_timer;
  135. bool _blocking_writes;
  136. bool _initialised;
  137. bool _device_initialised;
  138. bool _lock_rx_in_timer_tick = false;
  139. #ifndef HAL_UART_NODMA
  140. Shared_DMA *dma_handle;
  141. #endif
  142. static const SerialDef _serial_tab[];
  143. // timestamp for receiving data on the UART, avoiding a lock
  144. uint64_t _receive_timestamp[2];
  145. uint8_t _receive_timestamp_idx;
  146. // handling of flow control
  147. enum flow_control _flow_control = FLOW_CONTROL_DISABLE;
  148. bool _rts_is_active;
  149. uint32_t _last_write_completed_us;
  150. uint32_t _first_write_started_us;
  151. uint32_t _total_written;
  152. // we remember cr2 and cr2 options from set_options to apply on sdStart()
  153. uint32_t _cr3_options;
  154. uint32_t _cr2_options;
  155. uint8_t _last_options;
  156. // half duplex control. After writing we throw away bytes for 4 byte widths to
  157. // prevent reading our own bytes back
  158. bool half_duplex;
  159. uint32_t hd_read_delay_us;
  160. uint32_t hd_write_us;
  161. void half_duplex_setup_delay(uint16_t len);
  162. // set to true for unbuffered writes (low latency writes)
  163. bool unbuffered_writes;
  164. #if CH_CFG_USE_EVENTS == TRUE
  165. // listener for parity error events
  166. event_listener_t ev_listener;
  167. bool parity_enabled;
  168. #endif
  169. #ifndef HAL_UART_NODMA
  170. static void rx_irq_cb(void* sd);
  171. #endif
  172. static void rxbuff_full_irq(void* self, uint32_t flags);
  173. static void tx_complete(void* self, uint32_t flags);
  174. static void handle_tx_timeout(void *arg);
  175. #ifndef HAL_UART_NODMA
  176. void dma_tx_allocate(Shared_DMA *ctx);
  177. void dma_tx_deallocate(Shared_DMA *ctx);
  178. #endif
  179. void update_rts_line(void);
  180. void check_dma_tx_completion(void);
  181. #ifndef HAL_UART_NODMA
  182. void write_pending_bytes_DMA(uint32_t n);
  183. #endif
  184. void write_pending_bytes_NODMA(uint32_t n);
  185. void write_pending_bytes(void);
  186. void receive_timestamp_update(void);
  187. void thread_init();
  188. static void uart_thread(void *);
  189. };