UARTDriver.cpp 38 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340
  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. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS && !defined(HAL_NO_UARTDRIVER)
  19. #include "UARTDriver.h"
  20. #include "GPIO.h"
  21. #include <usbcfg.h>
  22. #include "shared_dma.h"
  23. #include <AP_Math/AP_Math.h>
  24. #include "Scheduler.h"
  25. #include "hwdef/common/stm32_util.h"
  26. extern const AP_HAL::HAL& hal;
  27. using namespace ChibiOS;
  28. #ifdef HAL_USB_VENDOR_ID
  29. // USB has been configured in hwdef.dat
  30. #define HAVE_USB_SERIAL
  31. #endif
  32. #if HAL_WITH_IO_MCU
  33. extern ChibiOS::UARTDriver uart_io;
  34. #endif
  35. const UARTDriver::SerialDef UARTDriver::_serial_tab[] = { HAL_UART_DEVICE_LIST };
  36. // handle for UART handling thread
  37. thread_t *UARTDriver::uart_thread_ctx;
  38. // table to find UARTDrivers from serial number, used for event handling
  39. UARTDriver *UARTDriver::uart_drivers[UART_MAX_DRIVERS];
  40. // event used to wake up waiting thread. This event number is for
  41. // caller threads
  42. #define EVT_DATA EVENT_MASK(0)
  43. // event for parity error
  44. #define EVT_PARITY EVENT_MASK(1)
  45. #ifndef HAL_UART_MIN_TX_SIZE
  46. #define HAL_UART_MIN_TX_SIZE 1024
  47. #endif
  48. #ifndef HAL_UART_MIN_RX_SIZE
  49. #define HAL_UART_MIN_RX_SIZE 512
  50. #endif
  51. #ifndef HAL_UART_STACK_SIZE
  52. #define HAL_UART_STACK_SIZE 2048
  53. #endif
  54. UARTDriver::UARTDriver(uint8_t _serial_num) :
  55. serial_num(_serial_num),
  56. sdef(_serial_tab[_serial_num]),
  57. _baudrate(57600)
  58. {
  59. osalDbgAssert(serial_num < UART_MAX_DRIVERS, "too many UART drivers");
  60. uart_drivers[serial_num] = this;
  61. }
  62. /*
  63. thread for handling UART send/receive
  64. We use events indexed by serial_num to trigger a more rapid send for
  65. unbuffered_write uarts, and run at 1kHz for general UART handling
  66. */
  67. void UARTDriver::uart_thread(void* arg)
  68. {
  69. uint32_t last_thread_run_us = 0; // last time we did a 1kHz run of uarts
  70. uart_thread_ctx = chThdGetSelfX();
  71. while (true) {
  72. eventmask_t mask = chEvtWaitAnyTimeout(~0, chTimeMS2I(1));
  73. uint32_t now = AP_HAL::micros();
  74. if (now - last_thread_run_us >= 1000) {
  75. // run them all if it's been more than 1ms since we ran
  76. // them all
  77. mask = ~0;
  78. last_thread_run_us = now;
  79. }
  80. for (uint8_t i=0; i<UART_MAX_DRIVERS; i++) {
  81. if (uart_drivers[i] == nullptr) {
  82. continue;
  83. }
  84. if ((mask & EVENT_MASK(i)) &&
  85. uart_drivers[i]->_initialised) {
  86. uart_drivers[i]->_timer_tick();
  87. }
  88. }
  89. }
  90. }
  91. /*
  92. initialise UART thread
  93. */
  94. void UARTDriver::thread_init(void)
  95. {
  96. if (uart_thread_ctx) {
  97. // already initialised
  98. return;
  99. }
  100. #if CH_CFG_USE_HEAP == TRUE
  101. uart_thread_ctx = thread_create_alloc(THD_WORKING_AREA_SIZE(HAL_UART_STACK_SIZE),
  102. "apm_uart",
  103. APM_UART_PRIORITY,
  104. uart_thread,
  105. this);
  106. #endif
  107. }
  108. #ifndef HAL_STDOUT_SERIAL
  109. /*
  110. hook to allow printf() to work on hal.console when we don't have a
  111. dedicated debug console
  112. */
  113. static int hal_console_vprintf(const char *fmt, va_list arg)
  114. {
  115. hal.console->vprintf(fmt, arg);
  116. return 1; // wrong length, but doesn't matter for what this is used for
  117. }
  118. #endif
  119. void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
  120. {
  121. thread_init();
  122. if (sdef.serial == nullptr) {
  123. return;
  124. }
  125. uint16_t min_tx_buffer = HAL_UART_MIN_TX_SIZE;
  126. uint16_t min_rx_buffer = HAL_UART_MIN_RX_SIZE;
  127. if (sdef.is_usb) {
  128. // give more buffer space for log download on USB
  129. min_tx_buffer *= 4;
  130. }
  131. // on PX4 we have enough memory to have a larger transmit and
  132. // receive buffer for all ports. This means we don't get delays
  133. // while waiting to write GPS config packets
  134. if (txS < min_tx_buffer) {
  135. txS = min_tx_buffer;
  136. }
  137. if (rxS < min_rx_buffer) {
  138. rxS = min_rx_buffer;
  139. }
  140. /*
  141. allocate the read buffer
  142. we allocate buffers before we successfully open the device as we
  143. want to allocate in the early stages of boot, and cause minimum
  144. thrashing of the heap once we are up. The ttyACM0 driver may not
  145. connect for some time after boot
  146. */
  147. while (_in_timer) {
  148. hal.scheduler->delay(1);
  149. }
  150. if (rxS != _readbuf.get_size()) {
  151. _initialised = false;
  152. _readbuf.set_size(rxS);
  153. }
  154. bool clear_buffers = false;
  155. if (b != 0) {
  156. // clear buffers on baudrate change, but not on the console (which is usually USB)
  157. if (_baudrate != b && hal.console != this) {
  158. clear_buffers = true;
  159. }
  160. _baudrate = b;
  161. }
  162. if (clear_buffers) {
  163. _readbuf.clear();
  164. }
  165. #ifndef HAL_UART_NODMA
  166. if (rx_bounce_buf == nullptr) {
  167. rx_bounce_buf = (uint8_t *)hal.util->malloc_type(RX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
  168. }
  169. if (tx_bounce_buf == nullptr) {
  170. tx_bounce_buf = (uint8_t *)hal.util->malloc_type(TX_BOUNCE_BUFSIZE, AP_HAL::Util::MEM_DMA_SAFE);
  171. chVTObjectInit(&tx_timeout);
  172. tx_bounce_buf_ready = true;
  173. }
  174. #endif
  175. /*
  176. allocate the write buffer
  177. */
  178. while (_in_timer) {
  179. hal.scheduler->delay(1);
  180. }
  181. if (txS != _writebuf.get_size()) {
  182. _initialised = false;
  183. _writebuf.set_size(txS);
  184. }
  185. if (clear_buffers) {
  186. _writebuf.clear();
  187. }
  188. if (sdef.is_usb) {
  189. #ifdef HAVE_USB_SERIAL
  190. /*
  191. * Initializes a serial-over-USB CDC driver.
  192. */
  193. if (!_device_initialised) {
  194. if ((SerialUSBDriver*)sdef.serial == &SDU1) {
  195. sduObjectInit(&SDU1);
  196. sduStart(&SDU1, &serusbcfg1);
  197. #if HAL_HAVE_DUAL_USB_CDC
  198. sduObjectInit(&SDU2);
  199. sduStart(&SDU2, &serusbcfg2);
  200. #endif
  201. /*
  202. * Activates the USB driver and then the USB bus pull-up on D+.
  203. * Note, a delay is inserted in order to not have to disconnect the cable
  204. * after a reset.
  205. */
  206. usbDisconnectBus(serusbcfg1.usbp);
  207. hal.scheduler->delay_microseconds(1500);
  208. usbStart(serusbcfg1.usbp, &usbcfg);
  209. usbConnectBus(serusbcfg1.usbp);
  210. }
  211. _device_initialised = true;
  212. }
  213. #endif
  214. } else {
  215. #if HAL_USE_SERIAL == TRUE
  216. if (_baudrate != 0) {
  217. #ifndef HAL_UART_NODMA
  218. bool was_initialised = _device_initialised;
  219. //setup Rx DMA
  220. if(!_device_initialised) {
  221. if(sdef.dma_rx) {
  222. osalDbgAssert(rxdma == nullptr, "double DMA allocation");
  223. chSysLock();
  224. rxdma = dmaStreamAllocI(sdef.dma_rx_stream_id,
  225. 12, //IRQ Priority
  226. (stm32_dmaisr_t)rxbuff_full_irq,
  227. (void *)this);
  228. osalDbgAssert(rxdma, "stream alloc failed");
  229. chSysUnlock();
  230. #if defined(STM32F7) || defined(STM32H7)
  231. dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->RDR);
  232. #else
  233. dmaStreamSetPeripheral(rxdma, &((SerialDriver*)sdef.serial)->usart->DR);
  234. #endif // STM32F7
  235. #if STM32_DMA_SUPPORTS_DMAMUX
  236. dmaSetRequestSource(rxdma, sdef.dma_rx_channel_id);
  237. #endif
  238. }
  239. if (sdef.dma_tx) {
  240. // we only allow for sharing of the TX DMA channel, not the RX
  241. // DMA channel, as the RX side is active all the time, so
  242. // cannot be shared
  243. dma_handle = new Shared_DMA(sdef.dma_tx_stream_id,
  244. SHARED_DMA_NONE,
  245. FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_allocate, void, Shared_DMA *),
  246. FUNCTOR_BIND_MEMBER(&UARTDriver::dma_tx_deallocate, void, Shared_DMA *));
  247. }
  248. _device_initialised = true;
  249. }
  250. #endif // HAL_UART_NODMA
  251. sercfg.speed = _baudrate;
  252. // start with options from set_options()
  253. sercfg.cr1 = 0;
  254. sercfg.cr2 = _cr2_options;
  255. sercfg.cr3 = _cr3_options;
  256. #ifndef HAL_UART_NODMA
  257. if (!sdef.dma_tx && !sdef.dma_rx) {
  258. } else {
  259. if (sdef.dma_rx) {
  260. sercfg.cr1 |= USART_CR1_IDLEIE;
  261. sercfg.cr3 |= USART_CR3_DMAR;
  262. }
  263. if (sdef.dma_tx) {
  264. sercfg.cr3 |= USART_CR3_DMAT;
  265. }
  266. }
  267. sercfg.irq_cb = rx_irq_cb;
  268. #endif // HAL_UART_NODMA
  269. sercfg.cr2 |= USART_CR2_STOP1_BITS;
  270. sercfg.ctx = (void*)this;
  271. sdStart((SerialDriver*)sdef.serial, &sercfg);
  272. #ifndef HAL_UART_NODMA
  273. if(sdef.dma_rx) {
  274. //Configure serial driver to skip handling RX packets
  275. //because we will handle them via DMA
  276. ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
  277. //Start DMA
  278. if(!was_initialised) {
  279. uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
  280. dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_rx_channel_id);
  281. dmamode |= STM32_DMA_CR_PL(0);
  282. dmaStreamSetMemory0(rxdma, rx_bounce_buf);
  283. dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
  284. dmaStreamSetMode(rxdma, dmamode | STM32_DMA_CR_DIR_P2M |
  285. STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
  286. dmaStreamEnable(rxdma);
  287. }
  288. }
  289. #endif // HAL_UART_NODMA
  290. }
  291. #endif // HAL_USE_SERIAL
  292. }
  293. if (_writebuf.get_size() && _readbuf.get_size()) {
  294. _initialised = true;
  295. }
  296. _uart_owner_thd = chThdGetSelfX();
  297. // setup flow control
  298. set_flow_control(_flow_control);
  299. if (serial_num == 0 && _initialised) {
  300. #ifndef HAL_STDOUT_SERIAL
  301. // setup hal.console to take printf() output
  302. vprintf_console_hook = hal_console_vprintf;
  303. #endif
  304. }
  305. }
  306. #ifndef HAL_UART_NODMA
  307. void UARTDriver::dma_tx_allocate(Shared_DMA *ctx)
  308. {
  309. #if HAL_USE_SERIAL == TRUE
  310. if (txdma != nullptr) {
  311. return;
  312. }
  313. chSysLock();
  314. txdma = dmaStreamAllocI(sdef.dma_tx_stream_id,
  315. 12, //IRQ Priority
  316. (stm32_dmaisr_t)tx_complete,
  317. (void *)this);
  318. osalDbgAssert(txdma, "stream alloc failed");
  319. chSysUnlock();
  320. #if defined(STM32F7) || defined(STM32H7)
  321. dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->TDR);
  322. #else
  323. dmaStreamSetPeripheral(txdma, &((SerialDriver*)sdef.serial)->usart->DR);
  324. #endif // STM32F7
  325. #if STM32_DMA_SUPPORTS_DMAMUX
  326. dmaSetRequestSource(txdma, sdef.dma_tx_channel_id);
  327. #endif
  328. #endif // HAL_USE_SERIAL
  329. }
  330. void UARTDriver::dma_tx_deallocate(Shared_DMA *ctx)
  331. {
  332. chSysLock();
  333. dmaStreamFreeI(txdma);
  334. txdma = nullptr;
  335. chSysUnlock();
  336. }
  337. /*
  338. DMA transmit complettion interrupt handler
  339. */
  340. void UARTDriver::tx_complete(void* self, uint32_t flags)
  341. {
  342. UARTDriver* uart_drv = (UARTDriver*)self;
  343. chSysLockFromISR();
  344. if (!uart_drv->tx_bounce_buf_ready) {
  345. // reset timeout
  346. chVTResetI(&uart_drv->tx_timeout);
  347. uart_drv->_last_write_completed_us = AP_HAL::micros();
  348. uart_drv->tx_bounce_buf_ready = true;
  349. if (uart_drv->unbuffered_writes && uart_drv->_writebuf.available()) {
  350. // trigger a rapid send of next bytes
  351. chEvtSignalI(uart_thread_ctx, EVENT_MASK(uart_drv->serial_num));
  352. }
  353. uart_drv->dma_handle->unlock_from_IRQ();
  354. }
  355. chSysUnlockFromISR();
  356. }
  357. void UARTDriver::rx_irq_cb(void* self)
  358. {
  359. #if HAL_USE_SERIAL == TRUE
  360. UARTDriver* uart_drv = (UARTDriver*)self;
  361. if (!uart_drv->sdef.dma_rx) {
  362. return;
  363. }
  364. #if defined(STM32F7) || defined(STM32H7)
  365. //disable dma, triggering DMA transfer complete interrupt
  366. uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
  367. #else
  368. volatile uint16_t sr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->SR;
  369. if(sr & USART_SR_IDLE) {
  370. volatile uint16_t dr = ((SerialDriver*)(uart_drv->sdef.serial))->usart->DR;
  371. (void)dr;
  372. //disable dma, triggering DMA transfer complete interrupt
  373. uart_drv->rxdma->stream->CR &= ~STM32_DMA_CR_EN;
  374. }
  375. #endif // STM32F7
  376. #endif // HAL_USE_SERIAL
  377. }
  378. void UARTDriver::rxbuff_full_irq(void* self, uint32_t flags)
  379. {
  380. #if HAL_USE_SERIAL == TRUE
  381. UARTDriver* uart_drv = (UARTDriver*)self;
  382. if (uart_drv->_lock_rx_in_timer_tick) {
  383. return;
  384. }
  385. if (!uart_drv->sdef.dma_rx) {
  386. return;
  387. }
  388. stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, RX_BOUNCE_BUFSIZE);
  389. uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(uart_drv->rxdma);
  390. if (len > 0) {
  391. if (uart_drv->half_duplex) {
  392. uint32_t now = AP_HAL::micros();
  393. if (now - uart_drv->hd_write_us < uart_drv->hd_read_delay_us) {
  394. len = 0;
  395. }
  396. }
  397. stm32_cacheBufferInvalidate(uart_drv->rx_bounce_buf, len);
  398. uart_drv->_readbuf.write(uart_drv->rx_bounce_buf, len);
  399. uart_drv->receive_timestamp_update();
  400. }
  401. //restart the DMA transfers
  402. dmaStreamSetMemory0(uart_drv->rxdma, uart_drv->rx_bounce_buf);
  403. dmaStreamSetTransactionSize(uart_drv->rxdma, RX_BOUNCE_BUFSIZE);
  404. dmaStreamEnable(uart_drv->rxdma);
  405. if (uart_drv->_wait.thread_ctx && uart_drv->_readbuf.available() >= uart_drv->_wait.n) {
  406. chSysLockFromISR();
  407. chEvtSignalI(uart_drv->_wait.thread_ctx, EVT_DATA);
  408. chSysUnlockFromISR();
  409. }
  410. if (uart_drv->_rts_is_active) {
  411. uart_drv->update_rts_line();
  412. }
  413. #endif // HAL_USE_SERIAL
  414. }
  415. #endif // HAL_UART_NODMA
  416. void UARTDriver::begin(uint32_t b)
  417. {
  418. begin(b, 0, 0);
  419. }
  420. void UARTDriver::end()
  421. {
  422. _initialised = false;
  423. while (_in_timer) hal.scheduler->delay(1);
  424. if (sdef.is_usb) {
  425. #ifdef HAVE_USB_SERIAL
  426. sduStop((SerialUSBDriver*)sdef.serial);
  427. #endif
  428. } else {
  429. #if HAL_USE_SERIAL == TRUE
  430. sdStop((SerialDriver*)sdef.serial);
  431. #endif
  432. }
  433. _readbuf.set_size(0);
  434. _writebuf.set_size(0);
  435. }
  436. void UARTDriver::flush()
  437. {
  438. if (sdef.is_usb) {
  439. #ifdef HAVE_USB_SERIAL
  440. sduSOFHookI((SerialUSBDriver*)sdef.serial);
  441. #endif
  442. } else {
  443. //TODO: Handle this for other serial ports
  444. }
  445. }
  446. bool UARTDriver::is_initialized()
  447. {
  448. return _initialised;
  449. }
  450. void UARTDriver::set_blocking_writes(bool blocking)
  451. {
  452. _blocking_writes = blocking;
  453. }
  454. bool UARTDriver::tx_pending() { return false; }
  455. /* Empty implementations of Stream virtual methods */
  456. uint32_t UARTDriver::available() {
  457. if (!_initialised || lock_read_key) {
  458. return 0;
  459. }
  460. if (sdef.is_usb) {
  461. #ifdef HAVE_USB_SERIAL
  462. if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) {
  463. return 0;
  464. }
  465. #endif
  466. }
  467. return _readbuf.available();
  468. }
  469. uint32_t UARTDriver::txspace()
  470. {
  471. if (!_initialised) {
  472. return 0;
  473. }
  474. return _writebuf.space();
  475. }
  476. int16_t UARTDriver::read()
  477. {
  478. if (lock_read_key != 0 || _uart_owner_thd != chThdGetSelfX()){
  479. return -1;
  480. }
  481. if (!_initialised) {
  482. return -1;
  483. }
  484. uint8_t byte;
  485. if (!_readbuf.read_byte(&byte)) {
  486. return -1;
  487. }
  488. if (!_rts_is_active) {
  489. update_rts_line();
  490. }
  491. return byte;
  492. }
  493. int16_t UARTDriver::read_locked(uint32_t key)
  494. {
  495. if (lock_read_key != 0 && key != lock_read_key) {
  496. return -1;
  497. }
  498. if (!_initialised) {
  499. return -1;
  500. }
  501. uint8_t byte;
  502. if (!_readbuf.read_byte(&byte)) {
  503. return -1;
  504. }
  505. if (!_rts_is_active) {
  506. update_rts_line();
  507. }
  508. return byte;
  509. }
  510. /* Empty implementations of Print virtual methods */
  511. size_t UARTDriver::write(uint8_t c)
  512. {
  513. if (lock_write_key != 0 || !_write_mutex.take_nonblocking()) {
  514. return 0;
  515. }
  516. if (!_initialised) {
  517. _write_mutex.give();
  518. return 0;
  519. }
  520. while (_writebuf.space() == 0) {
  521. if (!_blocking_writes || unbuffered_writes) {
  522. _write_mutex.give();
  523. return 0;
  524. }
  525. hal.scheduler->delay(1);
  526. }
  527. size_t ret = _writebuf.write(&c, 1);
  528. if (unbuffered_writes) {
  529. write_pending_bytes();
  530. }
  531. _write_mutex.give();
  532. return ret;
  533. }
  534. size_t UARTDriver::write(const uint8_t *buffer, size_t size)
  535. {
  536. if (!_initialised || lock_write_key != 0) {
  537. return 0;
  538. }
  539. if (_blocking_writes && unbuffered_writes) {
  540. _write_mutex.take_blocking();
  541. } else {
  542. if (!_write_mutex.take_nonblocking()) {
  543. return 0;
  544. }
  545. }
  546. if (_blocking_writes && !unbuffered_writes) {
  547. /*
  548. use the per-byte delay loop in write() above for blocking writes
  549. */
  550. _write_mutex.give();
  551. size_t ret = 0;
  552. while (size--) {
  553. if (write(*buffer++) != 1) break;
  554. ret++;
  555. }
  556. return ret;
  557. }
  558. size_t ret = _writebuf.write(buffer, size);
  559. if (unbuffered_writes) {
  560. write_pending_bytes();
  561. }
  562. _write_mutex.give();
  563. return ret;
  564. }
  565. /*
  566. lock the uart for exclusive use by write_locked() and read_locked() with the right key
  567. */
  568. bool UARTDriver::lock_port(uint32_t write_key, uint32_t read_key)
  569. {
  570. if (lock_write_key && write_key != lock_write_key && read_key != 0) {
  571. // someone else is using it
  572. return false;
  573. }
  574. if (lock_read_key && read_key != lock_read_key && read_key != 0) {
  575. // someone else is using it
  576. return false;
  577. }
  578. lock_write_key = write_key;
  579. lock_read_key = read_key;
  580. return true;
  581. }
  582. /*
  583. write to a locked port. If port is locked and key is not correct then 0 is returned
  584. and write is discarded. All writes are non-blocking
  585. */
  586. size_t UARTDriver::write_locked(const uint8_t *buffer, size_t size, uint32_t key)
  587. {
  588. if (lock_write_key != 0 && key != lock_write_key) {
  589. return 0;
  590. }
  591. if (!_write_mutex.take_nonblocking()) {
  592. return 0;
  593. }
  594. size_t ret = _writebuf.write(buffer, size);
  595. _write_mutex.give();
  596. return ret;
  597. }
  598. /*
  599. wait for data to arrive, or a timeout. Return true if data has
  600. arrived, false on timeout
  601. */
  602. bool UARTDriver::wait_timeout(uint16_t n, uint32_t timeout_ms)
  603. {
  604. uint32_t t0 = AP_HAL::millis();
  605. while (available() < n) {
  606. chEvtGetAndClearEvents(EVT_DATA);
  607. _wait.n = n;
  608. _wait.thread_ctx = chThdGetSelfX();
  609. uint32_t now = AP_HAL::millis();
  610. if (now - t0 >= timeout_ms) {
  611. break;
  612. }
  613. chEvtWaitAnyTimeout(EVT_DATA, chTimeMS2I(timeout_ms - (now - t0)));
  614. }
  615. return available() >= n;
  616. }
  617. #ifndef HAL_UART_NODMA
  618. /*
  619. check for DMA completed for TX
  620. */
  621. void UARTDriver::check_dma_tx_completion(void)
  622. {
  623. chSysLock();
  624. if (!tx_bounce_buf_ready) {
  625. if (!(txdma->stream->CR & STM32_DMA_CR_EN)) {
  626. if (dmaStreamGetTransactionSize(txdma) == 0) {
  627. tx_bounce_buf_ready = true;
  628. _last_write_completed_us = AP_HAL::micros();
  629. chVTResetI(&tx_timeout);
  630. dma_handle->unlock_from_lockzone();
  631. }
  632. }
  633. }
  634. chSysUnlock();
  635. }
  636. /*
  637. handle a TX timeout. This can happen with using hardware flow
  638. control if CTS pin blocks transmit
  639. */
  640. void UARTDriver::handle_tx_timeout(void *arg)
  641. {
  642. UARTDriver* uart_drv = (UARTDriver*)arg;
  643. chSysLockFromISR();
  644. if (!uart_drv->tx_bounce_buf_ready) {
  645. dmaStreamDisable(uart_drv->txdma);
  646. uart_drv->tx_len -= dmaStreamGetTransactionSize(uart_drv->txdma);
  647. uart_drv->tx_bounce_buf_ready = true;
  648. uart_drv->dma_handle->unlock_from_IRQ();
  649. }
  650. chSysUnlockFromISR();
  651. }
  652. /*
  653. write out pending bytes with DMA
  654. */
  655. void UARTDriver::write_pending_bytes_DMA(uint32_t n)
  656. {
  657. check_dma_tx_completion();
  658. if (!tx_bounce_buf_ready) {
  659. return;
  660. }
  661. /* TX DMA channel preparation.*/
  662. _total_written += tx_len;
  663. _writebuf.advance(tx_len);
  664. tx_len = _writebuf.peekbytes(tx_bounce_buf, MIN(n, TX_BOUNCE_BUFSIZE));
  665. if (tx_len == 0) {
  666. return;
  667. }
  668. if (!dma_handle->lock_nonblock()) {
  669. tx_len = 0;
  670. return;
  671. }
  672. if (dma_handle->has_contention()) {
  673. /*
  674. someone else is using this same DMA channel. To reduce
  675. latency we will drop the TX size with DMA on this UART to
  676. keep TX times below 250us. This can still suffer from long
  677. times due to CTS blockage
  678. */
  679. uint32_t max_tx_bytes = 1 + (_baudrate * 250UL / 1000000UL);
  680. if (tx_len > max_tx_bytes) {
  681. tx_len = max_tx_bytes;
  682. }
  683. }
  684. if (half_duplex) {
  685. half_duplex_setup_delay(tx_len);
  686. }
  687. tx_bounce_buf_ready = false;
  688. osalDbgAssert(txdma != nullptr, "UART TX DMA allocation failed");
  689. stm32_cacheBufferFlush(tx_bounce_buf, tx_len);
  690. dmaStreamSetMemory0(txdma, tx_bounce_buf);
  691. dmaStreamSetTransactionSize(txdma, tx_len);
  692. uint32_t dmamode = STM32_DMA_CR_DMEIE | STM32_DMA_CR_TEIE;
  693. dmamode |= STM32_DMA_CR_CHSEL(sdef.dma_tx_channel_id);
  694. dmamode |= STM32_DMA_CR_PL(0);
  695. dmaStreamSetMode(txdma, dmamode | STM32_DMA_CR_DIR_M2P |
  696. STM32_DMA_CR_MINC | STM32_DMA_CR_TCIE);
  697. dmaStreamEnable(txdma);
  698. uint32_t timeout_us = ((1000000UL * (tx_len+2) * 10) / _baudrate) + 500;
  699. chVTSet(&tx_timeout, chTimeUS2I(timeout_us), handle_tx_timeout, this);
  700. }
  701. #endif // HAL_UART_NODMA
  702. /*
  703. write any pending bytes to the device, non-DMA method
  704. */
  705. void UARTDriver::write_pending_bytes_NODMA(uint32_t n)
  706. {
  707. ByteBuffer::IoVec vec[2];
  708. uint16_t nwritten = 0;
  709. const auto n_vec = _writebuf.peekiovec(vec, n);
  710. for (int i = 0; i < n_vec; i++) {
  711. int ret = -1;
  712. if (sdef.is_usb) {
  713. ret = 0;
  714. #ifdef HAVE_USB_SERIAL
  715. ret = chnWriteTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
  716. #endif
  717. } else {
  718. #if HAL_USE_SERIAL == TRUE
  719. ret = chnWriteTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
  720. #endif
  721. }
  722. if (ret < 0) {
  723. break;
  724. }
  725. if (ret > 0) {
  726. _last_write_completed_us = AP_HAL::micros();
  727. nwritten += ret;
  728. }
  729. _writebuf.advance(ret);
  730. /* We wrote less than we asked for, stop */
  731. if ((unsigned)ret != vec[i].len) {
  732. break;
  733. }
  734. }
  735. _total_written += nwritten;
  736. if (half_duplex) {
  737. half_duplex_setup_delay(nwritten);
  738. }
  739. }
  740. /*
  741. write any pending bytes to the device
  742. */
  743. void UARTDriver::write_pending_bytes(void)
  744. {
  745. uint32_t n;
  746. #ifndef HAL_UART_NODMA
  747. if (sdef.dma_tx) {
  748. check_dma_tx_completion();
  749. }
  750. #endif
  751. // write any pending bytes
  752. n = _writebuf.available();
  753. if (n <= 0) {
  754. return;
  755. }
  756. #ifndef HAL_UART_NODMA
  757. if (sdef.dma_tx) {
  758. write_pending_bytes_DMA(n);
  759. } else
  760. #endif
  761. {
  762. write_pending_bytes_NODMA(n);
  763. }
  764. // handle AUTO flow control mode
  765. if (_flow_control == FLOW_CONTROL_AUTO) {
  766. if (_first_write_started_us == 0) {
  767. _first_write_started_us = AP_HAL::micros();
  768. }
  769. #ifndef HAL_UART_NODMA
  770. if (sdef.dma_tx) {
  771. // when we are using DMA we have a reliable indication that a write
  772. // has completed from the DMA completion interrupt
  773. if (_last_write_completed_us != 0) {
  774. _flow_control = FLOW_CONTROL_ENABLE;
  775. return;
  776. }
  777. } else
  778. #endif
  779. {
  780. // without DMA we need to look at the number of bytes written into the queue versus the
  781. // remaining queue space
  782. uint32_t space = qSpaceI(&((SerialDriver*)sdef.serial)->oqueue);
  783. uint32_t used = SERIAL_BUFFERS_SIZE - space;
  784. // threshold is 8 for the GCS_Common code to unstick SiK radios, which
  785. // sends 6 bytes with flow control disabled
  786. const uint8_t threshold = 8;
  787. if (_total_written > used && _total_written - used > threshold) {
  788. _flow_control = FLOW_CONTROL_ENABLE;
  789. return;
  790. }
  791. }
  792. if (AP_HAL::micros() - _first_write_started_us > 500*1000UL) {
  793. // it doesn't look like hw flow control is working
  794. hal.console->printf("disabling flow control on serial %u\n", sdef.get_index());
  795. set_flow_control(FLOW_CONTROL_DISABLE);
  796. }
  797. }
  798. }
  799. /*
  800. setup a delay after writing bytes to a half duplex UART to prevent
  801. read-back of the same bytes that we wrote. half-duplex protocols
  802. tend to have quite loose timing, which makes this possible
  803. */
  804. void UARTDriver::half_duplex_setup_delay(uint16_t len)
  805. {
  806. const uint16_t pad_us = 1000;
  807. hd_write_us = AP_HAL::micros();
  808. hd_read_delay_us = ((1000000UL * len * 10) / _baudrate) + pad_us;
  809. }
  810. /*
  811. push any pending bytes to/from the serial port. This is called at
  812. 1kHz in the timer thread. Doing it this way reduces the system call
  813. overhead in the main task enormously.
  814. */
  815. void UARTDriver::_timer_tick(void)
  816. {
  817. if (!_initialised) return;
  818. #ifndef HAL_UART_NODMA
  819. if (sdef.dma_rx && rxdma) {
  820. _lock_rx_in_timer_tick = true;
  821. //Check if DMA is enabled
  822. //if not, it might be because the DMA interrupt was silenced
  823. //let's handle that here so that we can continue receiving
  824. if (!(rxdma->stream->CR & STM32_DMA_CR_EN)) {
  825. uint8_t len = RX_BOUNCE_BUFSIZE - dmaStreamGetTransactionSize(rxdma);
  826. if (len != 0) {
  827. stm32_cacheBufferInvalidate(rx_bounce_buf, len);
  828. _readbuf.write(rx_bounce_buf, len);
  829. receive_timestamp_update();
  830. if (_rts_is_active) {
  831. update_rts_line();
  832. }
  833. }
  834. //DMA disabled by idle interrupt never got a chance to be handled
  835. //we will enable it here
  836. dmaStreamSetMemory0(rxdma, rx_bounce_buf);
  837. dmaStreamSetTransactionSize(rxdma, RX_BOUNCE_BUFSIZE);
  838. dmaStreamEnable(rxdma);
  839. }
  840. _lock_rx_in_timer_tick = false;
  841. }
  842. #endif
  843. // don't try IO on a disconnected USB port
  844. if (sdef.is_usb) {
  845. #ifdef HAVE_USB_SERIAL
  846. if (((SerialUSBDriver*)sdef.serial)->config->usbp->state != USB_ACTIVE) {
  847. return;
  848. }
  849. #endif
  850. }
  851. if(sdef.is_usb) {
  852. #ifdef HAVE_USB_SERIAL
  853. ((GPIO *)hal.gpio)->set_usb_connected();
  854. #endif
  855. }
  856. _in_timer = true;
  857. #ifndef HAL_UART_NODMA
  858. if (!sdef.dma_rx)
  859. #endif
  860. {
  861. // try to fill the read buffer
  862. ByteBuffer::IoVec vec[2];
  863. const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
  864. for (int i = 0; i < n_vec; i++) {
  865. int ret = 0;
  866. //Do a non-blocking read
  867. if (sdef.is_usb) {
  868. #ifdef HAVE_USB_SERIAL
  869. ret = chnReadTimeout((SerialUSBDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
  870. #endif
  871. } else {
  872. #if HAL_USE_SERIAL == TRUE
  873. ret = chnReadTimeout((SerialDriver*)sdef.serial, vec[i].data, vec[i].len, TIME_IMMEDIATE);
  874. #endif
  875. }
  876. if (ret < 0) {
  877. break;
  878. }
  879. #if CH_CFG_USE_EVENTS == TRUE
  880. if (parity_enabled && ((chEvtGetAndClearFlags(&ev_listener) & SD_PARITY_ERROR))) {
  881. // discard bytes with parity error
  882. ret = -1;
  883. }
  884. #endif
  885. if (half_duplex) {
  886. uint32_t now = AP_HAL::micros();
  887. if (now - hd_write_us < hd_read_delay_us) {
  888. break;
  889. }
  890. }
  891. _readbuf.commit((unsigned)ret);
  892. receive_timestamp_update();
  893. /* stop reading as we read less than we asked for */
  894. if ((unsigned)ret < vec[i].len) {
  895. break;
  896. }
  897. }
  898. }
  899. if (_wait.thread_ctx && _readbuf.available() >= _wait.n) {
  900. chEvtSignal(_wait.thread_ctx, EVT_DATA);
  901. }
  902. if (unbuffered_writes) {
  903. // now send pending bytes. If we are doing "unbuffered" writes
  904. // then the send normally happens as soon as the bytes are
  905. // provided by the write() call, but if the write is larger
  906. // than the DMA buffer size then there can be extra bytes to
  907. // send here, and they must be sent with the write lock held
  908. _write_mutex.take(HAL_SEMAPHORE_BLOCK_FOREVER);
  909. write_pending_bytes();
  910. _write_mutex.give();
  911. } else {
  912. write_pending_bytes();
  913. }
  914. _in_timer = false;
  915. }
  916. /*
  917. change flow control mode for port
  918. */
  919. void UARTDriver::set_flow_control(enum flow_control flowcontrol)
  920. {
  921. if (sdef.rts_line == 0 || sdef.is_usb) {
  922. // no hw flow control available
  923. return;
  924. }
  925. #if HAL_USE_SERIAL == TRUE
  926. SerialDriver *sd = (SerialDriver*)(sdef.serial);
  927. _flow_control = flowcontrol;
  928. if (!_initialised) {
  929. // not ready yet, we just set variable for when we call begin
  930. return;
  931. }
  932. switch (_flow_control) {
  933. case FLOW_CONTROL_DISABLE:
  934. // force RTS active when flow disabled
  935. palSetLineMode(sdef.rts_line, 1);
  936. palClearLine(sdef.rts_line);
  937. _rts_is_active = true;
  938. // disable hardware CTS support
  939. chSysLock();
  940. if ((sd->usart->CR3 & (USART_CR3_CTSE | USART_CR3_RTSE)) != 0) {
  941. sd->usart->CR1 &= ~USART_CR1_UE;
  942. sd->usart->CR3 &= ~(USART_CR3_CTSE | USART_CR3_RTSE);
  943. sd->usart->CR1 |= USART_CR1_UE;
  944. }
  945. chSysUnlock();
  946. break;
  947. case FLOW_CONTROL_AUTO:
  948. // reset flow control auto state machine
  949. _first_write_started_us = 0;
  950. _last_write_completed_us = 0;
  951. FALLTHROUGH;
  952. case FLOW_CONTROL_ENABLE:
  953. // we do RTS in software as STM32 hardware RTS support toggles
  954. // the pin for every byte which loses a lot of bandwidth
  955. palSetLineMode(sdef.rts_line, 1);
  956. palClearLine(sdef.rts_line);
  957. _rts_is_active = true;
  958. // enable hardware CTS support, disable RTS support as we do that in software
  959. chSysLock();
  960. if ((sd->usart->CR3 & (USART_CR3_CTSE | USART_CR3_RTSE)) != USART_CR3_CTSE) {
  961. // CTSE and RTSE can only be written when uart is disabled
  962. sd->usart->CR1 &= ~USART_CR1_UE;
  963. sd->usart->CR3 |= USART_CR3_CTSE;
  964. sd->usart->CR3 &= ~USART_CR3_RTSE;
  965. sd->usart->CR1 |= USART_CR1_UE;
  966. }
  967. chSysUnlock();
  968. break;
  969. }
  970. #endif // HAL_USE_SERIAL
  971. }
  972. /*
  973. software update of rts line. We don't use the HW support for RTS as
  974. it has no hysteresis, so it ends up toggling RTS on every byte
  975. */
  976. void UARTDriver::update_rts_line(void)
  977. {
  978. if (sdef.rts_line == 0 || _flow_control == FLOW_CONTROL_DISABLE) {
  979. return;
  980. }
  981. uint16_t space = _readbuf.space();
  982. if (_rts_is_active && space < 16) {
  983. _rts_is_active = false;
  984. palSetLine(sdef.rts_line);
  985. } else if (!_rts_is_active && space > 32) {
  986. _rts_is_active = true;
  987. palClearLine(sdef.rts_line);
  988. }
  989. }
  990. /*
  991. setup unbuffered writes for lower latency
  992. */
  993. bool UARTDriver::set_unbuffered_writes(bool on)
  994. {
  995. #ifdef HAL_UART_NODMA
  996. return false;
  997. #else
  998. if (on && !sdef.dma_tx) {
  999. // we can't implement low latemcy writes safely without TX DMA
  1000. return false;
  1001. }
  1002. unbuffered_writes = on;
  1003. return true;
  1004. #endif
  1005. }
  1006. /*
  1007. setup parity
  1008. */
  1009. void UARTDriver::configure_parity(uint8_t v)
  1010. {
  1011. if (sdef.is_usb) {
  1012. // not possible
  1013. return;
  1014. }
  1015. #if HAL_USE_SERIAL == TRUE
  1016. // stop and start to take effect
  1017. sdStop((SerialDriver*)sdef.serial);
  1018. #ifdef USART_CR1_M0
  1019. // cope with F7 where there are 2 bits in CR1_M
  1020. const uint32_t cr1_m0 = USART_CR1_M0;
  1021. #else
  1022. const uint32_t cr1_m0 = USART_CR1_M;
  1023. #endif
  1024. switch (v) {
  1025. case 0:
  1026. // no parity
  1027. sercfg.cr1 &= ~(USART_CR1_PCE | USART_CR1_PS | USART_CR1_M);
  1028. break;
  1029. case 1:
  1030. // odd parity
  1031. // setting USART_CR1_M ensures extra bit is used as parity
  1032. // not last bit of data
  1033. sercfg.cr1 |= cr1_m0 | USART_CR1_PCE;
  1034. sercfg.cr1 |= USART_CR1_PS;
  1035. break;
  1036. case 2:
  1037. // even parity
  1038. sercfg.cr1 |= cr1_m0 | USART_CR1_PCE;
  1039. sercfg.cr1 &= ~USART_CR1_PS;
  1040. break;
  1041. }
  1042. sdStart((SerialDriver*)sdef.serial, &sercfg);
  1043. #if CH_CFG_USE_EVENTS == TRUE
  1044. if (parity_enabled) {
  1045. chEvtUnregister(chnGetEventSource((SerialDriver*)sdef.serial), &ev_listener);
  1046. }
  1047. parity_enabled = (v != 0);
  1048. if (parity_enabled) {
  1049. chEvtRegisterMaskWithFlags(chnGetEventSource((SerialDriver*)sdef.serial),
  1050. &ev_listener,
  1051. EVT_PARITY,
  1052. SD_PARITY_ERROR);
  1053. }
  1054. #endif
  1055. #ifndef HAL_UART_NODMA
  1056. if(sdef.dma_rx) {
  1057. //Configure serial driver to skip handling RX packets
  1058. //because we will handle them via DMA
  1059. ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
  1060. }
  1061. #endif
  1062. #endif // HAL_USE_SERIAL
  1063. }
  1064. /*
  1065. set stop bits
  1066. */
  1067. void UARTDriver::set_stop_bits(int n)
  1068. {
  1069. if (sdef.is_usb) {
  1070. // not possible
  1071. return;
  1072. }
  1073. #if HAL_USE_SERIAL
  1074. // stop and start to take effect
  1075. sdStop((SerialDriver*)sdef.serial);
  1076. switch (n) {
  1077. case 1:
  1078. sercfg.cr2 = _cr2_options | USART_CR2_STOP1_BITS;
  1079. break;
  1080. case 2:
  1081. sercfg.cr2 = _cr2_options | USART_CR2_STOP2_BITS;
  1082. break;
  1083. }
  1084. sdStart((SerialDriver*)sdef.serial, &sercfg);
  1085. #ifndef HAL_UART_NODMA
  1086. if(sdef.dma_rx) {
  1087. //Configure serial driver to skip handling RX packets
  1088. //because we will handle them via DMA
  1089. ((SerialDriver*)sdef.serial)->usart->CR1 &= ~USART_CR1_RXNEIE;
  1090. }
  1091. #endif
  1092. #endif // HAL_USE_SERIAL
  1093. }
  1094. // record timestamp of new incoming data
  1095. void UARTDriver::receive_timestamp_update(void)
  1096. {
  1097. _receive_timestamp[_receive_timestamp_idx^1] = AP_HAL::micros64();
  1098. _receive_timestamp_idx ^= 1;
  1099. }
  1100. /*
  1101. return timestamp estimate in microseconds for when the start of
  1102. a nbytes packet arrived on the uart. This should be treated as a
  1103. time constraint, not an exact time. It is guaranteed that the
  1104. packet did not start being received after this time, but it
  1105. could have been in a system buffer before the returned time.
  1106. This takes account of the baudrate of the link. For transports
  1107. that have no baudrate (such as USB) the time estimate may be
  1108. less accurate.
  1109. A return value of zero means the HAL does not support this API
  1110. */
  1111. uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
  1112. {
  1113. uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
  1114. if (_baudrate > 0 && !sdef.is_usb) {
  1115. // assume 10 bits per byte. For USB we assume zero transport delay
  1116. uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes + available());
  1117. last_receive_us -= transport_time_us;
  1118. }
  1119. return last_receive_us;
  1120. }
  1121. // set optional features, return true on success
  1122. bool UARTDriver::set_options(uint8_t options)
  1123. {
  1124. if (sdef.is_usb) {
  1125. // no options allowed on USB
  1126. return (options == 0);
  1127. }
  1128. bool ret = true;
  1129. _last_options = options;
  1130. #if HAL_USE_SERIAL == TRUE
  1131. SerialDriver *sd = (SerialDriver*)(sdef.serial);
  1132. uint32_t cr2 = sd->usart->CR2;
  1133. uint32_t cr3 = sd->usart->CR3;
  1134. bool was_enabled = (sd->usart->CR1 & USART_CR1_UE);
  1135. #if defined(STM32F7) || defined(STM32H7)
  1136. // F7 has built-in support for inversion in all uarts
  1137. if (options & OPTION_RXINV) {
  1138. cr2 |= USART_CR2_RXINV;
  1139. _cr2_options |= USART_CR2_RXINV;
  1140. } else {
  1141. cr2 &= ~USART_CR2_RXINV;
  1142. }
  1143. if (options & OPTION_TXINV) {
  1144. cr2 |= USART_CR2_TXINV;
  1145. _cr2_options |= USART_CR2_TXINV;
  1146. } else {
  1147. cr2 &= ~USART_CR2_TXINV;
  1148. }
  1149. // F7 can also support swapping RX and TX pins
  1150. if (options & OPTION_SWAP) {
  1151. cr2 |= USART_CR2_SWAP;
  1152. _cr2_options |= USART_CR2_SWAP;
  1153. } else {
  1154. cr2 &= ~USART_CR2_SWAP;
  1155. }
  1156. #else // STM32F4
  1157. // F4 can do inversion by GPIO if enabled in hwdef.dat, using
  1158. // TXINV and RXINV options
  1159. if (options & OPTION_RXINV) {
  1160. if (sdef.rxinv_gpio >= 0) {
  1161. hal.gpio->write(sdef.rxinv_gpio, sdef.rxinv_polarity);
  1162. } else {
  1163. ret = false;
  1164. }
  1165. }
  1166. if (options & OPTION_TXINV) {
  1167. if (sdef.txinv_gpio >= 0) {
  1168. hal.gpio->write(sdef.txinv_gpio, sdef.txinv_polarity);
  1169. } else {
  1170. ret = false;
  1171. }
  1172. }
  1173. if (options & OPTION_SWAP) {
  1174. ret = false;
  1175. }
  1176. #endif // STM32xx
  1177. // both F4 and F7 can do half-duplex
  1178. if (options & OPTION_HDPLEX) {
  1179. cr3 |= USART_CR3_HDSEL;
  1180. _cr3_options |= USART_CR3_HDSEL;
  1181. half_duplex = true;
  1182. } else {
  1183. cr3 &= ~USART_CR3_HDSEL;
  1184. }
  1185. if (sd->usart->CR2 == cr2 &&
  1186. sd->usart->CR3 == cr3) {
  1187. // no change
  1188. return ret;
  1189. }
  1190. if (was_enabled) {
  1191. sd->usart->CR1 &= ~USART_CR1_UE;
  1192. }
  1193. sd->usart->CR2 = cr2;
  1194. sd->usart->CR3 = cr3;
  1195. if (was_enabled) {
  1196. sd->usart->CR1 |= USART_CR1_UE;
  1197. }
  1198. #endif // HAL_USE_SERIAL == TRUE
  1199. return ret;
  1200. }
  1201. // get optional features
  1202. uint8_t UARTDriver::get_options(void) const
  1203. {
  1204. return _last_options;
  1205. }
  1206. #endif //CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS