forked from betaflight/betaflight
-
Notifications
You must be signed in to change notification settings - Fork 1
/
serial_uart_hal.c
434 lines (364 loc) · 14.7 KB
/
serial_uart_hal.c
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
/*
* This file is part of Cleanflight and Betaflight.
*
* Cleanflight and Betaflight are free software. You can redistribute
* this software and/or modify this software 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.
*
* Cleanflight and Betaflight are distributed in the hope that they
* 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 software.
*
* If not, see <http://www.gnu.org/licenses/>.
*/
/*
* Authors:
* jflyper - Refactoring, cleanup and made pin-configurable
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
* Hamasaki/Timecop - Initial baseflight code
*/
#include <stdbool.h>
#include <stdint.h>
#include <stdlib.h>
#include "platform.h"
#include "build/debug.h"
#ifdef USE_UART
#include "build/build_config.h"
#include "build/atomic.h"
#include "common/utils.h"
#include "drivers/io.h"
#include "drivers/nvic.h"
#include "drivers/inverter.h"
#include "drivers/dma.h"
#include "drivers/rcc.h"
#include "drivers/serial.h"
#include "drivers/serial_uart.h"
#include "drivers/serial_uart_impl.h"
static void usartConfigurePinInversion(uartPort_t *uartPort)
{
bool inverted = uartPort->port.options & SERIAL_INVERTED;
if (inverted)
{
if (uartPort->port.mode & MODE_RX)
{
uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_RXINVERT_INIT;
uartPort->Handle.AdvancedInit.RxPinLevelInvert = UART_ADVFEATURE_RXINV_ENABLE;
}
if (uartPort->port.mode & MODE_TX)
{
uartPort->Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_TXINVERT_INIT;
uartPort->Handle.AdvancedInit.TxPinLevelInvert = UART_ADVFEATURE_TXINV_ENABLE;
}
}
}
static uartDevice_t *uartFindDevice(uartPort_t *uartPort)
{
for (uint32_t i = 0; i < UARTDEV_COUNT_MAX; i++) {
uartDevice_t *candidate = uartDevmap[i];
if (&candidate->port == uartPort) {
return candidate;
}
}
return NULL;
}
#if !(defined(STM32F4))
static void uartConfigurePinSwap(uartPort_t *uartPort)
{
uartDevice_t *uartDevice = uartFindDevice(uartPort);
if (!uartDevice) {
return;
}
if (uartDevice->pinSwap) {
uartDevice->port.Handle.AdvancedInit.AdvFeatureInit |= UART_ADVFEATURE_SWAP_INIT;
uartDevice->port.Handle.AdvancedInit.Swap = UART_ADVFEATURE_SWAP_ENABLE;
}
}
#endif
// XXX uartReconfigure does not handle resource management properly.
void uartReconfigure(uartPort_t *uartPort)
{
HAL_UART_DeInit(&uartPort->Handle);
uartPort->Handle.Init.BaudRate = uartPort->port.baudRate;
// according to the stm32 documentation wordlen has to be 9 for parity bits
// this does not seem to matter for rx but will give bad data on tx!
uartPort->Handle.Init.WordLength = (uartPort->port.options & SERIAL_PARITY_EVEN) ? UART_WORDLENGTH_9B : UART_WORDLENGTH_8B;
uartPort->Handle.Init.StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_STOPBITS_2 : USART_STOPBITS_1;
uartPort->Handle.Init.Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_PARITY_EVEN : USART_PARITY_NONE;
uartPort->Handle.Init.HwFlowCtl = UART_HWCONTROL_NONE;
uartPort->Handle.Init.OneBitSampling = UART_ONE_BIT_SAMPLE_DISABLE;
uartPort->Handle.Init.Mode = 0;
#if defined(STM32G4) || defined(STM32H7)
if (uartPort->Handle.Instance == LPUART1) {
uartPort->Handle.Init.ClockPrescaler = UART_PRESCALER_DIV8;
}
#endif
if (uartPort->port.mode & MODE_RX)
uartPort->Handle.Init.Mode |= UART_MODE_RX;
if (uartPort->port.mode & MODE_TX)
uartPort->Handle.Init.Mode |= UART_MODE_TX;
usartConfigurePinInversion(uartPort);
#if !(defined(STM32F1) || defined(STM32F4))
uartConfigurePinSwap(uartPort);
#endif
#ifdef TARGET_USART_CONFIG
void usartTargetConfigure(uartPort_t *);
usartTargetConfigure(uartPort);
#endif
if (uartPort->port.options & SERIAL_BIDIR)
{
HAL_HalfDuplex_Init(&uartPort->Handle);
}
else
{
HAL_UART_Init(&uartPort->Handle);
}
// Receive DMA or IRQ
if (uartPort->port.mode & MODE_RX)
{
#ifdef USE_DMA
if (uartPort->rxDMAResource)
{
uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource;
#if !(defined(STM32H7) || defined(STM32G4))
uartPort->rxDMAHandle.Init.Channel = uartPort->rxDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->rxDMAChannel;
#endif
uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY;
uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR;
#if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
#endif
uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&uartPort->rxDMAHandle);
HAL_DMA_Init(&uartPort->rxDMAHandle);
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle);
HAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize);
uartPort->rxDMAPos = __HAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle);
} else
#endif
{
/* Enable the UART Parity Error Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_PEIE);
/* Enable the UART Error Interrupt: (Frame error, noise error, overrun error) */
SET_BIT(uartPort->USARTx->CR3, USART_CR3_EIE);
/* Enable the UART Data Register not empty Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_RXNEIE);
/* Enable Idle Line detection */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_IDLEIE);
}
}
// Transmit DMA or IRQ
if (uartPort->port.mode & MODE_TX) {
#ifdef USE_DMA
if (uartPort->txDMAResource) {
uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource;
#if !(defined(STM32H7) || defined(STM32G4))
uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel;
#else
uartPort->txDMAHandle.Init.Request = uartPort->txDMAChannel;
#endif
uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH;
uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE;
uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE;
uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
uartPort->txDMAHandle.Init.Mode = DMA_NORMAL;
#if !defined(STM32G4)
// G4's DMA is channel based, and does not have FIFO
uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE;
uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE;
#endif
uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM;
HAL_DMA_DeInit(&uartPort->txDMAHandle);
HAL_StatusTypeDef status = HAL_DMA_Init(&uartPort->txDMAHandle);
if (status != HAL_OK)
{
while (1);
}
/* Associate the initialized DMA handle to the UART handle */
__HAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle);
__HAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0);
} else
#endif
{
/* Enable the UART Transmit Data Register Empty Interrupt */
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TXEIE);
SET_BIT(uartPort->USARTx->CR1, USART_CR1_TCIE);
}
}
return;
}
bool checkUsartTxOutput(uartPort_t *s)
{
uartDevice_t *uart = container_of(s, uartDevice_t, port);
IO_t txIO = IOGetByTag(uart->tx.pin);
if ((uart->txPinState == TX_PIN_MONITOR) && txIO) {
if (IORead(txIO)) {
// TX is high so we're good to transmit
// Enable USART TX output
uart->txPinState = TX_PIN_ACTIVE;
IOConfigGPIOAF(txIO, IOCFG_AF_PP, uart->tx.af);
return true;
} else {
// TX line is pulled low so don't enable USART TX
return false;
}
}
return true;
}
void uartTxMonitor(uartPort_t *s)
{
uartDevice_t *uart = container_of(s, uartDevice_t, port);
IO_t txIO = IOGetByTag(uart->tx.pin);
if (uart->txPinState == TX_PIN_ACTIVE) {
// Switch TX to an input with pullup so it's state can be monitored
uart->txPinState = TX_PIN_MONITOR;
IOConfigGPIO(txIO, IOCFG_IPU);
}
}
#ifdef USE_DMA
void uartTryStartTxDMA(uartPort_t *s)
{
ATOMIC_BLOCK(NVIC_PRIO_SERIALUART_TXDMA) {
if (IS_DMA_ENABLED(s->txDMAResource)) {
// DMA is already in progress
return;
}
HAL_UART_StateTypeDef state = HAL_UART_GetState(&s->Handle);
if ((state & HAL_UART_STATE_BUSY_TX) == HAL_UART_STATE_BUSY_TX) {
// UART is still transmitting
return;
}
if (s->port.txBufferHead == s->port.txBufferTail) {
// No more data to transmit
s->txDMAEmpty = true;
return;
}
uint16_t size;
uint32_t fromwhere = s->port.txBufferTail;
if (s->port.txBufferHead > s->port.txBufferTail) {
size = s->port.txBufferHead - s->port.txBufferTail;
s->port.txBufferTail = s->port.txBufferHead;
} else {
size = s->port.txBufferSize - s->port.txBufferTail;
s->port.txBufferTail = 0;
}
s->txDMAEmpty = false;
HAL_UART_Transmit_DMA(&s->Handle, (uint8_t *)&s->port.txBuffer[fromwhere], size);
}
}
static void handleUsartTxDma(uartPort_t *s)
{
uartDevice_t *uart = container_of(s, uartDevice_t, port);
uartTryStartTxDMA(s);
if (s->txDMAEmpty && (uart->txPinState != TX_PIN_IGNORE)) {
// Switch TX to an input with pullup so it's state can be monitored
uartTxMonitor(s);
}
}
void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor)
{
uartPort_t *s = &(((uartDevice_t*)(descriptor->userParam))->port);
HAL_DMA_IRQHandler(&s->txDMAHandle);
#ifdef STM32G4
// G4's DMA HAL turns on half transfer interrupt.
// Only detect the transfer complete interrupt by checking remaining transfer count.
// XXX TODO Consider using HAL's XferCpltCallback facility to do this.
if (s->txDMAHandle.Instance->CNDTR == 0) {
// Unlike other stream based DMA implementations (F4, F7 and H7),
// G4's DMA implementation does not clear EN bit upon completion of a transfer,
// and it is neccesary to clear the EN bit explicitly here for IS_DMA_ENABLED macro
// used in uartTryStartTxDMA() to continue working with G4.
__HAL_DMA_DISABLE(&s->txDMAHandle);
}
#endif
}
#endif
FAST_IRQ_HANDLER void uartIrqHandler(uartPort_t *s)
{
UART_HandleTypeDef *huart = &s->Handle;
/* UART in mode Receiver ---------------------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_RXNE) != RESET)) {
uint8_t rbyte = (uint8_t)(huart->Instance->RDR & (uint8_t) 0xff);
if (s->port.rxCallback) {
s->port.rxCallback(rbyte, s->port.rxCallbackData);
} else {
s->port.rxBuffer[s->port.rxBufferHead] = rbyte;
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
}
CLEAR_BIT(huart->Instance->CR1, (USART_CR1_PEIE));
/* Disable the UART Error Interrupt: (Frame error, noise error, overrun error) */
CLEAR_BIT(huart->Instance->CR3, USART_CR3_EIE);
__HAL_UART_SEND_REQ(huart, UART_RXDATA_FLUSH_REQUEST);
}
/* UART parity error interrupt occurred -------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_PE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_PEF);
}
/* UART frame error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_FE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_FEF);
}
/* UART noise error interrupt occurred --------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_NE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_NEF);
}
/* UART Over-Run interrupt occurred -----------------------------------------*/
if ((__HAL_UART_GET_IT(huart, UART_IT_ORE) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_OREF);
}
// UART transmission completed
if ((__HAL_UART_GET_IT(huart, UART_IT_TC) != RESET)) {
__HAL_UART_CLEAR_IT(huart, UART_CLEAR_TCF);
// Switch TX to an input with pull-up so it's state can be monitored
uartTxMonitor(s);
#ifdef USE_DMA
if (s->txDMAResource) {
handleUsartTxDma(s);
}
#endif
}
if (
#ifdef USE_DMA
!s->txDMAResource &&
#endif
(__HAL_UART_GET_IT(huart, UART_IT_TXE) != RESET)) {
/* Check that a Tx process is ongoing */
if (s->port.txBufferTail == s->port.txBufferHead) {
/* Disable the UART Transmit Data Register Empty Interrupt */
CLEAR_BIT(huart->Instance->CR1, USART_CR1_TXEIE);
} else {
if ((huart->Init.WordLength == UART_WORDLENGTH_9B) && (huart->Init.Parity == UART_PARITY_NONE)) {
huart->Instance->TDR = (((uint16_t) s->port.txBuffer[s->port.txBufferTail]) & (uint16_t) 0x01FFU);
} else {
huart->Instance->TDR = (uint8_t)(s->port.txBuffer[s->port.txBufferTail]);
}
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
}
}
// UART reception idle detected
if (__HAL_UART_GET_IT(huart, UART_IT_IDLE)) {
if (s->port.idleCallback) {
s->port.idleCallback();
}
__HAL_UART_CLEAR_IDLEFLAG(huart);
}
}
#endif // USE_UART