[FLYWOOF411] add board documentation
[inav/snaewe.git] / src / main / drivers / serial_uart.c
blobe670c2a1367aa6b5ce99787324233c601c5aa49b
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
19 * Authors:
20 * Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
21 * Hamasaki/Timecop - Initial baseflight code
23 #include <stdbool.h>
24 #include <stdint.h>
26 #include "platform.h"
28 #include "build/build_config.h"
30 #include "common/utils.h"
32 #include "drivers/uart_inverter.h"
34 #include "serial.h"
35 #include "serial_uart.h"
36 #include "serial_uart_impl.h"
38 static void usartConfigurePinInversion(uartPort_t *uartPort) {
39 #if !defined(USE_UART_INVERTER) && !defined(STM32F303xC) && !defined(STM32F7)
40 UNUSED(uartPort);
41 #else
42 bool inverted = uartPort->port.options & SERIAL_INVERTED;
44 #ifdef USE_UART_INVERTER
45 uartInverterLine_e invertedLines = UART_INVERTER_LINE_NONE;
46 if (uartPort->port.mode & MODE_RX) {
47 invertedLines |= UART_INVERTER_LINE_RX;
49 if (uartPort->port.mode & MODE_TX) {
50 invertedLines |= UART_INVERTER_LINE_TX;
52 uartInverterSet(uartPort->USARTx, invertedLines, inverted);
53 #endif
55 #ifdef STM32F303xC
56 uint32_t inversionPins = 0;
58 if (uartPort->port.mode & MODE_TX) {
59 inversionPins |= USART_InvPin_Tx;
61 if (uartPort->port.mode & MODE_RX) {
62 inversionPins |= USART_InvPin_Rx;
65 USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
66 #endif
67 #endif
70 static void uartReconfigure(uartPort_t *uartPort)
72 USART_InitTypeDef USART_InitStructure;
73 USART_Cmd(uartPort->USARTx, DISABLE);
75 USART_InitStructure.USART_BaudRate = uartPort->port.baudRate;
77 // according to the stm32 documentation wordlen has to be 9 for parity bits
78 // this does not seem to matter for rx but will give bad data on tx!
79 if (uartPort->port.options & SERIAL_PARITY_EVEN) {
80 USART_InitStructure.USART_WordLength = USART_WordLength_9b;
81 } else {
82 USART_InitStructure.USART_WordLength = USART_WordLength_8b;
85 USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
86 USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
88 USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
89 USART_InitStructure.USART_Mode = 0;
90 if (uartPort->port.mode & MODE_RX)
91 USART_InitStructure.USART_Mode |= USART_Mode_Rx;
92 if (uartPort->port.mode & MODE_TX)
93 USART_InitStructure.USART_Mode |= USART_Mode_Tx;
95 USART_Init(uartPort->USARTx, &USART_InitStructure);
97 usartConfigurePinInversion(uartPort);
99 if (uartPort->port.options & SERIAL_BIDIR)
100 USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
101 else
102 USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
104 USART_Cmd(uartPort->USARTx, ENABLE);
107 serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options)
109 uartPort_t *s = NULL;
111 if (false) {
112 #ifdef USE_UART1
113 } else if (USARTx == USART1) {
114 s = serialUART1(baudRate, mode, options);
116 #endif
117 #ifdef USE_UART2
118 } else if (USARTx == USART2) {
119 s = serialUART2(baudRate, mode, options);
120 #endif
121 #ifdef USE_UART3
122 } else if (USARTx == USART3) {
123 s = serialUART3(baudRate, mode, options);
124 #endif
125 #ifdef USE_UART4
126 } else if (USARTx == UART4) {
127 s = serialUART4(baudRate, mode, options);
128 #endif
129 #ifdef USE_UART5
130 } else if (USARTx == UART5) {
131 s = serialUART5(baudRate, mode, options);
132 #endif
133 #ifdef USE_UART6
134 } else if (USARTx == USART6) {
135 s = serialUART6(baudRate, mode, options);
136 #endif
137 #ifdef USE_UART7
138 } else if (USARTx == UART7) {
139 s = serialUART7(baudRate, mode, options);
140 #endif
141 #ifdef USE_UART8
142 } else if (USARTx == UART8) {
143 s = serialUART8(baudRate, mode, options);
144 #endif
146 } else {
147 return (serialPort_t *)s;
150 // common serial initialisation code should move to serialPort::init()
151 s->port.rxBufferHead = s->port.rxBufferTail = 0;
152 s->port.txBufferHead = s->port.txBufferTail = 0;
153 // callback works for IRQ-based RX ONLY
154 s->port.rxCallback = rxCallback;
155 s->port.rxCallbackData = rxCallbackData;
156 s->port.mode = mode;
157 s->port.baudRate = baudRate;
158 s->port.options = options;
160 uartReconfigure(s);
162 if (mode & MODE_RX) {
163 USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
164 USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
167 if (mode & MODE_TX) {
168 USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
171 USART_Cmd(s->USARTx, ENABLE);
173 return (serialPort_t *)s;
176 void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
178 uartPort_t *uartPort = (uartPort_t *)instance;
179 uartPort->port.baudRate = baudRate;
180 uartReconfigure(uartPort);
183 void uartSetMode(serialPort_t *instance, portMode_t mode)
185 uartPort_t *uartPort = (uartPort_t *)instance;
186 uartPort->port.mode = mode;
187 uartReconfigure(uartPort);
190 uint32_t uartTotalRxBytesWaiting(const serialPort_t *instance)
192 const uartPort_t *s = (const uartPort_t*)instance;
194 if (s->port.rxBufferHead >= s->port.rxBufferTail) {
195 return s->port.rxBufferHead - s->port.rxBufferTail;
196 } else {
197 return s->port.rxBufferSize + s->port.rxBufferHead - s->port.rxBufferTail;
201 uint32_t uartTotalTxBytesFree(const serialPort_t *instance)
203 const uartPort_t *s = (const uartPort_t*)instance;
205 uint32_t bytesUsed;
207 if (s->port.txBufferHead >= s->port.txBufferTail) {
208 bytesUsed = s->port.txBufferHead - s->port.txBufferTail;
209 } else {
210 bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
213 return (s->port.txBufferSize - 1) - bytesUsed;
216 bool isUartTransmitBufferEmpty(const serialPort_t *instance)
218 const uartPort_t *s = (const uartPort_t *)instance;
219 return s->port.txBufferTail == s->port.txBufferHead;
222 uint8_t uartRead(serialPort_t *instance)
224 uint8_t ch;
225 uartPort_t *s = (uartPort_t *)instance;
227 ch = s->port.rxBuffer[s->port.rxBufferTail];
228 if (s->port.rxBufferTail + 1 >= s->port.rxBufferSize) {
229 s->port.rxBufferTail = 0;
230 } else {
231 s->port.rxBufferTail++;
234 return ch;
237 void uartWrite(serialPort_t *instance, uint8_t ch)
239 uartPort_t *s = (uartPort_t *)instance;
240 s->port.txBuffer[s->port.txBufferHead] = ch;
241 if (s->port.txBufferHead + 1 >= s->port.txBufferSize) {
242 s->port.txBufferHead = 0;
243 } else {
244 s->port.txBufferHead++;
247 USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
250 bool isUartIdle(serialPort_t *instance)
252 uartPort_t *s = (uartPort_t *)instance;
253 if(USART_GetFlagStatus(s->USARTx, USART_FLAG_IDLE)) {
254 uartClearIdleFlag(s);
255 return true;
256 } else {
257 return false;
261 const struct serialPortVTable uartVTable[] = {
263 .serialWrite = uartWrite,
264 .serialTotalRxWaiting = uartTotalRxBytesWaiting,
265 .serialTotalTxFree = uartTotalTxBytesFree,
266 .serialRead = uartRead,
267 .serialSetBaudRate = uartSetBaudRate,
268 .isSerialTransmitBufferEmpty = isUartTransmitBufferEmpty,
269 .setMode = uartSetMode,
270 .isConnected = NULL,
271 .writeBuf = NULL,
272 .beginWrite = NULL,
273 .endWrite = NULL,
274 .isIdle = isUartIdle,