APM:Libraries
UARTDriver.cpp
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 #include <AP_HAL/AP_HAL.h>
18 
19 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
20 #include "UARTDriver.h"
21 #include "GPIO.h"
22 #include <usbcfg.h>
23 #include "shared_dma.h"
24 #include <AP_Math/AP_Math.h>
25 #include "Scheduler.h"
26 
27 extern const AP_HAL::HAL& hal;
28 
29 using namespace ChibiOS;
30 
31 #ifdef HAL_USB_VENDOR_ID
32 // USB has been configured in hwdef.dat
33 #define HAVE_USB_SERIAL
34 #endif
35 
36 #if HAL_WITH_IO_MCU
37 extern ChibiOS::UARTDriver uart_io;
38 #endif
39 
40 const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_UART_DEVICE_LIST };
41 
42 // handle for UART handling thread
44 
45 // table to find UARTDrivers from serial number, used for event handling
47 
48 // last time we did a 1kHz run of uarts
50 
51 // event used to wake up waiting thread. This event number is for
52 // caller threads
53 #define EVT_DATA EVENT_MASK(0)
54 
55 UARTDriver::UARTDriver(uint8_t _serial_num) :
56 tx_bounce_buf_ready(true),
57 serial_num(_serial_num),
58 sdef(_serial_tab[_serial_num]),
59 _baudrate(57600),
60 _in_timer(false),
61 _initialised(false)
62 {
63  osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many UART drivers");
64  uart_drivers[serial_num] = this;
65 }
66 
67 /*
68  thread for handling UART send/receive
69 
70  We use events indexed by serial_num to trigger a more rapid send for
71  unbuffered_write uarts, and run at 1kHz for general UART handling
72  */
73 void UARTDriver::uart_thread(void* arg)
74 {
75  uart_thread_ctx = chThdGetSelfX();
76  while (true) {
77  eventmask_t mask = chEvtWaitAnyTimeout(~0, MS2ST(1));
78  uint32_t now = AP_HAL::micros();
79  if (now - last_thread_run_us >= 1000) {
80  // run them all if it's been more than 1ms since we ran
81  // them all
82  mask = ~0;
83  last_thread_run_us = now;
84  }
85  for (uint8_t i=0; i<UART_MAX_DRIVERS; i++) {
86  if (uart_drivers[i] == nullptr) {
87  continue;
88  }
89  if ((mask & EVENT_MASK(i)) &&
92  }
93  }
94  }
95 }
96 
97 /*
98  initialise UART thread
99  */
101 {
102  if (uart_thread_ctx) {
103  // already initialised
104  return;
105  }
106 #if CH_CFG_USE_HEAP == TRUE
107  uart_thread_ctx = chThdCreateFromHeap(NULL,
108  THD_WORKING_AREA_SIZE(2048),
109  "apm_uart",
111  uart_thread,
112  this);
113 #endif
114 }
115 
116 
117 /*
118  hook to allow printf() to work on hal.console when we don't have a
119  dedicated debug console
120  */
121 static int hal_console_vprintf(const char *fmt, va_list arg)
122 {
123  hal.console->vprintf(fmt, arg);
124  return 1; // wrong length, but doesn't matter for what this is used for
125 }
126 
127 
128 void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
129 {
130  thread_init();
131 
132  if (sdef.serial == nullptr) {
133  return;
134  }
135  uint16_t min_tx_buffer = 4096;
136  uint16_t min_rx_buffer = 1024;
137  // on PX4 we have enough memory to have a larger transmit and
138  // receive buffer for all ports. This means we don't get delays
139  // while waiting to write GPS config packets
140  if (txS < min_tx_buffer) {
141  txS = min_tx_buffer;
142  }
143  if (rxS < min_rx_buffer) {
144  rxS = min_rx_buffer;
145  }
146 
147  /*
148  allocate the read buffer
149  we allocate buffers before we successfully open the device as we
150  want to allocate in the early stages of boot, and cause minimum
151  thrashing of the heap once we are up. The ttyACM0 driver may not
152  connect for some time after boot
153  */
154  if (rxS != _readbuf.get_size()) {
155  _initialised = false;
156  while (_in_timer) {
157  hal.scheduler->delay(1);
158  }
159 
160  _readbuf.set_size(rxS);
161  }
162 
163  if (b != 0) {
164  _baudrate = b;
165  }
166 
167  /*
168  allocate the write buffer
169  */
170  if (txS != _writebuf.get_size()) {
171  _initialised = false;
172  while (_in_timer) {
173  hal.scheduler->delay(1);
174  }
175  _writebuf.set_size(txS);
176  }
177 
178  if (sdef.is_usb) {
179 #ifdef HAVE_USB_SERIAL
180  /*
181  * Initializes a serial-over-USB CDC driver.
182  */
183  if (!_device_initialised) {
184  sduObjectInit((SerialUSBDriver*)sdef.serial);
185  sduStart((SerialUSBDriver*)sdef.serial, &serusbcfg);
186  /*
187  * Activates the USB driver and then the USB bus pull-up on D+.
188  * Note, a delay is inserted in order to not have to disconnect the cable
189  * after a reset.
190  */
191  usbDisconnectBus(serusbcfg.usbp);
192  hal.scheduler->delay_microseconds(1500);
193  usbStart(serusbcfg.usbp, &usbcfg);
194  usbConnectBus(serusbcfg.usbp);
195  _device_initialised = true;
196  }
197 #endif
198  } else {
199 #if HAL_USE_SERIAL == TRUE
200  if (_baudrate != 0) {
201  bool was_initialised = _device_initialised;
202  //setup Rx DMA
203  if(!_device_initialised) {
204  if(sdef.dma_rx) {
205  rxdma = STM32_DMA_STREAM(sdef.dma_rx_stream_id);
206  chSysLock();
207  bool dma_allocated = dmaStreamAllocate(rxdma,
208  12, //IRQ Priority
209  (stm32_dmaisr_t)rxbuff_full_irq,
210  (void *)this);
211  osalDbgAssert(!dma_allocated, "stream already allocated");
212  chSysUnlock();
213 #if defined(STM32F7)
214  dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
215 #else
216  dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
217 #endif // STM32F7
218  }
219  if (sdef.dma_tx) {
220  // we only allow for sharing of the TX DMA channel, not the RX
221  // DMA channel, as the RX side is active all the time, so
222  // cannot be shared
227  }
228  _device_initialised = true;
229  }
230  sercfg.speed = _baudrate;
231  if (!sdef.dma_tx && !sdef.dma_rx) {
232  sercfg.cr1 = 0;
233  sercfg.cr3 = 0;
234  } else {
235  if (sdef.dma_rx) {
236  sercfg.cr1 = USART_CR1_IDLEIE;
237  sercfg.cr3 = USART_CR3_DMAR;
238  }
239  if (sdef.dma_tx) {
240  sercfg.cr3 |= USART_CR3_DMAT;
241  }
242  }
243  sercfg.cr2 = USART_CR2_STOP1_BITS;
244  sercfg.irq_cb = rx_irq_cb;
245  sercfg.ctx = (void*)this;
246  sdStart((SerialDriver*)sdef.serial, &sercfg);
247  if(sdef.dma_rx) {
248  //Configure serial driver to skip handling RX packets
249  //because we will handle them via DMA
250  ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
251  //Start DMA
252  if(!was_initialised) {
253  uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
254  dmamode |= STM32_DMA_CR_CHSEL(STM32_DMA_GETCHANNEL(sdef.dma_rx_stream_id,
256  dmamode |= STM32_DMA_CR_PL(0);
257  dmaStreamSetMemory0(rxdma, rx_bounce_buf);
258  dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
259  dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M |
260  STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
261  dmaStreamEnable(rxdma);
262  }
263  }
264  }
265 #endif // HAL_USE_SERIAL
266  }
267 
268  if (_writebuf.get_size() && _readbuf.get_size()) {
269  _initialised = true;
270  }
271  _uart_owner_thd = chThdGetSelfX();
272 
273  // setup flow control
275 
276  if (serial_num == 0 && _initialised) {
277 #ifndef HAL_STDOUT_SERIAL
278  // setup hal.console to take printf() output
280 #endif
281  }
282 }
283 
285 {
286 #if HAL_USE_SERIAL == TRUE
287  osalDbgAssert(txdma == nullptr, "double DMA allocation");
288  txdma = STM32_DMA_STREAM(sdef.dma_tx_stream_id);
289  chSysLock();
290  bool dma_allocated = dmaStreamAllocate(txdma,
291  12, //IRQ Priority
292  (stm32_dmaisr_t)tx_complete,
293  (void *)this);
294  osalDbgAssert(!dma_allocated, "stream already allocated");
295  chSysUnlock();
296 #if defined(STM32F7)
297  dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
298 #else
299  dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
300 #endif // STM32F7
301 #endif // HAL_USE_SERIAL
302 }
303 
305 {
306  chSysLock();
307  dmaStreamRelease(txdma);
308  txdma = nullptr;
309  chSysUnlock();
310 }
311 
312 /*
313  DMA transmit complettion interrupt handler
314  */
315 void UARTDriver::tx_complete(void* self, uint32_t flags)
316 {
317  UARTDriver* uart_drv = (UARTDriver*)self;
318  if (!uart_drv->tx_bounce_buf_ready) {
320  uart_drv->tx_bounce_buf_ready = true;
321  if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) {
322  // trigger a rapid send of next bytes
323  chSysLockFromISR();
324  chEvtSignalI(uart_thread_ctx, EVENT_MASK(uart_drv->serial_num));
325  chSysUnlockFromISR();
326  }
327  uart_drv->dma_handle->unlock_from_IRQ();
328  }
329 }
330 
331 
332 void UARTDriver::rx_irq_cb(void* self)
333 {
334 #if HAL_USE_SERIAL == TRUE
335  UARTDriver* uart_drv = (UARTDriver*)self;
336  if (!uart_drv->sdef.dma_rx) {
337  return;
338  }
339 #if defined(STM32F7)
340  //disable dma, triggering DMA transfer complete interrupt
341  uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
342 #else
343  volatile uint16_t sr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->SR;
344  if(sr & USART_SR_IDLE) {
345  volatile uint16_t dr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->DR;
346  (void)dr;
347  //disable dma, triggering DMA transfer complete interrupt
348  uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
349  }
350 #endif // STM32F7
351 #endif // HAL_USE_SERIAL
352 }
353 
354 void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
355 {
356 #if HAL_USE_SERIAL == TRUE
357  UARTDriver* uart_drv = (UARTDriver*)self;
358  if (uart_drv->_lock_rx_in_timer_tick) {
359  return;
360  }
361  if (!uart_drv->sdef.dma_rx) {
362  return;
363  }
364  uint8_t len = RX_BOUNCE_BUFSIZE - uart_drv->rxdma->stream->NDTR;
365  if (len == 0) {
366  return;
367  }
368  uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len);
369 
370  uart_drv->receive_timestamp_update();
371 
372  //restart the DMA transfers
373  dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf);
374  dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE);
375  dmaStreamEnable(uart_drv->rxdma);
376  if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) {
377  chSysLockFromISR();
378  chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA);
379  chSysUnlockFromISR();
380  }
381  if (uart_drv->_rts_is_active) {
382  uart_drv->update_rts_line();
383  }
384 #endif // HAL_USE_SERIAL
385 }
386 
387 void UARTDriver::begin(uint32_t b)
388 {
389  begin(b, 0, 0);
390 }
391 
393 {
394  _initialised = false;
395  while (_in_timer) hal.scheduler->delay(1);
396 
397  if (sdef.is_usb) {
398 #ifdef HAVE_USB_SERIAL
399 
400  sduStop((SerialUSBDriver*)sdef.serial);
401 #endif
402  } else {
403 #if HAL_USE_SERIAL == TRUE
404  sdStop((SerialDriver*)sdef.serial);
405 #endif
406  }
407  _readbuf.set_size(0);
408  _writebuf.set_size(0);
409 }
410 
412 {
413  if (sdef.is_usb) {
414 #ifdef HAVE_USB_SERIAL
415 
416  sduSOFHookI((SerialUSBDriver*)sdef.serial);
417 #endif
418  } else {
419  //TODO: Handle this for other serial ports
420  }
421 }
422 
424 {
425  return _initialised;
426 }
427 
429 {
430  _blocking_writes = blocking;
431 }
432 
433 bool UARTDriver::tx_pending() { return false; }
434 
435 /* Empty implementations of Stream virtual methods */
437  if (!_initialised) {
438  return 0;
439  }
440  if (sdef.is_usb) {
441 #ifdef HAVE_USB_SERIAL
442 
443  if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) {
444  return 0;
445  }
446 #endif
447  }
448  return _readbuf.available();
449 }
450 
452 {
453  if (!_initialised) {
454  return 0;
455  }
456  return _writebuf.space();
457 }
458 
460 {
461  if (_uart_owner_thd != chThdGetSelfX()){
462  return -1;
463  }
464  if (!_initialised) {
465  return -1;
466  }
467 
468  uint8_t byte;
469  if (!_readbuf.read_byte(&byte)) {
470  return -1;
471  }
472  if (!_rts_is_active) {
473  update_rts_line();
474  }
475 
476  return byte;
477 }
478 
479 /* Empty implementations of Print virtual methods */
480 size_t UARTDriver::write(uint8_t c)
481 {
482  if (lock_key != 0 || !_write_mutex.take_nonblocking()) {
483  return 0;
484  }
485 
486  if (!_initialised) {
487  _write_mutex.give();
488  return 0;
489  }
490 
491  while (_writebuf.space() == 0) {
492  if (!_blocking_writes) {
493  _write_mutex.give();
494  return 0;
495  }
496  hal.scheduler->delay(1);
497  }
498  size_t ret = _writebuf.write(&c, 1);
499  if (unbuffered_writes) {
501  }
502  _write_mutex.give();
503  return ret;
504 }
505 
506 size_t UARTDriver::write(const uint8_t *buffer, size_t size)
507 {
508  if (!_initialised || lock_key != 0) {
509  return 0;
510  }
511 
513  return 0;
514  }
515 
517  /*
518  use the per-byte delay loop in write() above for blocking writes
519  */
520  _write_mutex.give();
521  size_t ret = 0;
522  while (size--) {
523  if (write(*buffer++) != 1) break;
524  ret++;
525  }
526  return ret;
527  }
528 
529  size_t ret = _writebuf.write(buffer, size);
530  if (unbuffered_writes) {
532  }
533  _write_mutex.give();
534  return ret;
535 }
536 
537 /*
538  lock the uart for exclusive use by write_locked() with the right key
539  */
540 bool UARTDriver::lock_port(uint32_t key)
541 {
542  if (lock_key && key != lock_key && key != 0) {
543  // someone else is using it
544  return false;
545  }
546  lock_key = key;
547  return true;
548 }
549 
550 /*
551  write to a locked port. If port is locked and key is not correct then 0 is returned
552  and write is discarded. All writes are non-blocking
553 */
554 size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key)
555 {
556  if (lock_key != 0 && key != lock_key) {
557  return 0;
558  }
560  return 0;
561  }
562  size_t ret = _writebuf.write(buffer, size);
563 
564  _write_mutex.give();
565 
566  return ret;
567 }
568 
569 /*
570  wait for data to arrive, or a timeout. Return true if data has
571  arrived, false on timeout
572  */
573 bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
574 {
575  chEvtGetAndClearEvents(EVT_DATA);
576  if (available() >= n) {
577  return true;
578  }
579  _wait.n = n;
580  _wait.thread_ctx = chThdGetSelfX();
581  eventmask_t mask = chEvtWaitAnyTimeout(EVT_DATA, MS2ST(timeout_ms));
582  return (mask & EVT_DATA) != 0;
583 }
584 
585 /*
586  check for DMA completed for TX
587  */
589 {
590  chSysLock();
591  if (!tx_bounce_buf_ready) {
592  if (!(txdma->stream->CR & STM32_DMA_CR_EN)) {
593  if (txdma->stream->NDTR == 0) {
594  tx_bounce_buf_ready = true;
597  }
598  }
599  }
600  chSysUnlock();
601 }
602 
603 /*
604  write out pending bytes with DMA
605  */
607 {
609 
610  if (!tx_bounce_buf_ready) {
611  return;
612  }
613 
614  /* TX DMA channel preparation.*/
617  if (tx_len == 0) {
618  return;
619  }
620  if (!dma_handle->lock_nonblock()) {
621  tx_len = 0;
622  return;
623  }
624  if (dma_handle->has_contention()) {
625  /*
626  someone else is using this same DMA channel. To reduce
627  latency we will drop the TX size with DMA on this UART to
628  keep TX times below 250us. This can still suffer from long
629  times due to CTS blockage
630  */
631  uint32_t max_tx_bytes = 1 + (_baudrate * 250UL / 1000000UL);
632  if (tx_len > max_tx_bytes) {
633  tx_len = max_tx_bytes;
634  }
635  }
636  tx_bounce_buf_ready = false;
637  osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
638  dmaStreamSetMemory0(txdma, tx_bounce_buf);
639  dmaStreamSetTransactionSize(txdma, tx_len);
640  uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
641  dmamode |= STM32_DMA_CR_CHSEL(STM32_DMA_GETCHANNEL(sdef.dma_tx_stream_id,
643  dmamode |= STM32_DMA_CR_PL(0);
644  dmaStreamSetMode(txdma, dmamode | STM32_DMA_CR_DIR_M2P |
645  STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
646  dmaStreamEnable(txdma);
647 }
648 
649 /*
650  write any pending bytes to the device, non-DMA method
651  */
653 {
654  ByteBuffer::IoVec vec[2];
655  const auto n_vec = _writebuf.peekiovec(vec, n);
656  for (int i = 0; i < n_vec; i++) {
657  int ret = -1;
658  if (sdef.is_usb) {
659  ret = 0;
660 #ifdef HAVE_USB_SERIAL
661  ret = chnWriteTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
662 #endif
663  } else {
664 #if HAL_USE_SERIAL == TRUE
665  ret = chnWriteTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
666 #endif
667  }
668  if (ret < 0) {
669  break;
670  }
671  if (ret > 0) {
673  }
674  _writebuf.advance(ret);
675 
676  /* We wrote less than we asked for, stop */
677  if ((unsigned)ret != vec[i].len) {
678  break;
679  }
680  }
681 }
682 
683 
684 /*
685  write any pending bytes to the device
686  */
688 {
689  uint32_t n;
690 
691  if (sdef.dma_tx) {
693  }
694 
695  // write any pending bytes
696  n = _writebuf.available();
697  if (n <= 0) {
698  return;
699  }
700 
701  if (!sdef.dma_tx) {
703  } else {
705  }
706 
707  // handle AUTO flow control mode
709  if (_first_write_started_us == 0) {
711  }
712  if (_last_write_completed_us != 0) {
714  } else if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) {
715  // it doesn't look like hw flow control is working
716  hal.console->printf("disabling flow control on serial %u\n", sdef.get_index());
718  }
719  }
720 }
721 
722 /*
723  push any pending bytes to/from the serial port. This is called at
724  1kHz in the timer thread. Doing it this way reduces the system call
725  overhead in the main task enormously.
726  */
728 {
729  if (!_initialised) return;
730 
731  if (sdef.dma_rx && rxdma) {
732  _lock_rx_in_timer_tick = true;
733  //Check if DMA is enabled
734  //if not, it might be because the DMA interrupt was silenced
735  //let's handle that here so that we can continue receiving
736  if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
737  uint8_t len = RX_BOUNCE_BUFSIZE - rxdma->stream->NDTR;
738  if (len != 0) {
740 
742 
743  if (_wait.thread_ctx && _readbuf.available() >= _wait.n) {
744  chEvtSignal(_wait.thread_ctx, EVT_DATA);
745  }
746  if (_rts_is_active) {
747  update_rts_line();
748  }
749  }
750  //DMA disabled by idle interrupt never got a chance to be handled
751  //we will enable it here
752  dmaStreamSetMemory0(rxdma, rx_bounce_buf);
753  dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
754  dmaStreamEnable(rxdma);
755  }
756  _lock_rx_in_timer_tick = false;
757  }
758 
759  // don't try IO on a disconnected USB port
760  if (sdef.is_usb) {
761 #ifdef HAVE_USB_SERIAL
762  if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) {
763  return;
764  }
765 #endif
766  }
767  if(sdef.is_usb) {
768 #ifdef HAVE_USB_SERIAL
769  ((GPIO *)hal.gpio)->set_usb_connected();
770 #endif
771  }
772  _in_timer = true;
773 
774  if (!sdef.dma_rx) {
775  // try to fill the read buffer
776  ByteBuffer::IoVec vec[2];
777 
778  const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
779  for (int i = 0; i < n_vec; i++) {
780  int ret = 0;
781  //Do a non-blocking read
782  if (sdef.is_usb) {
783  #ifdef HAVE_USB_SERIAL
784  ret = chnReadTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
785  #endif
786  } else {
787 #if HAL_USE_SERIAL == TRUE
788  ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
789 #endif
790  }
791  if (ret < 0) {
792  break;
793  }
794  _readbuf.commit((unsigned)ret);
795 
797 
798  /* stop reading as we read less than we asked for */
799  if ((unsigned)ret < vec[i].len) {
800  break;
801  }
802  }
803  }
804 
805  if (unbuffered_writes) {
806  // now send pending bytes. If we are doing "unbuffered" writes
807  // then the send normally happens as soon as the bytes are
808  // provided by the write() call, but if the write is larger
809  // than the DMA buffer size then there can be extra bytes to
810  // send here, and they must be sent with the write lock held
813  _write_mutex.give();
814  } else {
816  }
817 
818  _in_timer = false;
819 }
820 
821 /*
822  change flow control mode for port
823  */
824 void UARTDriver::set_flow_control(enum flow_control flowcontrol)
825 {
826  if (sdef.rts_line == 0 || sdef.is_usb) {
827  // no hw flow control available
828  return;
829  }
830 #if HAL_USE_SERIAL == TRUE
831  _flow_control = flowcontrol;
832  if (!_initialised) {
833  // not ready yet, we just set variable for when we call begin
834  return;
835  }
836  switch (_flow_control) {
837 
839  // force RTS active when flow disabled
840  palSetLineMode(sdef.rts_line, 1);
841  palClearLine(sdef.rts_line);
842  _rts_is_active = true;
843  // disable hardware CTS support
844  ((SerialDriver*)(sdef.serial))->usart->CR3 &= ~(USART_CR3_CTSE | USART_CR3_RTSE);
845  break;
846 
847  case FLOW_CONTROL_AUTO:
848  // reset flow control auto state machine
851  FALLTHROUGH;
852 
853  case FLOW_CONTROL_ENABLE:
854  // we do RTS in software as STM32 hardware RTS support toggles
855  // the pin for every byte which loses a lot of bandwidth
856  palSetLineMode(sdef.rts_line, 1);
857  palClearLine(sdef.rts_line);
858  _rts_is_active = true;
859  // enable hardware CTS support, disable RTS support as we do that in software
860  ((SerialDriver*)(sdef.serial))->usart->CR3 |= USART_CR3_CTSE;
861  ((SerialDriver*)(sdef.serial))->usart->CR3 &= ~USART_CR3_RTSE;
862  break;
863  }
864 #endif // HAL_USE_SERIAL
865 }
866 
867 /*
868  software update of rts line. We don't use the HW support for RTS as
869  it has no hysteresis, so it ends up toggling RTS on every byte
870  */
872 {
874  return;
875  }
876  uint16_t space = _readbuf.space();
877  if (_rts_is_active && space < 16) {
878  _rts_is_active = false;
879  palSetLine(sdef.rts_line);
880  } else if (!_rts_is_active && space > 32) {
881  _rts_is_active = true;
882  palClearLine(sdef.rts_line);
883  }
884 }
885 
886 /*
887  setup unbuffered writes for lower latency
888  */
890 {
891  if (on && !sdef.dma_tx) {
892  // we can't implement low latemcy writes safely without TX DMA
893  return false;
894  }
896  return true;
897 }
898 
899 /*
900  setup parity
901  */
903 {
904  if (sdef.is_usb) {
905  // not possible
906  return;
907  }
908 #if HAL_USE_SERIAL == TRUE
909  // stop and start to take effect
910  sdStop((SerialDriver*)sdef.serial);
911 
912  switch (v) {
913  case 0:
914  // no parity
915  sercfg.cr1 &= ~(USART_CR1_PCE | USART_CR1_PS);
916  break;
917  case 1:
918  // odd parity
919  // setting USART_CR1_M ensures extra bit is used as parity
920  // not last bit of data
921  sercfg.cr1 |= USART_CR1_M | USART_CR1_PCE;
922  sercfg.cr1 |= USART_CR1_PS;
923  break;
924  case 2:
925  // even parity
926  sercfg.cr1 |= USART_CR1_M | USART_CR1_PCE;
927  sercfg.cr1 &= ~USART_CR1_PS;
928  break;
929  }
930 
931  sdStart((SerialDriver*)sdef.serial, &sercfg);
932  if(sdef.dma_rx) {
933  //Configure serial driver to skip handling RX packets
934  //because we will handle them via DMA
935  ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
936  }
937 #endif // HAL_USE_SERIAL
938 }
939 
940 /*
941  set stop bits
942  */
944 {
945  if (sdef.is_usb) {
946  // not possible
947  return;
948  }
949 #if HAL_USE_SERIAL
950  // stop and start to take effect
951  sdStop((SerialDriver*)sdef.serial);
952 
953  switch (n) {
954  case 1:
955  sercfg.cr2 = USART_CR2_STOP1_BITS;
956  break;
957  case 2:
958  sercfg.cr2 = USART_CR2_STOP2_BITS;
959  break;
960  }
961  sdStart((SerialDriver*)sdef.serial, &sercfg);
962  if(sdef.dma_rx) {
963  //Configure serial driver to skip handling RX packets
964  //because we will handle them via DMA
965  ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
966  }
967 #endif // HAL_USE_SERIAL
968 }
969 
970 
971 // record timestamp of new incoming data
973 {
976 }
977 
978 /*
979  return timestamp estimate in microseconds for when the start of
980  a nbytes packet arrived on the uart. This should be treated as a
981  time constraint, not an exact time. It is guaranteed that the
982  packet did not start being received after this time, but it
983  could have been in a system buffer before the returned time.
984 
985  This takes account of the baudrate of the link. For transports
986  that have no baudrate (such as USB) the time estimate may be
987  less accurate.
988 
989  A return value of zero means the HAL does not support this API
990 */
991 uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
992 {
993  uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
994  if (_baudrate > 0 && !sdef.is_usb) {
995  // assume 10 bits per byte. For USB we assume zero transport delay
996  uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes + available());
997  last_receive_us -= transport_time_us;
998  }
999  return last_receive_us;
1000 }
1001 
1002 #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
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
uint32_t available(void) const
Definition: RingBuffer.cpp:37
static void rx_irq_cb(void *sd)
Definition: UARTDriver.cpp:332
void set_stop_bits(int n) override
Definition: UARTDriver.cpp:943
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
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
#define APM_UART_PRIORITY
Definition: Scheduler.h:29
static thread_t * uart_thread_ctx
Definition: UARTDriver.h:104
Semaphore _write_mutex
Definition: UARTDriver.h:138
#define FALLTHROUGH
Definition: AP_Common.h:50
#define RX_BOUNCE_BUFSIZE
Definition: UARTDriver.h:25
AP_HAL::UARTDriver * console
Definition: HAL.h:110
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
uint8_t * data
Definition: RingBuffer.h:66
const stm32_dma_stream_t * rxdma
Definition: UARTDriver.h:139
ByteBuffer _writebuf
Definition: UARTDriver.h:137
Shared_DMA * dma_handle
Definition: UARTDriver.h:146
bool commit(uint32_t len)
Definition: RingBuffer.cpp:202
void write_pending_bytes_DMA(uint32_t n)
Definition: UARTDriver.cpp:606
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:151
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
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
uint32_t get_size(void) const
Definition: RingBuffer.h:42
uint32_t space(void) const
Definition: RingBuffer.cpp:54
#define MIN(a, b)
Definition: usb_conf.h:215
int16_t read() override
Definition: UARTDriver.cpp:459
void unlock_from_lockzone(void)
Definition: shared_dma.cpp:149
#define TX_BOUNCE_BUFSIZE
Definition: UARTDriver.h:26
virtual void delay(uint16_t ms)=0
bool set_unbuffered_writes(bool on) override
Definition: UARTDriver.cpp:889
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void set_blocking_writes(bool blocking)
Definition: UARTDriver.cpp:428
int(* vprintf_console_hook)(const char *fmt, va_list arg)
Definition: stdio.c:111
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
const char * fmt
Definition: Printf.cpp:14
bool advance(uint32_t n)
Definition: RingBuffer.cpp:116
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
bool set_size(uint32_t size)
Definition: RingBuffer.cpp:20
uint32_t peekbytes(uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:157
#define SHARED_DMA_NONE
Definition: shared_dma.h:24
uint64_t micros64()
Definition: system.cpp:162
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
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:32
bool lock_nonblock(void)
Definition: shared_dma.cpp:104
float v
Definition: Printf.cpp:15
void update_rts_line(void)
Definition: UARTDriver.cpp:871
uint8_t byte
Definition: compat.h:8
uint32_t available() override
Definition: UARTDriver.cpp:436
#define NULL
Definition: hal_types.h:59
bool has_contention(void) const
Definition: shared_dma.h:63
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
void unlock_from_IRQ(void)
Definition: shared_dma.cpp:164
void set_flow_control(enum flow_control flow_control) override
void begin(uint32_t b)
Definition: UARTDriver.cpp:387
uint8_t peekiovec(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:125
void write_pending_bytes(void)
Definition: UARTDriver.cpp:687
#define EVT_DATA
Definition: UARTDriver.cpp:53
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
virtual void virtual void vprintf(const char *, va_list)
AP_HAL::GPIO * gpio
Definition: HAL.h:111
virtual void delay_microseconds(uint16_t us)=0
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 int hal_console_vprintf(const char *fmt, va_list arg)
Definition: UARTDriver.cpp:121
static UARTDriver * uart_drivers[UART_MAX_DRIVERS]
Definition: UARTDriver.h:110
#define FUNCTOR_BIND_MEMBER(func, rettype,...)
Definition: functor.h:31
uint8_t reserve(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:171
#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
uint32_t micros()
Definition: system.cpp:152
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool read_byte(uint8_t *data)
Definition: RingBuffer.cpp:219