Configurable UART
This commit is contained in:
parent
4ee7a330d6
commit
fdfe9e8af3
7
Makefile
7
Makefile
|
@ -680,6 +680,7 @@ COMMON_SRC = \
|
||||||
drivers/resource.c \
|
drivers/resource.c \
|
||||||
drivers/rcc.c \
|
drivers/rcc.c \
|
||||||
drivers/serial.c \
|
drivers/serial.c \
|
||||||
|
drivers/serial_pinconfig.c \
|
||||||
drivers/serial_uart.c \
|
drivers/serial_uart.c \
|
||||||
drivers/sound_beeper.c \
|
drivers/sound_beeper.c \
|
||||||
drivers/stack_check.c \
|
drivers/stack_check.c \
|
||||||
|
@ -894,6 +895,8 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
|
||||||
config/feature.c \
|
config/feature.c \
|
||||||
config/parameter_group.c \
|
config/parameter_group.c \
|
||||||
config/config_streamer.c \
|
config/config_streamer.c \
|
||||||
|
drivers/serial_pinconfig.c \
|
||||||
|
drivers/serial_uart_init.c \
|
||||||
io/serial_4way.c \
|
io/serial_4way.c \
|
||||||
io/serial_4way_avrootloader.c \
|
io/serial_4way_avrootloader.c \
|
||||||
io/serial_4way_stk500v2.c \
|
io/serial_4way_stk500v2.c \
|
||||||
|
@ -946,6 +949,7 @@ STM32F10x_COMMON_SRC = \
|
||||||
drivers/gpio_stm32f10x.c \
|
drivers/gpio_stm32f10x.c \
|
||||||
drivers/inverter.c \
|
drivers/inverter.c \
|
||||||
drivers/light_ws2811strip_stdperiph.c \
|
drivers/light_ws2811strip_stdperiph.c \
|
||||||
|
drivers/serial_uart_init.c \
|
||||||
drivers/serial_uart_stm32f10x.c \
|
drivers/serial_uart_stm32f10x.c \
|
||||||
drivers/system_stm32f10x.c \
|
drivers/system_stm32f10x.c \
|
||||||
drivers/timer_stm32f10x.c
|
drivers/timer_stm32f10x.c
|
||||||
|
@ -958,6 +962,7 @@ STM32F30x_COMMON_SRC = \
|
||||||
drivers/gpio_stm32f30x.c \
|
drivers/gpio_stm32f30x.c \
|
||||||
drivers/light_ws2811strip_stdperiph.c \
|
drivers/light_ws2811strip_stdperiph.c \
|
||||||
drivers/pwm_output_dshot.c \
|
drivers/pwm_output_dshot.c \
|
||||||
|
drivers/serial_uart_init.c \
|
||||||
drivers/serial_uart_stm32f30x.c \
|
drivers/serial_uart_stm32f30x.c \
|
||||||
drivers/system_stm32f30x.c \
|
drivers/system_stm32f30x.c \
|
||||||
drivers/timer_stm32f30x.c
|
drivers/timer_stm32f30x.c
|
||||||
|
@ -972,6 +977,7 @@ STM32F4xx_COMMON_SRC = \
|
||||||
drivers/inverter.c \
|
drivers/inverter.c \
|
||||||
drivers/light_ws2811strip_stdperiph.c \
|
drivers/light_ws2811strip_stdperiph.c \
|
||||||
drivers/pwm_output_dshot.c \
|
drivers/pwm_output_dshot.c \
|
||||||
|
drivers/serial_uart_init.c \
|
||||||
drivers/serial_uart_stm32f4xx.c \
|
drivers/serial_uart_stm32f4xx.c \
|
||||||
drivers/system_stm32f4xx.c \
|
drivers/system_stm32f4xx.c \
|
||||||
drivers/timer_stm32f4xx.c
|
drivers/timer_stm32f4xx.c
|
||||||
|
@ -1008,6 +1014,7 @@ SITLEXCLUDES = \
|
||||||
drivers/system.c \
|
drivers/system.c \
|
||||||
drivers/rcc.c \
|
drivers/rcc.c \
|
||||||
drivers/serial_uart.c \
|
drivers/serial_uart.c \
|
||||||
|
drivers/serial_pinconfig.c \
|
||||||
|
|
||||||
|
|
||||||
# check if target.mk supplied
|
# check if target.mk supplied
|
||||||
|
|
|
@ -0,0 +1,274 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "io/serial.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/serial_uart.h"
|
||||||
|
|
||||||
|
#include "config/parameter_group.h"
|
||||||
|
#include "config/parameter_group_ids.h"
|
||||||
|
|
||||||
|
// Backward compatibility for exisiting targets
|
||||||
|
|
||||||
|
// F1 targets don't explicitly define pins.
|
||||||
|
|
||||||
|
#ifdef STM32F1
|
||||||
|
#ifdef USE_UART1
|
||||||
|
#ifndef UART1_RX_PIN
|
||||||
|
#define UART1_RX_PIN PA10
|
||||||
|
#endif
|
||||||
|
#ifndef UART1_TX_PIN
|
||||||
|
#define UART1_TX_PIN PA9
|
||||||
|
#endif
|
||||||
|
#endif // USE_UART1
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
#ifndef UART2_RX_PIN
|
||||||
|
#define UART2_RX_PIN PA3
|
||||||
|
#endif
|
||||||
|
#ifndef UART2_TX_PIN
|
||||||
|
#define UART2_TX_PIN PA2
|
||||||
|
#endif
|
||||||
|
#endif // USE_UART2
|
||||||
|
#endif // STM32F1
|
||||||
|
|
||||||
|
// XXX Is there an F3 target that does not define UART pins?
|
||||||
|
|
||||||
|
#ifdef STM32F3
|
||||||
|
#ifdef USE_UART1
|
||||||
|
#ifndef UART1_TX_PIN
|
||||||
|
#define UART1_TX_PIN PA9
|
||||||
|
#endif
|
||||||
|
#ifndef UART1_RX_PIN
|
||||||
|
#define UART1_RX_PIN PA10
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
#ifndef UART2_TX_PIN
|
||||||
|
#define UART2_TX_PIN PD5
|
||||||
|
#endif
|
||||||
|
#ifndef UART2_RX_PIN
|
||||||
|
#define UART2_RX_PIN PD6
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3
|
||||||
|
#ifndef UART3_TX_PIN
|
||||||
|
#define UART3_TX_PIN PB10
|
||||||
|
#endif
|
||||||
|
#ifndef UART3_RX_PIN
|
||||||
|
#define UART3_RX_PIN PB11
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART4
|
||||||
|
#ifndef UART4_TX_PIN
|
||||||
|
#define UART4_TX_PIN PC10
|
||||||
|
#endif
|
||||||
|
#ifndef UART4_RX_PIN
|
||||||
|
#define UART4_RX_PIN PC11
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART5
|
||||||
|
#ifndef UART5_TX_PIN
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
#endif
|
||||||
|
#ifndef UART5_RX_PIN
|
||||||
|
#define UART5_RX_PIN PD2
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
#endif // STM32F3
|
||||||
|
|
||||||
|
// Default pin (NONE).
|
||||||
|
|
||||||
|
#ifdef USE_UART1
|
||||||
|
# if !defined(UART1_RX_PIN)
|
||||||
|
# define UART1_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART1_TX_PIN)
|
||||||
|
# define UART1_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART1)
|
||||||
|
# define INVERTER_PIN_UART1 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
# if !defined(UART2_RX_PIN)
|
||||||
|
# define UART2_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART2_TX_PIN)
|
||||||
|
# define UART2_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART2)
|
||||||
|
# define INVERTER_PIN_UART2 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3
|
||||||
|
# if !defined(UART3_RX_PIN)
|
||||||
|
# define UART3_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART3_TX_PIN)
|
||||||
|
# define UART3_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART3)
|
||||||
|
# define INVERTER_PIN_UART3 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART4
|
||||||
|
# if !defined(UART4_RX_PIN)
|
||||||
|
# define UART4_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART4_TX_PIN)
|
||||||
|
# define UART4_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART4)
|
||||||
|
# define INVERTER_PIN_UART4 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART5
|
||||||
|
# if !defined(UART5_RX_PIN)
|
||||||
|
# define UART5_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART5_TX_PIN)
|
||||||
|
# define UART5_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART5)
|
||||||
|
# define INVERTER_PIN_UART5 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART6
|
||||||
|
# if !defined(UART6_RX_PIN)
|
||||||
|
# define UART6_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART6_TX_PIN)
|
||||||
|
# define UART6_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART6)
|
||||||
|
# define INVERTER_PIN_UART6 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART7
|
||||||
|
# if !defined(UART7_RX_PIN)
|
||||||
|
# define UART7_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART7_TX_PIN)
|
||||||
|
# define UART7_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART7)
|
||||||
|
# define INVERTER_PIN_UART7 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART8
|
||||||
|
# if !defined(UART8_RX_PIN)
|
||||||
|
# define UART8_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(UART8_TX_PIN)
|
||||||
|
# define UART8_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(INVERTER_PIN_UART8)
|
||||||
|
# define INVERTER_PIN_UART8 NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SOFTSERIAL1
|
||||||
|
# if !defined(SOFTSERIAL1_RX_PIN)
|
||||||
|
# define SOFTSERIAL1_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(SOFTSERIAL1_TX_PIN)
|
||||||
|
# define SOFTSERIAL1_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SOFTSERIAL2
|
||||||
|
# if !defined(SOFTSERIAL2_RX_PIN)
|
||||||
|
# define SOFTSERIAL2_RX_PIN NONE
|
||||||
|
# endif
|
||||||
|
# if !defined(SOFTSERIAL2_TX_PIN)
|
||||||
|
# define SOFTSERIAL2_TX_PIN NONE
|
||||||
|
# endif
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL1)
|
||||||
|
typedef struct serialDefaultPin_s {
|
||||||
|
serialPortIdentifier_e ident;
|
||||||
|
ioTag_t rxIO, txIO, inverterIO;
|
||||||
|
} serialDefaultPin_t;
|
||||||
|
|
||||||
|
static const serialDefaultPin_t serialDefaultPin[] = {
|
||||||
|
#ifdef USE_UART1
|
||||||
|
{ SERIAL_PORT_USART1, IO_TAG(UART1_RX_PIN), IO_TAG(UART1_TX_PIN), IO_TAG(INVERTER_PIN_UART1) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART2
|
||||||
|
{ SERIAL_PORT_USART2, IO_TAG(UART2_RX_PIN), IO_TAG(UART2_TX_PIN), IO_TAG(INVERTER_PIN_UART2) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART3
|
||||||
|
{ SERIAL_PORT_USART3, IO_TAG(UART3_RX_PIN), IO_TAG(UART3_TX_PIN), IO_TAG(INVERTER_PIN_UART3) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART4
|
||||||
|
{ SERIAL_PORT_UART4, IO_TAG(UART4_RX_PIN), IO_TAG(UART4_TX_PIN), IO_TAG(INVERTER_PIN_UART4) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART5
|
||||||
|
{ SERIAL_PORT_UART5, IO_TAG(UART5_RX_PIN), IO_TAG(UART5_TX_PIN), IO_TAG(INVERTER_PIN_UART5) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART6
|
||||||
|
{ SERIAL_PORT_USART6, IO_TAG(UART6_RX_PIN), IO_TAG(UART6_TX_PIN), IO_TAG(INVERTER_PIN_UART6) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART7
|
||||||
|
{ SERIAL_PORT_USART7, IO_TAG(UART7_RX_PIN), IO_TAG(UART7_TX_PIN), IO_TAG(INVERTER_PIN_UART7) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_UART8
|
||||||
|
{ SERIAL_PORT_USART8, IO_TAG(UART8_RX_PIN), IO_TAG(UART8_TX_PIN), IO_TAG(INVERTER_PIN_UART8) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SOFTSERIAL1
|
||||||
|
{ SERIAL_PORT_SOFTSERIAL1, IO_TAG(SOFTSERIAL1_RX_PIN), IO_TAG(SOFTSERIAL1_TX_PIN), IO_TAG(NONE) },
|
||||||
|
#endif
|
||||||
|
#ifdef USE_SOFTSERIAL2
|
||||||
|
{ SERIAL_PORT_SOFTSERIAL2, IO_TAG(SOFTSERIAL2_RX_PIN), IO_TAG(SOFTSERIAL2_TX_PIN), IO_TAG(NONE) },
|
||||||
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
|
PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
|
||||||
|
|
||||||
|
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
||||||
|
{
|
||||||
|
memset(serialPinConfig, 0, sizeof(*serialPinConfig));
|
||||||
|
|
||||||
|
for (size_t index = 0 ; index < ARRAYLEN(serialDefaultPin) ; index++) {
|
||||||
|
const serialDefaultPin_t *defpin = &serialDefaultPin[index];
|
||||||
|
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->rxIO;
|
||||||
|
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->txIO;
|
||||||
|
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(defpin->ident)] = defpin->inverterIO;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
|
@ -17,9 +17,11 @@
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Authors:
|
* Authors:
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
|
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
|
||||||
* Hamasaki/Timecop - Initial baseflight code
|
* Hamasaki/Timecop - Initial baseflight code
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
@ -29,207 +31,12 @@
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
#include "drivers/gpio.h"
|
#include "drivers/gpio.h"
|
||||||
#include "inverter.h"
|
#include "drivers/inverter.h"
|
||||||
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
|
||||||
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
|
|
||||||
UNUSED(uartPort);
|
|
||||||
#else
|
|
||||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
|
||||||
|
|
||||||
#ifdef USE_INVERTER
|
|
||||||
if (inverted) {
|
|
||||||
// Enable hardware inverter if available.
|
|
||||||
enableInverter(uartPort->USARTx, true);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef STM32F303xC
|
|
||||||
uint32_t inversionPins = 0;
|
|
||||||
|
|
||||||
if (uartPort->port.mode & MODE_TX) {
|
|
||||||
inversionPins |= USART_InvPin_Tx;
|
|
||||||
}
|
|
||||||
if (uartPort->port.mode & MODE_RX) {
|
|
||||||
inversionPins |= USART_InvPin_Rx;
|
|
||||||
}
|
|
||||||
|
|
||||||
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
}
|
|
||||||
|
|
||||||
static void uartReconfigure(uartPort_t *uartPort)
|
|
||||||
{
|
|
||||||
USART_InitTypeDef USART_InitStructure;
|
|
||||||
USART_Cmd(uartPort->USARTx, DISABLE);
|
|
||||||
|
|
||||||
USART_InitStructure.USART_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!
|
|
||||||
if (uartPort->port.options & SERIAL_PARITY_EVEN) {
|
|
||||||
USART_InitStructure.USART_WordLength = USART_WordLength_9b;
|
|
||||||
} else {
|
|
||||||
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
|
||||||
}
|
|
||||||
|
|
||||||
USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
|
|
||||||
USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
|
|
||||||
|
|
||||||
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
|
||||||
USART_InitStructure.USART_Mode = 0;
|
|
||||||
if (uartPort->port.mode & MODE_RX)
|
|
||||||
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
|
||||||
if (uartPort->port.mode & MODE_TX)
|
|
||||||
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
|
||||||
|
|
||||||
USART_Init(uartPort->USARTx, &USART_InitStructure);
|
|
||||||
|
|
||||||
usartConfigurePinInversion(uartPort);
|
|
||||||
|
|
||||||
if(uartPort->port.options & SERIAL_BIDIR)
|
|
||||||
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
|
||||||
else
|
|
||||||
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
|
|
||||||
|
|
||||||
USART_Cmd(uartPort->USARTx, ENABLE);
|
|
||||||
}
|
|
||||||
|
|
||||||
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s = serialUART(device, baudRate, mode, options);
|
|
||||||
|
|
||||||
if (!s)
|
|
||||||
return (serialPort_t *)s;
|
|
||||||
|
|
||||||
s->txDMAEmpty = true;
|
|
||||||
|
|
||||||
// common serial initialisation code should move to serialPort::init()
|
|
||||||
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
|
||||||
s->port.txBufferHead = s->port.txBufferTail = 0;
|
|
||||||
// callback works for IRQ-based RX ONLY
|
|
||||||
s->port.rxCallback = rxCallback;
|
|
||||||
s->port.mode = mode;
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
s->port.options = options;
|
|
||||||
|
|
||||||
uartReconfigure(s);
|
|
||||||
|
|
||||||
// Receive DMA or IRQ
|
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
|
||||||
if (mode & MODE_RX) {
|
|
||||||
#ifdef STM32F4
|
|
||||||
if (s->rxDMAStream) {
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
|
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
|
||||||
#else
|
|
||||||
if (s->rxDMAChannel) {
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
#endif
|
|
||||||
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
|
|
||||||
|
|
||||||
#ifdef STM32F4
|
|
||||||
DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
|
||||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer;
|
|
||||||
DMA_DeInit(s->rxDMAStream);
|
|
||||||
DMA_Init(s->rxDMAStream, &DMA_InitStructure);
|
|
||||||
DMA_Cmd(s->rxDMAStream, ENABLE);
|
|
||||||
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
|
|
||||||
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
|
|
||||||
#else
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
|
|
||||||
DMA_DeInit(s->rxDMAChannel);
|
|
||||||
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
|
|
||||||
DMA_Cmd(s->rxDMAChannel, ENABLE);
|
|
||||||
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
|
|
||||||
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
|
|
||||||
#endif
|
|
||||||
} else {
|
|
||||||
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
|
|
||||||
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// Transmit DMA or IRQ
|
|
||||||
if (mode & MODE_TX) {
|
|
||||||
#ifdef STM32F4
|
|
||||||
if (s->txDMAStream) {
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
|
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
|
||||||
#else
|
|
||||||
if (s->txDMAChannel) {
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
|
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
|
||||||
#endif
|
|
||||||
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
|
|
||||||
|
|
||||||
#ifdef STM32F4
|
|
||||||
DMA_InitStructure.DMA_Channel = s->txDMAChannel;
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
|
||||||
DMA_DeInit(s->txDMAStream);
|
|
||||||
DMA_Init(s->txDMAStream, &DMA_InitStructure);
|
|
||||||
DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
|
|
||||||
DMA_SetCurrDataCounter(s->txDMAStream, 0);
|
|
||||||
#else
|
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
|
||||||
DMA_DeInit(s->txDMAChannel);
|
|
||||||
DMA_Init(s->txDMAChannel, &DMA_InitStructure);
|
|
||||||
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
|
|
||||||
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
|
|
||||||
s->txDMAChannel->CNDTR = 0;
|
|
||||||
#endif
|
|
||||||
USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE);
|
|
||||||
} else {
|
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
USART_Cmd(s->USARTx, ENABLE);
|
|
||||||
|
|
||||||
return (serialPort_t *)s;
|
|
||||||
}
|
|
||||||
|
|
||||||
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
void uartSetBaudRate(serialPort_t *instance, uint32_t baudRate)
|
||||||
{
|
{
|
||||||
|
@ -417,3 +224,75 @@ const struct serialPortVTable uartVTable[] = {
|
||||||
.endWrite = NULL,
|
.endWrite = NULL,
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#ifdef USE_UART1
|
||||||
|
// USART1 Rx/Tx IRQ Handler
|
||||||
|
void USART1_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_1]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
// USART2 Rx/Tx IRQ Handler
|
||||||
|
void USART2_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_2]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3
|
||||||
|
// USART3 Rx/Tx IRQ Handler
|
||||||
|
void USART3_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_3]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART4
|
||||||
|
// UART4 Rx/Tx IRQ Handler
|
||||||
|
void UART4_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_4]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART5
|
||||||
|
// UART5 Rx/Tx IRQ Handler
|
||||||
|
void UART5_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_5]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART6
|
||||||
|
// USART6 Rx/Tx IRQ Handler
|
||||||
|
void USART6_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_6]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART7
|
||||||
|
// UART7 Rx/Tx IRQ Handler
|
||||||
|
void UART7_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_7]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART8
|
||||||
|
// UART8 Rx/Tx IRQ Handler
|
||||||
|
void UART8_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_8]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -23,22 +23,10 @@
|
||||||
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
|
// Size must be a power of two due to various optimizations which use 'and' instead of 'mod'
|
||||||
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
// Various serial routines return the buffer occupied size as uint8_t which would need to be extended in order to
|
||||||
// increase size further.
|
// increase size further.
|
||||||
#define UART1_RX_BUFFER_SIZE 256
|
|
||||||
#define UART1_TX_BUFFER_SIZE 256
|
#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8)
|
||||||
#define UART2_RX_BUFFER_SIZE 256
|
#define USE_UART
|
||||||
#define UART2_TX_BUFFER_SIZE 256
|
#endif
|
||||||
#define UART3_RX_BUFFER_SIZE 256
|
|
||||||
#define UART3_TX_BUFFER_SIZE 256
|
|
||||||
#define UART4_RX_BUFFER_SIZE 256
|
|
||||||
#define UART4_TX_BUFFER_SIZE 256
|
|
||||||
#define UART5_RX_BUFFER_SIZE 256
|
|
||||||
#define UART5_TX_BUFFER_SIZE 256
|
|
||||||
#define UART6_RX_BUFFER_SIZE 256
|
|
||||||
#define UART6_TX_BUFFER_SIZE 256
|
|
||||||
#define UART7_RX_BUFFER_SIZE 256
|
|
||||||
#define UART7_TX_BUFFER_SIZE 256
|
|
||||||
#define UART8_RX_BUFFER_SIZE 256
|
|
||||||
#define UART8_TX_BUFFER_SIZE 256
|
|
||||||
|
|
||||||
typedef enum UARTDevice {
|
typedef enum UARTDevice {
|
||||||
UARTDEV_1 = 0,
|
UARTDEV_1 = 0,
|
||||||
|
@ -51,7 +39,7 @@ typedef enum UARTDevice {
|
||||||
UARTDEV_8 = 7
|
UARTDEV_8 = 7
|
||||||
} UARTDevice;
|
} UARTDevice;
|
||||||
|
|
||||||
typedef struct {
|
typedef struct uartPort_s {
|
||||||
serialPort_t port;
|
serialPort_t port;
|
||||||
|
|
||||||
#if defined(STM32F7)
|
#if defined(STM32F7)
|
||||||
|
@ -83,6 +71,7 @@ typedef struct {
|
||||||
USART_TypeDef *USARTx;
|
USART_TypeDef *USARTx;
|
||||||
} uartPort_t;
|
} uartPort_t;
|
||||||
|
|
||||||
|
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig);
|
||||||
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||||
|
|
||||||
// serialPort API
|
// serialPort API
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Authors:
|
* Authors:
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
|
* Dominic Clifton - Serial port abstraction, Separation of common STM32 code for cleanflight, various cleanups.
|
||||||
* Hamasaki/Timecop - Initial baseflight code
|
* Hamasaki/Timecop - Initial baseflight code
|
||||||
*/
|
*/
|
||||||
|
@ -31,12 +32,40 @@
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "inverter.h"
|
#include "drivers/inverter.h"
|
||||||
#include "dma.h"
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
|
uartDevice_t uartDevice[UARTDEV_COUNT]; // Only configured in target.h
|
||||||
|
uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
|
||||||
|
|
||||||
|
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
||||||
|
{
|
||||||
|
uartDevice_t *uartdev = uartDevice;
|
||||||
|
|
||||||
|
for (size_t hindex = 0 ; hindex < UARTDEV_COUNT ; hindex++) {
|
||||||
|
|
||||||
|
const uartHardware_t *hardware = &uartHardware[hindex];
|
||||||
|
UARTDevice device = hardware->device;
|
||||||
|
|
||||||
|
for (int pair = 0 ; pair < UARTHARDWARE_PINPAIR_COUNT ; pair++) {
|
||||||
|
if (hardware->pinPair[pair].rx == pSerialPinConfig->ioTagRx[device]
|
||||||
|
&& hardware->pinPair[pair].tx == pSerialPinConfig->ioTagTx[device]) {
|
||||||
|
// Matching pin pair found
|
||||||
|
|
||||||
|
uartdev->hardware = hardware;
|
||||||
|
uartdev->rx = hardware->pinPair[pair].rx;
|
||||||
|
uartdev->tx = hardware->pinPair[pair].tx;
|
||||||
|
uartDevmap[device] = uartdev++;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||||
|
@ -56,7 +85,7 @@ static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static void uartReconfigure(uartPort_t *uartPort)
|
void uartReconfigure(uartPort_t *uartPort)
|
||||||
{
|
{
|
||||||
/*RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
|
/*RCC_PeriphCLKInitTypeDef RCC_PeriphClkInit;
|
||||||
RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3|
|
RCC_PeriphClkInit.PeriphClockSelection = RCC_PERIPHCLK_USART1|RCC_PERIPHCLK_USART2|RCC_PERIPHCLK_USART3|
|
||||||
|
@ -357,3 +386,75 @@ const struct serialPortVTable uartVTable[] = {
|
||||||
.endWrite = NULL,
|
.endWrite = NULL,
|
||||||
}
|
}
|
||||||
};
|
};
|
||||||
|
|
||||||
|
#ifdef USE_UART1
|
||||||
|
// USART1 Rx/Tx IRQ Handler
|
||||||
|
void USART1_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_1]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
// USART2 Rx/Tx IRQ Handler
|
||||||
|
void USART2_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_2]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3
|
||||||
|
// USART3 Rx/Tx IRQ Handler
|
||||||
|
void USART3_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_3]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART4
|
||||||
|
// UART4 Rx/Tx IRQ Handler
|
||||||
|
void UART4_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_4]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART5
|
||||||
|
// UART5 Rx/Tx IRQ Handler
|
||||||
|
void UART5_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_5]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART6
|
||||||
|
// USART6 Rx/Tx IRQ Handler
|
||||||
|
void USART6_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_6]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART7
|
||||||
|
// UART7 Rx/Tx IRQ Handler
|
||||||
|
void UART7_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_7]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART8
|
||||||
|
// UART8 Rx/Tx IRQ Handler
|
||||||
|
void UART8_IRQHandler(void)
|
||||||
|
{
|
||||||
|
uartPort_t *s = &(uartDevmap[UARTDEV_8]->port);
|
||||||
|
uartIrqHandler(s);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
|
@ -17,10 +17,158 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// device specific uart implementation is defined here
|
// Configuration constants
|
||||||
|
|
||||||
|
#if defined(STM32F1)
|
||||||
|
#define UARTDEV_COUNT_MAX 3
|
||||||
|
#define UARTHARDWARE_PINPAIR_COUNT 3
|
||||||
|
#ifndef UART_RX_BUFFER_SIZE
|
||||||
|
#define UART_RX_BUFFER_SIZE 256
|
||||||
|
#endif
|
||||||
|
#ifndef UART_TX_BUFFER_SIZE
|
||||||
|
#define UART_TX_BUFFER_SIZE 256
|
||||||
|
#endif
|
||||||
|
#elif defined(STM32F3)
|
||||||
|
#define UARTDEV_COUNT_MAX 5
|
||||||
|
#define UARTHARDWARE_PINPAIR_COUNT 4
|
||||||
|
#ifndef UART_RX_BUFFER_SIZE
|
||||||
|
#define UART_RX_BUFFER_SIZE 256
|
||||||
|
#endif
|
||||||
|
#ifndef UART_TX_BUFFER_SIZE
|
||||||
|
#define UART_TX_BUFFER_SIZE 256
|
||||||
|
#endif
|
||||||
|
#elif defined(STM32F4)
|
||||||
|
#define UARTDEV_COUNT_MAX 6
|
||||||
|
#define UARTHARDWARE_PINPAIR_COUNT 4
|
||||||
|
#ifndef UART_RX_BUFFER_SIZE
|
||||||
|
#define UART_RX_BUFFER_SIZE 512
|
||||||
|
#endif
|
||||||
|
#ifndef UART_TX_BUFFER_SIZE
|
||||||
|
#define UART_TX_BUFFER_SIZE 512
|
||||||
|
#endif
|
||||||
|
#elif defined(STM32F7)
|
||||||
|
#define UARTDEV_COUNT_MAX 8
|
||||||
|
#define UARTHARDWARE_PINPAIR_COUNT 3
|
||||||
|
#ifndef UART_RX_BUFFER_SIZE
|
||||||
|
#define UART_RX_BUFFER_SIZE 512
|
||||||
|
#endif
|
||||||
|
#ifndef UART_TX_BUFFER_SIZE
|
||||||
|
#define UART_TX_BUFFER_SIZE 512
|
||||||
|
#endif
|
||||||
|
#else
|
||||||
|
#error unknown MCU family
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Count number of configured UARTs
|
||||||
|
|
||||||
|
#ifdef USE_UART1
|
||||||
|
#define UARTDEV_COUNT_1 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_1 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2
|
||||||
|
#define UARTDEV_COUNT_2 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_2 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3
|
||||||
|
#define UARTDEV_COUNT_3 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_3 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART4
|
||||||
|
#define UARTDEV_COUNT_4 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_4 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART5
|
||||||
|
#define UARTDEV_COUNT_5 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_5 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART6
|
||||||
|
#define UARTDEV_COUNT_6 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_6 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART7
|
||||||
|
#define UARTDEV_COUNT_7 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_7 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART8
|
||||||
|
#define UARTDEV_COUNT_8 1
|
||||||
|
#else
|
||||||
|
#define UARTDEV_COUNT_8 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define UARTDEV_COUNT (UARTDEV_COUNT_1 + UARTDEV_COUNT_2 + UARTDEV_COUNT_3 + UARTDEV_COUNT_4 + UARTDEV_COUNT_5 + UARTDEV_COUNT_6 + UARTDEV_COUNT_7 + UARTDEV_COUNT_8)
|
||||||
|
|
||||||
|
typedef struct uartPinPair_s {
|
||||||
|
ioTag_t rx;
|
||||||
|
ioTag_t tx;
|
||||||
|
} uartPinPair_t;
|
||||||
|
|
||||||
|
typedef struct uartHardware_s {
|
||||||
|
UARTDevice device; // XXX Not required for full allocation
|
||||||
|
USART_TypeDef* reg;
|
||||||
|
#if defined(STM32F1) || defined(STM32F3)
|
||||||
|
DMA_Channel_TypeDef *txDMAChannel;
|
||||||
|
DMA_Channel_TypeDef *rxDMAChannel;
|
||||||
|
#elif defined(STM32F4) || defined(STM32F7)
|
||||||
|
uint32_t DMAChannel;
|
||||||
|
DMA_Stream_TypeDef *txDMAStream;
|
||||||
|
DMA_Stream_TypeDef *rxDMAStream;
|
||||||
|
#endif
|
||||||
|
uartPinPair_t pinPair[UARTHARDWARE_PINPAIR_COUNT];
|
||||||
|
#if defined(STM32F7)
|
||||||
|
uint32_t rcc_ahb1;
|
||||||
|
rccPeriphTag_t rcc_apb2;
|
||||||
|
rccPeriphTag_t rcc_apb1;
|
||||||
|
#else
|
||||||
|
rccPeriphTag_t rcc;
|
||||||
|
#endif
|
||||||
|
uint8_t af;
|
||||||
|
#if defined(STM32F7)
|
||||||
|
uint8_t txIrq;
|
||||||
|
uint8_t rxIrq;
|
||||||
|
#else
|
||||||
|
uint8_t irqn;
|
||||||
|
#endif
|
||||||
|
uint8_t txPriority;
|
||||||
|
uint8_t rxPriority;
|
||||||
|
} uartHardware_t;
|
||||||
|
|
||||||
|
extern const uartHardware_t uartHardware[];
|
||||||
|
|
||||||
|
// uartDevice_t is an actual device instance.
|
||||||
|
// XXX Instances are allocated for uarts defined by USE_UARTx atm.
|
||||||
|
|
||||||
|
typedef struct uartDevice_s {
|
||||||
|
uartPort_t port;
|
||||||
|
const uartHardware_t *hardware;
|
||||||
|
ioTag_t rx;
|
||||||
|
ioTag_t tx;
|
||||||
|
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
|
||||||
|
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
|
||||||
|
} uartDevice_t;
|
||||||
|
|
||||||
|
extern uartDevice_t uartDevice[];
|
||||||
|
extern uartDevice_t *uartDevmap[];
|
||||||
|
|
||||||
extern const struct serialPortVTable uartVTable[];
|
extern const struct serialPortVTable uartVTable[];
|
||||||
|
|
||||||
void uartStartTxDMA(uartPort_t *s);
|
void uartStartTxDMA(uartPort_t *s);
|
||||||
|
|
||||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||||
|
|
||||||
|
void uartIrqHandler(uartPort_t *s);
|
||||||
|
|
||||||
|
void uartReconfigure(uartPort_t *uartPort);
|
||||||
|
|
|
@ -0,0 +1,266 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it 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 is distributed in the hope that it 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 Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Initialization part of serial_uart.c
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* 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 "platform.h"
|
||||||
|
|
||||||
|
#include "build/build_config.h"
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
#include "drivers/gpio.h"
|
||||||
|
#include "drivers/inverter.h"
|
||||||
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/serial_uart.h"
|
||||||
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
|
uartDevice_t uartDevice[UARTDEV_COUNT]; // Only those configured in target.h
|
||||||
|
uartDevice_t *uartDevmap[UARTDEV_COUNT_MAX]; // Full array
|
||||||
|
|
||||||
|
void uartPinConfigure(const serialPinConfig_t *pSerialPinConfig)
|
||||||
|
{
|
||||||
|
uartDevice_t *uartdev = uartDevice;
|
||||||
|
|
||||||
|
for (size_t hindex = 0; hindex < UARTDEV_COUNT_MAX; hindex++) {
|
||||||
|
|
||||||
|
const uartHardware_t *hardware = &uartHardware[hindex];
|
||||||
|
UARTDevice device = hardware->device;
|
||||||
|
|
||||||
|
for (int pair = 0 ; pair < UARTHARDWARE_PINPAIR_COUNT ; pair++) {
|
||||||
|
if (hardware->pinPair[pair].rx == pSerialPinConfig->ioTagRx[device]
|
||||||
|
&& hardware->pinPair[pair].tx == pSerialPinConfig->ioTagTx[device]) {
|
||||||
|
// Matching pin pair found
|
||||||
|
|
||||||
|
uartdev->hardware = hardware;
|
||||||
|
uartdev->rx = hardware->pinPair[pair].rx;
|
||||||
|
uartdev->tx = hardware->pinPair[pair].tx;
|
||||||
|
uartDevmap[device] = uartdev++;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void usartConfigurePinInversion(uartPort_t *uartPort) {
|
||||||
|
#if !defined(USE_INVERTER) && !defined(STM32F303xC)
|
||||||
|
UNUSED(uartPort);
|
||||||
|
#else
|
||||||
|
bool inverted = uartPort->port.options & SERIAL_INVERTED;
|
||||||
|
|
||||||
|
#ifdef USE_INVERTER
|
||||||
|
if (inverted) {
|
||||||
|
// Enable hardware inverter if available.
|
||||||
|
enableInverter(uartPort->USARTx, true);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef STM32F303xC
|
||||||
|
uint32_t inversionPins = 0;
|
||||||
|
|
||||||
|
if (uartPort->port.mode & MODE_TX) {
|
||||||
|
inversionPins |= USART_InvPin_Tx;
|
||||||
|
}
|
||||||
|
if (uartPort->port.mode & MODE_RX) {
|
||||||
|
inversionPins |= USART_InvPin_Rx;
|
||||||
|
}
|
||||||
|
|
||||||
|
USART_InvPinCmd(uartPort->USARTx, inversionPins, inverted ? ENABLE : DISABLE);
|
||||||
|
#endif
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void uartReconfigure(uartPort_t *uartPort)
|
||||||
|
{
|
||||||
|
USART_InitTypeDef USART_InitStructure;
|
||||||
|
USART_Cmd(uartPort->USARTx, DISABLE);
|
||||||
|
|
||||||
|
USART_InitStructure.USART_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!
|
||||||
|
if (uartPort->port.options & SERIAL_PARITY_EVEN) {
|
||||||
|
USART_InitStructure.USART_WordLength = USART_WordLength_9b;
|
||||||
|
} else {
|
||||||
|
USART_InitStructure.USART_WordLength = USART_WordLength_8b;
|
||||||
|
}
|
||||||
|
|
||||||
|
USART_InitStructure.USART_StopBits = (uartPort->port.options & SERIAL_STOPBITS_2) ? USART_StopBits_2 : USART_StopBits_1;
|
||||||
|
USART_InitStructure.USART_Parity = (uartPort->port.options & SERIAL_PARITY_EVEN) ? USART_Parity_Even : USART_Parity_No;
|
||||||
|
|
||||||
|
USART_InitStructure.USART_HardwareFlowControl = USART_HardwareFlowControl_None;
|
||||||
|
USART_InitStructure.USART_Mode = 0;
|
||||||
|
if (uartPort->port.mode & MODE_RX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Rx;
|
||||||
|
if (uartPort->port.mode & MODE_TX)
|
||||||
|
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
|
||||||
|
|
||||||
|
USART_Init(uartPort->USARTx, &USART_InitStructure);
|
||||||
|
|
||||||
|
usartConfigurePinInversion(uartPort);
|
||||||
|
|
||||||
|
if(uartPort->port.options & SERIAL_BIDIR)
|
||||||
|
USART_HalfDuplexCmd(uartPort->USARTx, ENABLE);
|
||||||
|
else
|
||||||
|
USART_HalfDuplexCmd(uartPort->USARTx, DISABLE);
|
||||||
|
|
||||||
|
USART_Cmd(uartPort->USARTx, ENABLE);
|
||||||
|
}
|
||||||
|
|
||||||
|
serialPort_t *uartOpen(UARTDevice device, serialReceiveCallbackPtr rxCallback, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
|
{
|
||||||
|
uartPort_t *s = serialUART(device, baudRate, mode, options);
|
||||||
|
|
||||||
|
if (!s)
|
||||||
|
return (serialPort_t *)s;
|
||||||
|
|
||||||
|
s->txDMAEmpty = true;
|
||||||
|
|
||||||
|
// common serial initialisation code should move to serialPort::init()
|
||||||
|
s->port.rxBufferHead = s->port.rxBufferTail = 0;
|
||||||
|
s->port.txBufferHead = s->port.txBufferTail = 0;
|
||||||
|
// callback works for IRQ-based RX ONLY
|
||||||
|
s->port.rxCallback = rxCallback;
|
||||||
|
s->port.mode = mode;
|
||||||
|
s->port.baudRate = baudRate;
|
||||||
|
s->port.options = options;
|
||||||
|
|
||||||
|
uartReconfigure(s);
|
||||||
|
|
||||||
|
// Receive DMA or IRQ
|
||||||
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
if (mode & MODE_RX) {
|
||||||
|
#ifdef STM32F4
|
||||||
|
if (s->rxDMAStream) {
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
|
||||||
|
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
||||||
|
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
||||||
|
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||||
|
#else
|
||||||
|
if (s->rxDMAChannel) {
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||||
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
#endif
|
||||||
|
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
|
||||||
|
|
||||||
|
#ifdef STM32F4
|
||||||
|
DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||||
|
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer;
|
||||||
|
DMA_DeInit(s->rxDMAStream);
|
||||||
|
DMA_Init(s->rxDMAStream, &DMA_InitStructure);
|
||||||
|
DMA_Cmd(s->rxDMAStream, ENABLE);
|
||||||
|
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
|
||||||
|
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
|
||||||
|
#else
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
|
||||||
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
|
||||||
|
DMA_DeInit(s->rxDMAChannel);
|
||||||
|
DMA_Init(s->rxDMAChannel, &DMA_InitStructure);
|
||||||
|
DMA_Cmd(s->rxDMAChannel, ENABLE);
|
||||||
|
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
|
||||||
|
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
|
||||||
|
#endif
|
||||||
|
} else {
|
||||||
|
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
|
||||||
|
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Transmit DMA or IRQ
|
||||||
|
if (mode & MODE_TX) {
|
||||||
|
#ifdef STM32F4
|
||||||
|
if (s->txDMAStream) {
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
|
||||||
|
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
|
||||||
|
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
|
||||||
|
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
||||||
|
#else
|
||||||
|
if (s->txDMAChannel) {
|
||||||
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
|
||||||
|
DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
|
||||||
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
|
||||||
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
|
#endif
|
||||||
|
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
|
||||||
|
|
||||||
|
#ifdef STM32F4
|
||||||
|
DMA_InitStructure.DMA_Channel = s->txDMAChannel;
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
|
DMA_DeInit(s->txDMAStream);
|
||||||
|
DMA_Init(s->txDMAStream, &DMA_InitStructure);
|
||||||
|
DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
|
||||||
|
DMA_SetCurrDataCounter(s->txDMAStream, 0);
|
||||||
|
#else
|
||||||
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
|
DMA_DeInit(s->txDMAChannel);
|
||||||
|
DMA_Init(s->txDMAChannel, &DMA_InitStructure);
|
||||||
|
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
|
||||||
|
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
|
||||||
|
s->txDMAChannel->CNDTR = 0;
|
||||||
|
#endif
|
||||||
|
USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE);
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
USART_Cmd(s->USARTx, ENABLE);
|
||||||
|
|
||||||
|
return (serialPort_t *)s;
|
||||||
|
}
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Authors:
|
* Authors:
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
* Dominic Clifton/Hydra - Various cleanups for Cleanflight
|
* Dominic Clifton/Hydra - Various cleanups for Cleanflight
|
||||||
* Bill Nesbitt - Code from AutoQuad
|
* Bill Nesbitt - Code from AutoQuad
|
||||||
* Hamasaki/Timecop - Initial baseflight code
|
* Hamasaki/Timecop - Initial baseflight code
|
||||||
|
@ -30,26 +31,172 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
|
#ifdef USE_UART
|
||||||
|
|
||||||
|
#ifdef USE_UART1_RX_DMA
|
||||||
|
# define UART1_RX_DMA_CHANNEL DMA1_Channel5
|
||||||
|
#else
|
||||||
|
# define UART1_RX_DMA_CHANNEL 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART1_TX_DMA
|
||||||
|
# define UART1_TX_DMA_CHANNEL DMA1_Channel4
|
||||||
|
#else
|
||||||
|
# define UART1_TX_DMA_CHANNEL 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#define UART2_RX_DMA_CHANNEL 0
|
||||||
|
#define UART2_TX_DMA_CHANNEL 0
|
||||||
|
#define UART3_RX_DMA_CHANNEL 0
|
||||||
|
#define UART3_TX_DMA_CHANNEL 0
|
||||||
|
|
||||||
|
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
static uartPort_t uartPort1;
|
{
|
||||||
|
.device = UARTDEV_1,
|
||||||
|
.reg = USART1,
|
||||||
|
.rxDMAChannel = UART1_RX_DMA_CHANNEL,
|
||||||
|
.txDMAChannel = UART1_TX_DMA_CHANNEL,
|
||||||
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PA10), DEFIO_TAG_E(PA9) },
|
||||||
|
{ DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB6) },
|
||||||
|
},
|
||||||
|
//.af = GPIO_AF_USART1,
|
||||||
|
.rcc = RCC_APB2(USART1),
|
||||||
|
.irqn = USART1_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART1
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
static uartPort_t uartPort2;
|
{
|
||||||
|
.device = UARTDEV_2,
|
||||||
|
.reg = USART2,
|
||||||
|
.rxDMAChannel = UART2_RX_DMA_CHANNEL,
|
||||||
|
.txDMAChannel = UART2_TX_DMA_CHANNEL,
|
||||||
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PA3), DEFIO_TAG_E(PA2) },
|
||||||
|
{ DEFIO_TAG_E(PD6), DEFIO_TAG_E(PD5) },
|
||||||
|
},
|
||||||
|
//.af = GPIO_AF_USART2,
|
||||||
|
.rcc = RCC_APB1(USART2),
|
||||||
|
.irqn = USART2_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART2,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART2
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
static uartPort_t uartPort3;
|
{
|
||||||
|
.device = UARTDEV_3,
|
||||||
|
.reg = USART3,
|
||||||
|
.rxDMAChannel = UART3_RX_DMA_CHANNEL,
|
||||||
|
.txDMAChannel = UART3_TX_DMA_CHANNEL,
|
||||||
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PB11), DEFIO_TAG_E(PB10) },
|
||||||
|
{ DEFIO_TAG_E(PD9), DEFIO_TAG_E(PD8) },
|
||||||
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
|
//.af = GPIO_AF_USART3,
|
||||||
|
.rcc = RCC_APB1(USART3),
|
||||||
|
.irqn = USART3_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART3,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART3
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
void uartIrqCallback(uartPort_t *s)
|
void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
|
{
|
||||||
|
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||||
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||||
|
DMA_Cmd(descriptor->ref, DISABLE);
|
||||||
|
|
||||||
|
if (s->port.txBufferHead != s->port.txBufferTail)
|
||||||
|
uartStartTxDMA(s);
|
||||||
|
else
|
||||||
|
s->txDMAEmpty = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
// XXX Should serialUART be consolidated?
|
||||||
|
|
||||||
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
|
{
|
||||||
|
uartDevice_t *uartdev = uartDevmap[device];
|
||||||
|
if (!uartdev) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
uartPort_t *s = &uartdev->port;
|
||||||
|
|
||||||
|
s->port.vTable = uartVTable;
|
||||||
|
|
||||||
|
s->port.baudRate = baudRate;
|
||||||
|
|
||||||
|
s->port.rxBuffer = uartdev->rxBuffer;
|
||||||
|
s->port.txBuffer = uartdev->txBuffer;
|
||||||
|
s->port.rxBufferSize = ARRAYLEN(uartdev->rxBuffer);
|
||||||
|
s->port.txBufferSize = ARRAYLEN(uartdev->txBuffer);
|
||||||
|
|
||||||
|
const uartHardware_t *hardware = uartdev->hardware;
|
||||||
|
|
||||||
|
s->USARTx = hardware->reg;
|
||||||
|
|
||||||
|
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||||
|
|
||||||
|
if (hardware->rxDMAChannel) {
|
||||||
|
dmaInit(dmaGetIdentifier(hardware->rxDMAChannel), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
|
s->rxDMAChannel = hardware->rxDMAChannel;
|
||||||
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hardware->txDMAChannel) {
|
||||||
|
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAChannel);
|
||||||
|
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
dmaSetHandler(identifier, uart_tx_dma_IRQHandler, hardware->txPriority, (uint32_t)s);
|
||||||
|
s->txDMAChannel = hardware->txDMAChannel;
|
||||||
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
}
|
||||||
|
|
||||||
|
IO_t rxIO = IOGetByTag(uartdev->rx);
|
||||||
|
IO_t txIO = IOGetByTag(uartdev->tx);
|
||||||
|
|
||||||
|
if (options & SERIAL_BIDIR) {
|
||||||
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
IOConfigGPIO(txIO, (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||||
|
} else {
|
||||||
|
if (mode & MODE_TX) {
|
||||||
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
IOConfigGPIO(txIO, IOCFG_AF_PP);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (mode & MODE_RX) {
|
||||||
|
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
|
IOConfigGPIO(rxIO, IOCFG_IPU);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// RX/TX Interrupt
|
||||||
|
if (!hardware->rxDMAChannel || !hardware->txDMAChannel) {
|
||||||
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
return s;
|
||||||
|
}
|
||||||
|
|
||||||
|
void uartIrqHandler(uartPort_t *s)
|
||||||
{
|
{
|
||||||
uint16_t SR = s->USARTx->SR;
|
uint16_t SR = s->USARTx->SR;
|
||||||
|
|
||||||
|
@ -75,236 +222,4 @@ void uartIrqCallback(uartPort_t *s)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // USE_UART
|
||||||
// USART1 Tx DMA Handler
|
|
||||||
void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
|
||||||
{
|
|
||||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
|
||||||
DMA_Cmd(descriptor->ref, DISABLE);
|
|
||||||
|
|
||||||
if (s->port.txBufferHead != s->port.txBufferTail)
|
|
||||||
uartStartTxDMA(s);
|
|
||||||
else
|
|
||||||
s->txDMAEmpty = true;
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef USE_UART1
|
|
||||||
// USART1 - Telemetry (RX/TX by DMA)
|
|
||||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
s = &uartPort1;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBuffer = rx1Buffer;
|
|
||||||
s->port.txBuffer = tx1Buffer;
|
|
||||||
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
|
|
||||||
|
|
||||||
s->USARTx = USART1;
|
|
||||||
|
|
||||||
#ifdef USE_UART1_RX_DMA
|
|
||||||
dmaInit(DMA1_CH5_HANDLER, OWNER_SERIAL_RX, 1);
|
|
||||||
s->rxDMAChannel = DMA1_Channel5;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
#endif
|
|
||||||
s->txDMAChannel = DMA1_Channel4;
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
|
||||||
|
|
||||||
// UART1_TX PA9
|
|
||||||
// UART1_RX PA10
|
|
||||||
if (options & SERIAL_BIDIR) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
|
||||||
} else {
|
|
||||||
if (mode & MODE_TX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, 1);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// DMA TX Interrupt
|
|
||||||
dmaInit(DMA1_CH4_HANDLER, OWNER_SERIAL_TX, 1);
|
|
||||||
dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
|
||||||
|
|
||||||
#ifndef USE_UART1_RX_DMA
|
|
||||||
// RX/TX Interrupt
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART1 Rx/Tx IRQ Handler
|
|
||||||
void USART1_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort1;
|
|
||||||
uartIrqCallback(s);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART2
|
|
||||||
// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
|
|
||||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
s = &uartPort2;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART2_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART2_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx2Buffer;
|
|
||||||
s->port.txBuffer = tx2Buffer;
|
|
||||||
|
|
||||||
s->USARTx = USART2;
|
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
|
||||||
|
|
||||||
// UART2_TX PA2
|
|
||||||
// UART2_RX PA3
|
|
||||||
if (options & SERIAL_BIDIR) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
|
||||||
} else {
|
|
||||||
if (mode & MODE_TX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, 2);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// RX/TX Interrupt
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
|
|
||||||
|
|
||||||
// USART2 Rx/Tx IRQ Handler
|
|
||||||
void USART2_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort2;
|
|
||||||
uartIrqCallback(s);
|
|
||||||
}
|
|
||||||
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
// USART3
|
|
||||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
s = &uartPort3;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBuffer = rx3Buffer;
|
|
||||||
s->port.txBuffer = tx3Buffer;
|
|
||||||
s->port.rxBufferSize = UART3_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART3_TX_BUFFER_SIZE;
|
|
||||||
|
|
||||||
s->USARTx = USART3;
|
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, 3);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
|
||||||
} else {
|
|
||||||
if (mode & MODE_TX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, 3);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
|
||||||
}
|
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL_RX, 3);
|
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
// RX/TX Interrupt
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
|
|
||||||
// USART2 Rx/Tx IRQ Handler
|
|
||||||
void USART3_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort3;
|
|
||||||
uartIrqCallback(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Temporary solution until serialUARTx() are refactored/consolidated
|
|
||||||
|
|
||||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
switch (device) {
|
|
||||||
#ifdef USE_UART1
|
|
||||||
case UARTDEV_1:
|
|
||||||
return serialUART1(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
case UARTDEV_2:
|
|
||||||
return serialUART2(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
case UARTDEV_3:
|
|
||||||
return serialUART3(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
default:
|
|
||||||
return NULL;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* Authors:
|
* Authors:
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
* Dominic Clifton - Port baseflight STM32F10x to STM32F30x for cleanflight
|
* Dominic Clifton - Port baseflight STM32F10x to STM32F30x for cleanflight
|
||||||
* J. Ihlein - Code from FocusFlight32
|
* J. Ihlein - Code from FocusFlight32
|
||||||
* Bill Nesbitt - Code from AutoQuad
|
* Bill Nesbitt - Code from AutoQuad
|
||||||
|
@ -31,75 +32,151 @@
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "drivers/dma.h"
|
||||||
#include "rcc.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
|
#ifdef USE_UART
|
||||||
|
|
||||||
|
// XXX Will DMA eventually be configurable?
|
||||||
|
// XXX Do these belong here?
|
||||||
|
|
||||||
|
#ifdef USE_UART1_RX_DMA
|
||||||
|
# define UART1_RX_DMA DMA1_Channel5
|
||||||
|
#else
|
||||||
|
# define UART1_RX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART1_TX_DMA
|
||||||
|
# define UART1_TX_DMA DMA1_Channel4
|
||||||
|
#else
|
||||||
|
# define UART1_TX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2_RX_DMA
|
||||||
|
# define UART2_RX_DMA DMA1_Channel6
|
||||||
|
#else
|
||||||
|
# define UART2_RX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART2_TX_DMA
|
||||||
|
# define UART2_TX_DMA DMA1_Channel7
|
||||||
|
#else
|
||||||
|
# define UART2_TX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3_RX_DMA
|
||||||
|
# define UART3_RX_DMA DMA1_Channel3
|
||||||
|
#else
|
||||||
|
# define UART3_RX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART3_TX_DMA
|
||||||
|
# define UART3_TX_DMA DMA1_Channel2
|
||||||
|
#else
|
||||||
|
# define UART3_TX_DMA 0
|
||||||
|
#endif
|
||||||
|
|
||||||
|
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
#ifndef UART1_TX_PIN
|
{
|
||||||
#define UART1_TX_PIN PA9 // PA9
|
.device = UARTDEV_1,
|
||||||
#endif
|
.reg = USART1,
|
||||||
#ifndef UART1_RX_PIN
|
.rxDMAChannel = UART1_RX_DMA,
|
||||||
#define UART1_RX_PIN PA10 // PA10
|
.txDMAChannel = UART1_TX_DMA,
|
||||||
#endif
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PA10), DEFIO_TAG_E(PA9) },
|
||||||
|
{ DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB6) },
|
||||||
|
{ DEFIO_TAG_E(PC5), DEFIO_TAG_E(PC4) },
|
||||||
|
{ DEFIO_TAG_E(PE1), DEFIO_TAG_E(PE0) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB2(USART1),
|
||||||
|
.af = GPIO_AF_7,
|
||||||
|
.irqn = USART1_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART1_RXDMA,
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
#ifndef UART2_TX_PIN
|
{
|
||||||
#define UART2_TX_PIN PD5 // PD5
|
.device = UARTDEV_2,
|
||||||
#endif
|
.reg = USART2,
|
||||||
#ifndef UART2_RX_PIN
|
.rxDMAChannel = UART2_RX_DMA,
|
||||||
#define UART2_RX_PIN PD6 // PD6
|
.txDMAChannel = UART2_TX_DMA,
|
||||||
#endif
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PA15), DEFIO_TAG_E(PA14) },
|
||||||
|
{ DEFIO_TAG_E(PA3), DEFIO_TAG_E(PA2) },
|
||||||
|
{ DEFIO_TAG_E(PB4), DEFIO_TAG_E(PB3) },
|
||||||
|
{ DEFIO_TAG_E(PD6), DEFIO_TAG_E(PD5) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(USART2),
|
||||||
|
.af = GPIO_AF_7,
|
||||||
|
.irqn = USART2_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART2_RXDMA,
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
#ifndef UART3_TX_PIN
|
{
|
||||||
#define UART3_TX_PIN PB10 // PB10 (AF7)
|
.device = UARTDEV_3,
|
||||||
#endif
|
.reg = USART3,
|
||||||
#ifndef UART3_RX_PIN
|
.rxDMAChannel = UART3_RX_DMA,
|
||||||
#define UART3_RX_PIN PB11 // PB11 (AF7)
|
.txDMAChannel = UART3_TX_DMA,
|
||||||
#endif
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PB11), DEFIO_TAG_E(PB10) },
|
||||||
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
{ DEFIO_TAG_E(PD9), DEFIO_TAG_E(PD8) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(USART3),
|
||||||
|
.af = GPIO_AF_7,
|
||||||
|
.irqn = USART3_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART3_RXDMA,
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
#ifndef UART4_TX_PIN
|
// UART4 XXX Not tested (yet!?) Need 303RC, e.g. LUX for testing
|
||||||
#define UART4_TX_PIN PC10 // PC10 (AF5)
|
{
|
||||||
#endif
|
.device = UARTDEV_4,
|
||||||
#ifndef UART4_RX_PIN
|
.reg = UART4,
|
||||||
#define UART4_RX_PIN PC11 // PC11 (AF5)
|
.rxDMAChannel = 0, // XXX UART4_RX_DMA !?
|
||||||
#endif
|
.txDMAChannel = 0, // XXX UART4_TX_DMA !?
|
||||||
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(UART4),
|
||||||
|
.af = GPIO_AF_5,
|
||||||
|
.irqn = UART4_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART4_RXDMA,
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
#ifndef UART5_TX_PIN // The real UART5_RX is on PD2, no board is using.
|
// UART5 XXX Not tested (yet!?) Need 303RC; e.g. LUX for testing
|
||||||
#define UART5_TX_PIN PC12 // PC12 (AF5)
|
{
|
||||||
#endif
|
.device = UARTDEV_5,
|
||||||
#ifndef UART5_RX_PIN
|
.reg = UART5,
|
||||||
#define UART5_RX_PIN PC12 // PC12 (AF5)
|
.rxDMAChannel = 0,
|
||||||
#endif
|
.txDMAChannel = 0,
|
||||||
|
.pinPair = {
|
||||||
|
{ DEFIO_TAG_E(PD2), DEFIO_TAG_E(PC12) },
|
||||||
|
},
|
||||||
|
.rcc = RCC_APB1(UART5),
|
||||||
|
.af = GPIO_AF_5,
|
||||||
|
.irqn = UART5_IRQn,
|
||||||
|
.txPriority = NVIC_PRIO_SERIALUART5,
|
||||||
|
.rxPriority = NVIC_PRIO_SERIALUART5,
|
||||||
|
},
|
||||||
#endif
|
#endif
|
||||||
|
};
|
||||||
|
|
||||||
#ifdef USE_UART1
|
|
||||||
static uartPort_t uartPort1;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
static uartPort_t uartPort2;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
static uartPort_t uartPort3;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
static uartPort_t uartPort4;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
static uartPort_t uartPort5;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if defined(USE_UART1_TX_DMA) || defined(USE_UART2_TX_DMA) || defined(USE_UART3_TX_DMA)
|
|
||||||
static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
|
static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
|
||||||
{
|
{
|
||||||
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
uartPort_t *s = (uartPort_t*)(descriptor->userParam);
|
||||||
|
@ -111,304 +188,91 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor)
|
||||||
else
|
else
|
||||||
s->txDMAEmpty = true;
|
s->txDMAEmpty = true;
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
|
void serialUARTInitIO(IO_t txIO, IO_t rxIO, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index)
|
||||||
{
|
{
|
||||||
if ((options & SERIAL_BIDIR) && tx) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
|
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz,
|
||||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_OType_PP : GPIO_OType_OD,
|
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_OType_PP : GPIO_OType_OD,
|
||||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||||
);
|
);
|
||||||
|
|
||||||
IOInit(tx, OWNER_SERIAL_TX, index);
|
IOInit(txIO, OWNER_SERIAL_TX, index);
|
||||||
IOConfigGPIOAF(tx, ioCfg, af);
|
IOConfigGPIOAF(txIO, ioCfg, af);
|
||||||
|
|
||||||
if (!(options & SERIAL_INVERTED))
|
if (!(options & SERIAL_INVERTED))
|
||||||
IOLo(tx); // OpenDrain output should be inactive
|
IOLo(txIO); // OpenDrain output should be inactive
|
||||||
} else {
|
} else {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
|
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
|
||||||
if ((mode & MODE_TX) && tx) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(tx, OWNER_SERIAL_TX, index);
|
IOInit(txIO, OWNER_SERIAL_TX, index);
|
||||||
IOConfigGPIOAF(tx, ioCfg, af);
|
IOConfigGPIOAF(txIO, ioCfg, af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((mode & MODE_RX) && rx) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
IOInit(rx, OWNER_SERIAL_RX, index);
|
IOInit(rxIO, OWNER_SERIAL_RX, index);
|
||||||
IOConfigGPIOAF(rx, ioCfg, af);
|
IOConfigGPIOAF(rxIO, ioCfg, af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_UART1
|
// XXX Should serialUART be consolidated?
|
||||||
uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
s = &uartPort1;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART1_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART1_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx1Buffer;
|
|
||||||
s->port.txBuffer = tx1Buffer;
|
|
||||||
|
|
||||||
s->USARTx = USART1;
|
|
||||||
|
|
||||||
#ifdef USE_UART1_RX_DMA
|
|
||||||
dmaInit(DMA1_CH5_HANDLER, OWNER_SERIAL, 1);
|
|
||||||
s->rxDMAChannel = DMA1_Channel5;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART1_TX_DMA
|
|
||||||
s->txDMAChannel = DMA1_Channel4;
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
|
||||||
|
|
||||||
#if defined(USE_UART1_TX_DMA) || defined(USE_UART1_RX_DMA)
|
|
||||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1);
|
|
||||||
|
|
||||||
#ifdef USE_UART1_TX_DMA
|
|
||||||
dmaInit(DMA1_CH4_HANDLER, OWNER_SERIAL, 1);
|
|
||||||
dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef USE_UART1_RX_DMA
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART1_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART1_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART2
|
|
||||||
uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
s = &uartPort2;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART2_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART2_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx2Buffer;
|
|
||||||
s->port.txBuffer = tx2Buffer;
|
|
||||||
|
|
||||||
s->USARTx = USART2;
|
|
||||||
|
|
||||||
#ifdef USE_UART2_RX_DMA
|
|
||||||
dmaInit(DMA1_CH6_HANDLER, OWNER_SERIAL, 2);
|
|
||||||
s->rxDMAChannel = DMA1_Channel6;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2_TX_DMA
|
|
||||||
dmaInit(DMA1_CH7_HANDLER, OWNER_SERIAL, 2);
|
|
||||||
s->txDMAChannel = DMA1_Channel7;
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
|
||||||
|
|
||||||
#if defined(USE_UART2_TX_DMA) || defined(USE_UART2_RX_DMA)
|
|
||||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2);
|
|
||||||
|
|
||||||
#ifdef USE_UART2_TX_DMA
|
|
||||||
// DMA TX Interrupt
|
|
||||||
dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, (uint32_t)&uartPort2);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef USE_UART2_RX_DMA
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART2_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART2_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE];
|
|
||||||
|
|
||||||
s = &uartPort3;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART3_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART3_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx3Buffer;
|
|
||||||
s->port.txBuffer = tx3Buffer;
|
|
||||||
|
|
||||||
s->USARTx = USART3;
|
|
||||||
|
|
||||||
#ifdef USE_UART3_RX_DMA
|
|
||||||
dmaInit(DMA1_CH3_HANDLER, OWNER_SERIAL, 3);
|
|
||||||
s->rxDMAChannel = DMA1_Channel3;
|
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3_TX_DMA
|
|
||||||
dmaInit(DMA1_CH2_HANDLER, OWNER_SERIAL, 3);
|
|
||||||
s->txDMAChannel = DMA1_Channel2;
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
|
||||||
#endif
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(USART3), ENABLE);
|
|
||||||
|
|
||||||
#if defined(USE_UART3_TX_DMA) || defined(USE_UART3_RX_DMA)
|
|
||||||
RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7, 3);
|
|
||||||
|
|
||||||
#ifdef USE_UART3_TX_DMA
|
|
||||||
// DMA TX Interrupt
|
|
||||||
dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, (uint32_t)&uartPort3);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifndef USE_UART3_RX_DMA
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART3_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART3_RXDMA);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART4
|
|
||||||
uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx4Buffer[UART4_TX_BUFFER_SIZE];
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
s = &uartPort4;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART4_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART4_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx4Buffer;
|
|
||||||
s->port.txBuffer = tx4Buffer;
|
|
||||||
|
|
||||||
s->USARTx = UART4;
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(UART4), ENABLE);
|
|
||||||
|
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5, 4);
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART4);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART5
|
|
||||||
uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
|
|
||||||
{
|
|
||||||
uartPort_t *s;
|
|
||||||
static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE];
|
|
||||||
static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE];
|
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
s = &uartPort5;
|
|
||||||
s->port.vTable = uartVTable;
|
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
|
||||||
|
|
||||||
s->port.rxBufferSize = UART5_RX_BUFFER_SIZE;
|
|
||||||
s->port.txBufferSize = UART5_TX_BUFFER_SIZE;
|
|
||||||
s->port.rxBuffer = rx5Buffer;
|
|
||||||
s->port.txBuffer = tx5Buffer;
|
|
||||||
|
|
||||||
s->USARTx = UART5;
|
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(UART5), ENABLE);
|
|
||||||
|
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5);
|
|
||||||
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn;
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SERIALUART5);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
|
||||||
|
|
||||||
return s;
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
// Temporary solution until serialUARTx() are refactored/consolidated
|
|
||||||
|
|
||||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
{
|
{
|
||||||
switch (device) {
|
uartPort_t *s;
|
||||||
#ifdef USE_UART1
|
|
||||||
case UARTDEV_1:
|
uartDevice_t *uartDev = uartDevmap[device];
|
||||||
return serialUART1(baudRate, mode, options);
|
if (!uartDev) {
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
case UARTDEV_2:
|
|
||||||
return serialUART2(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
case UARTDEV_3:
|
|
||||||
return serialUART3(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
case UARTDEV_4:
|
|
||||||
return serialUART4(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
case UARTDEV_5:
|
|
||||||
return serialUART5(baudRate, mode, options);
|
|
||||||
#endif
|
|
||||||
default:
|
|
||||||
return NULL;
|
return NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
s = &(uartDev->port);
|
||||||
|
s->port.vTable = uartVTable;
|
||||||
|
|
||||||
|
s->port.baudRate = baudRate;
|
||||||
|
|
||||||
|
s->port.rxBuffer = uartDev->rxBuffer;
|
||||||
|
s->port.txBuffer = uartDev->txBuffer;
|
||||||
|
s->port.rxBufferSize = sizeof(uartDev->rxBuffer);
|
||||||
|
s->port.txBufferSize = sizeof(uartDev->txBuffer);
|
||||||
|
|
||||||
|
const uartHardware_t *hardware = uartDev->hardware;
|
||||||
|
|
||||||
|
s->USARTx = hardware->reg;
|
||||||
|
|
||||||
|
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||||
|
|
||||||
|
if (hardware->rxDMAChannel) {
|
||||||
|
dmaInit(dmaGetIdentifier(hardware->rxDMAChannel), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
|
s->rxDMAChannel = hardware->rxDMAChannel;
|
||||||
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (hardware->txDMAChannel) {
|
||||||
|
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAChannel);
|
||||||
|
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
dmaSetHandler(identifier, handleUsartTxDma, hardware->txPriority, (uint32_t)s);
|
||||||
|
s->txDMAChannel = hardware->txDMAChannel;
|
||||||
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||||
|
}
|
||||||
|
|
||||||
|
serialUARTInitIO(IOGetByTag(uartDev->tx), IOGetByTag(uartDev->rx), mode, options, hardware->af, device);
|
||||||
|
|
||||||
|
if (!s->rxDMAChannel || !s->txDMAChannel) {
|
||||||
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
|
}
|
||||||
|
|
||||||
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
void usartIrqHandler(uartPort_t *s)
|
void uartIrqHandler(uartPort_t *s)
|
||||||
{
|
{
|
||||||
uint32_t ISR = s->USARTx->ISR;
|
uint32_t ISR = s->USARTx->ISR;
|
||||||
|
|
||||||
|
@ -439,48 +303,4 @@ void usartIrqHandler(uartPort_t *s)
|
||||||
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
|
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
#endif // USE_UART
|
||||||
#ifdef USE_UART1
|
|
||||||
void USART1_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort1;
|
|
||||||
|
|
||||||
usartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART2
|
|
||||||
void USART2_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort2;
|
|
||||||
|
|
||||||
usartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
void USART3_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort3;
|
|
||||||
|
|
||||||
usartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART4
|
|
||||||
void UART4_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort4;
|
|
||||||
|
|
||||||
usartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART5
|
|
||||||
void UART5_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &uartPort5;
|
|
||||||
|
|
||||||
usartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
|
@ -15,6 +15,10 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
|
@ -22,38 +26,21 @@
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "rcc.h"
|
#include "drivers/dma.h"
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
#define UART_RX_BUFFER_SIZE 512
|
#ifdef USE_UART
|
||||||
#define UART_TX_BUFFER_SIZE 512
|
|
||||||
|
|
||||||
typedef struct uartDevice_s {
|
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||||
USART_TypeDef* dev;
|
|
||||||
uartPort_t port;
|
|
||||||
uint32_t DMAChannel;
|
|
||||||
DMA_Stream_TypeDef *txDMAStream;
|
|
||||||
DMA_Stream_TypeDef *rxDMAStream;
|
|
||||||
ioTag_t rx;
|
|
||||||
ioTag_t tx;
|
|
||||||
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
|
|
||||||
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
|
|
||||||
rccPeriphTag_t rcc_uart;
|
|
||||||
uint8_t af;
|
|
||||||
uint8_t rxIrq;
|
|
||||||
uint32_t txPriority;
|
|
||||||
uint32_t rxPriority;
|
|
||||||
} uartDevice_t;
|
|
||||||
|
|
||||||
//static uartPort_t uartPort[MAX_UARTS];
|
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
static uartDevice_t uart1 =
|
{
|
||||||
{
|
.device = UARTDEV_1,
|
||||||
|
.reg = USART1,
|
||||||
.DMAChannel = DMA_Channel_4,
|
.DMAChannel = DMA_Channel_4,
|
||||||
#ifdef USE_UART1_RX_DMA
|
#ifdef USE_UART1_RX_DMA
|
||||||
.rxDMAStream = DMA2_Stream5,
|
.rxDMAStream = DMA2_Stream5,
|
||||||
|
@ -61,20 +48,22 @@ static uartDevice_t uart1 =
|
||||||
#ifdef USE_UART1_TX_DMA
|
#ifdef USE_UART1_TX_DMA
|
||||||
.txDMAStream = DMA2_Stream7,
|
.txDMAStream = DMA2_Stream7,
|
||||||
#endif
|
#endif
|
||||||
.dev = USART1,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART1_RX_PIN),
|
{ DEFIO_TAG_E(PA10), DEFIO_TAG_E(PA9) },
|
||||||
.tx = IO_TAG(UART1_TX_PIN),
|
{ DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB6) },
|
||||||
|
},
|
||||||
.af = GPIO_AF_USART1,
|
.af = GPIO_AF_USART1,
|
||||||
.rcc_uart = RCC_APB2(USART1),
|
.rcc = RCC_APB2(USART1),
|
||||||
.rxIrq = USART1_IRQn,
|
.irqn = USART1_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART1
|
.rxPriority = NVIC_PRIO_SERIALUART1
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
static uartDevice_t uart2 =
|
{
|
||||||
{
|
.device = UARTDEV_2,
|
||||||
|
.reg = USART2,
|
||||||
.DMAChannel = DMA_Channel_4,
|
.DMAChannel = DMA_Channel_4,
|
||||||
#ifdef USE_UART2_RX_DMA
|
#ifdef USE_UART2_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream5,
|
.rxDMAStream = DMA1_Stream5,
|
||||||
|
@ -82,20 +71,22 @@ static uartDevice_t uart2 =
|
||||||
#ifdef USE_UART2_TX_DMA
|
#ifdef USE_UART2_TX_DMA
|
||||||
.txDMAStream = DMA1_Stream6,
|
.txDMAStream = DMA1_Stream6,
|
||||||
#endif
|
#endif
|
||||||
.dev = USART2,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART2_RX_PIN),
|
{ DEFIO_TAG_E(PA3), DEFIO_TAG_E(PA2) },
|
||||||
.tx = IO_TAG(UART2_TX_PIN),
|
{ DEFIO_TAG_E(PD6), DEFIO_TAG_E(PD5) },
|
||||||
|
},
|
||||||
.af = GPIO_AF_USART2,
|
.af = GPIO_AF_USART2,
|
||||||
.rcc_uart = RCC_APB1(USART2),
|
.rcc = RCC_APB1(USART2),
|
||||||
.rxIrq = USART2_IRQn,
|
.irqn = USART2_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART2
|
.rxPriority = NVIC_PRIO_SERIALUART2
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
static uartDevice_t uart3 =
|
{
|
||||||
{
|
.device = UARTDEV_3,
|
||||||
|
.reg = USART3,
|
||||||
.DMAChannel = DMA_Channel_4,
|
.DMAChannel = DMA_Channel_4,
|
||||||
#ifdef USE_UART3_RX_DMA
|
#ifdef USE_UART3_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream1,
|
.rxDMAStream = DMA1_Stream1,
|
||||||
|
@ -103,20 +94,23 @@ static uartDevice_t uart3 =
|
||||||
#ifdef USE_UART3_TX_DMA
|
#ifdef USE_UART3_TX_DMA
|
||||||
.txDMAStream = DMA1_Stream3,
|
.txDMAStream = DMA1_Stream3,
|
||||||
#endif
|
#endif
|
||||||
.dev = USART3,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART3_RX_PIN),
|
{ DEFIO_TAG_E(PB11), DEFIO_TAG_E(PB10) },
|
||||||
.tx = IO_TAG(UART3_TX_PIN),
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
{ DEFIO_TAG_E(PD9), DEFIO_TAG_E(PD8) }
|
||||||
|
},
|
||||||
.af = GPIO_AF_USART3,
|
.af = GPIO_AF_USART3,
|
||||||
.rcc_uart = RCC_APB1(USART3),
|
.rcc = RCC_APB1(USART3),
|
||||||
.rxIrq = USART3_IRQn,
|
.irqn = USART3_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART3
|
.rxPriority = NVIC_PRIO_SERIALUART3
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
static uartDevice_t uart4 =
|
{
|
||||||
{
|
.device = UARTDEV_4,
|
||||||
|
.reg = UART4,
|
||||||
.DMAChannel = DMA_Channel_4,
|
.DMAChannel = DMA_Channel_4,
|
||||||
#ifdef USE_UART4_RX_DMA
|
#ifdef USE_UART4_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream2,
|
.rxDMAStream = DMA1_Stream2,
|
||||||
|
@ -124,20 +118,22 @@ static uartDevice_t uart4 =
|
||||||
#ifdef USE_UART4_TX_DMA
|
#ifdef USE_UART4_TX_DMA
|
||||||
.txDMAStream = DMA1_Stream4,
|
.txDMAStream = DMA1_Stream4,
|
||||||
#endif
|
#endif
|
||||||
.dev = UART4,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART4_RX_PIN),
|
{ DEFIO_TAG_E(PA1), DEFIO_TAG_E(PA0) },
|
||||||
.tx = IO_TAG(UART4_TX_PIN),
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
.af = GPIO_AF_UART4,
|
.af = GPIO_AF_UART4,
|
||||||
.rcc_uart = RCC_APB1(UART4),
|
.rcc = RCC_APB1(UART4),
|
||||||
.rxIrq = UART4_IRQn,
|
.irqn = UART4_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART4
|
.rxPriority = NVIC_PRIO_SERIALUART4
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
static uartDevice_t uart5 =
|
{
|
||||||
{
|
.device = UARTDEV_5,
|
||||||
|
.reg = UART5,
|
||||||
.DMAChannel = DMA_Channel_4,
|
.DMAChannel = DMA_Channel_4,
|
||||||
#ifdef USE_UART5_RX_DMA
|
#ifdef USE_UART5_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream0,
|
.rxDMAStream = DMA1_Stream0,
|
||||||
|
@ -145,20 +141,21 @@ static uartDevice_t uart5 =
|
||||||
#ifdef USE_UART5_TX_DMA
|
#ifdef USE_UART5_TX_DMA
|
||||||
.txDMAStream = DMA1_Stream7,
|
.txDMAStream = DMA1_Stream7,
|
||||||
#endif
|
#endif
|
||||||
.dev = UART5,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART5_RX_PIN),
|
{ DEFIO_TAG_E(PD2), DEFIO_TAG_E(PC12) },
|
||||||
.tx = IO_TAG(UART5_TX_PIN),
|
},
|
||||||
.af = GPIO_AF_UART5,
|
.af = GPIO_AF_UART5,
|
||||||
.rcc_uart = RCC_APB1(UART5),
|
.rcc = RCC_APB1(UART5),
|
||||||
.rxIrq = UART5_IRQn,
|
.irqn = UART5_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART5
|
.rxPriority = NVIC_PRIO_SERIALUART5
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
static uartDevice_t uart6 =
|
{
|
||||||
{
|
.device = UARTDEV_6,
|
||||||
|
.reg = USART6,
|
||||||
.DMAChannel = DMA_Channel_5,
|
.DMAChannel = DMA_Channel_5,
|
||||||
#ifdef USE_UART6_RX_DMA
|
#ifdef USE_UART6_RX_DMA
|
||||||
.rxDMAStream = DMA2_Stream1,
|
.rxDMAStream = DMA2_Stream1,
|
||||||
|
@ -166,75 +163,18 @@ static uartDevice_t uart6 =
|
||||||
#ifdef USE_UART6_TX_DMA
|
#ifdef USE_UART6_TX_DMA
|
||||||
.txDMAStream = DMA2_Stream6,
|
.txDMAStream = DMA2_Stream6,
|
||||||
#endif
|
#endif
|
||||||
.dev = USART6,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART6_RX_PIN),
|
{ DEFIO_TAG_E(PC7), DEFIO_TAG_E(PC6) },
|
||||||
.tx = IO_TAG(UART6_TX_PIN),
|
{ DEFIO_TAG_E(PG9), DEFIO_TAG_E(PG14) },
|
||||||
|
},
|
||||||
.af = GPIO_AF_USART6,
|
.af = GPIO_AF_USART6,
|
||||||
.rcc_uart = RCC_APB2(USART6),
|
.rcc = RCC_APB2(USART6),
|
||||||
.rxIrq = USART6_IRQn,
|
.irqn = USART6_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART6
|
.rxPriority = NVIC_PRIO_SERIALUART6
|
||||||
|
},
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
#endif
|
|
||||||
|
|
||||||
static uartDevice_t* uartHardwareMap[] = {
|
|
||||||
#ifdef USE_UART1
|
|
||||||
&uart1,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
&uart2,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
&uart3,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
&uart4,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
&uart5,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART6
|
|
||||||
&uart6,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
};
|
|
||||||
|
|
||||||
void uartIrqHandler(uartPort_t *s)
|
|
||||||
{
|
|
||||||
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
|
||||||
if (s->port.rxCallback) {
|
|
||||||
s->port.rxCallback(s->USARTx->DR);
|
|
||||||
} else {
|
|
||||||
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
|
||||||
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (!s->txDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
|
|
||||||
if (s->port.txBufferTail != s->port.txBufferHead) {
|
|
||||||
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
|
||||||
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
|
||||||
} else {
|
|
||||||
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
if (USART_GetITStatus(s->USARTx, USART_FLAG_ORE) == SET)
|
|
||||||
{
|
|
||||||
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
static void handleUsartTxDma(uartPort_t *s)
|
static void handleUsartTxDma(uartPort_t *s)
|
||||||
{
|
{
|
||||||
|
@ -269,14 +209,19 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// XXX Should serialUART be consolidated?
|
||||||
|
|
||||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
{
|
{
|
||||||
uartPort_t *s;
|
uartPort_t *s;
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
|
||||||
|
|
||||||
uartDevice_t *uart = uartHardwareMap[device];
|
uartDevice_t *uart = uartDevmap[device];
|
||||||
if (!uart) return NULL;
|
if (!uart) return NULL;
|
||||||
|
|
||||||
|
const uartHardware_t *hardware = uart->hardware;
|
||||||
|
|
||||||
|
if (!hardware) return NULL; // XXX Can't happen !?
|
||||||
|
|
||||||
s = &(uart->port);
|
s = &(uart->port);
|
||||||
s->port.vTable = uartVTable;
|
s->port.vTable = uartVTable;
|
||||||
|
|
||||||
|
@ -287,54 +232,52 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
s->port.rxBufferSize = sizeof(uart->rxBuffer);
|
s->port.rxBufferSize = sizeof(uart->rxBuffer);
|
||||||
s->port.txBufferSize = sizeof(uart->txBuffer);
|
s->port.txBufferSize = sizeof(uart->txBuffer);
|
||||||
|
|
||||||
s->USARTx = uart->dev;
|
s->USARTx = hardware->reg;
|
||||||
if (uart->rxDMAStream) {
|
|
||||||
s->rxDMAChannel = uart->DMAChannel;
|
|
||||||
s->rxDMAStream = uart->rxDMAStream;
|
|
||||||
dmaInit(dmaGetIdentifier(uart->rxDMAStream), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
|
||||||
}
|
|
||||||
if (uart->txDMAStream) {
|
|
||||||
s->txDMAChannel = uart->DMAChannel;
|
|
||||||
s->txDMAStream = uart->txDMAStream;
|
|
||||||
const dmaIdentifier_e identifier = dmaGetIdentifier(uart->txDMAStream);
|
|
||||||
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
|
||||||
// DMA TX Interrupt
|
|
||||||
dmaSetHandler(identifier, dmaIRQHandler, uart->txPriority, (uint32_t)uart);
|
|
||||||
}
|
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
if (hardware->rxDMAStream) {
|
||||||
|
dmaInit(dmaGetIdentifier(hardware->rxDMAStream), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
|
s->rxDMAChannel = hardware->DMAChannel;
|
||||||
|
s->rxDMAStream = hardware->rxDMAStream;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
}
|
||||||
|
|
||||||
IO_t tx = IOGetByTag(uart->tx);
|
if (hardware->txDMAStream) {
|
||||||
IO_t rx = IOGetByTag(uart->rx);
|
const dmaIdentifier_e identifier = dmaGetIdentifier(hardware->txDMAStream);
|
||||||
|
dmaInit(identifier, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
dmaSetHandler(identifier, dmaIRQHandler, hardware->txPriority, (uint32_t)uart);
|
||||||
|
s->txDMAChannel = hardware->DMAChannel;
|
||||||
|
s->txDMAStream = hardware->txDMAStream;
|
||||||
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
}
|
||||||
|
|
||||||
if (uart->rcc_uart) {
|
IO_t txIO = IOGetByTag(uart->tx);
|
||||||
RCC_ClockCmd(uart->rcc_uart, ENABLE);
|
IO_t rxIO = IOGetByTag(uart->rx);
|
||||||
|
|
||||||
|
if (hardware->rcc) {
|
||||||
|
RCC_ClockCmd(hardware->rcc, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
if (options & SERIAL_BIDIR_PP)
|
IOConfigGPIOAF(txIO, (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD, hardware->af);
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
} else {
|
||||||
else
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
}
|
IOConfigGPIOAF(txIO, IOCFG_AF_PP_UP, hardware->af);
|
||||||
else {
|
|
||||||
if ((mode & MODE_TX) && tx) {
|
|
||||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP_UP, uart->af);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((mode & MODE_RX) && rx) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(rx, IOCFG_AF_PP_UP, uart->af);
|
IOConfigGPIOAF(rxIO, IOCFG_AF_PP_UP, hardware->af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!(s->rxDMAChannel)) {
|
if (!(s->rxDMAChannel)) {
|
||||||
NVIC_InitStructure.NVIC_IRQChannel = uart->rxIrq;
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(uart->rxPriority);
|
|
||||||
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(uart->rxPriority);
|
NVIC_InitStructure.NVIC_IRQChannel = hardware->irqn;
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(hardware->rxPriority);
|
||||||
|
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(hardware->rxPriority);
|
||||||
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
}
|
}
|
||||||
|
@ -342,56 +285,29 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_UART1
|
void uartIrqHandler(uartPort_t *s)
|
||||||
// USART1 Rx/Tx IRQ Handler
|
|
||||||
void USART1_IRQHandler(void)
|
|
||||||
{
|
{
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
|
||||||
uartIrqHandler(s);
|
if (s->port.rxCallback) {
|
||||||
}
|
s->port.rxCallback(s->USARTx->DR);
|
||||||
|
} else {
|
||||||
|
s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
|
||||||
|
s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#endif
|
if (!s->txDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
|
||||||
|
if (s->port.txBufferTail != s->port.txBufferHead) {
|
||||||
|
USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
|
||||||
|
s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
|
||||||
|
} else {
|
||||||
|
USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
#ifdef USE_UART2
|
if (USART_GetITStatus(s->USARTx, USART_FLAG_ORE) == SET)
|
||||||
void USART2_IRQHandler(void)
|
{
|
||||||
{
|
USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
}
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
// USART3
|
|
||||||
void USART3_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART4
|
|
||||||
// UART4
|
|
||||||
void UART4_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART5
|
|
||||||
// UART5
|
|
||||||
void UART5_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART6
|
|
||||||
// USART6
|
|
||||||
void USART6_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -15,58 +15,43 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
* jflyper - Refactoring, cleanup and made pin-configurable
|
||||||
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
#include "drivers/dma.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "rcc.h"
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "dma.h"
|
#include "drivers/rcc.h"
|
||||||
|
|
||||||
#include "serial.h"
|
#include "drivers/serial.h"
|
||||||
#include "serial_uart.h"
|
#include "drivers/serial_uart.h"
|
||||||
#include "serial_uart_impl.h"
|
#include "drivers/serial_uart_impl.h"
|
||||||
|
|
||||||
|
#ifdef USE_UART
|
||||||
|
|
||||||
static void handleUsartTxDma(uartPort_t *s);
|
static void handleUsartTxDma(uartPort_t *s);
|
||||||
|
|
||||||
#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
|
const uartHardware_t uartHardware[UARTDEV_COUNT] = {
|
||||||
#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
|
|
||||||
|
|
||||||
typedef struct uartDevice_s {
|
|
||||||
USART_TypeDef* dev;
|
|
||||||
uartPort_t port;
|
|
||||||
uint32_t DMAChannel;
|
|
||||||
DMA_Stream_TypeDef *txDMAStream;
|
|
||||||
DMA_Stream_TypeDef *rxDMAStream;
|
|
||||||
ioTag_t rx;
|
|
||||||
ioTag_t tx;
|
|
||||||
volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
|
|
||||||
volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
|
|
||||||
uint32_t rcc_ahb1;
|
|
||||||
rccPeriphTag_t rcc_apb2;
|
|
||||||
rccPeriphTag_t rcc_apb1;
|
|
||||||
uint8_t af;
|
|
||||||
uint8_t txIrq;
|
|
||||||
uint8_t rxIrq;
|
|
||||||
uint32_t txPriority;
|
|
||||||
uint32_t rxPriority;
|
|
||||||
} uartDevice_t;
|
|
||||||
|
|
||||||
//static uartPort_t uartPort[MAX_UARTS];
|
|
||||||
#ifdef USE_UART1
|
#ifdef USE_UART1
|
||||||
static uartDevice_t uart1 =
|
{
|
||||||
{
|
.device = UARTDEV_1,
|
||||||
|
.reg = USART1,
|
||||||
.DMAChannel = DMA_CHANNEL_4,
|
.DMAChannel = DMA_CHANNEL_4,
|
||||||
#ifdef USE_UART1_RX_DMA
|
#ifdef USE_UART1_RX_DMA
|
||||||
.rxDMAStream = DMA2_Stream5,
|
.rxDMAStream = DMA2_Stream5,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA2_Stream7,
|
.txDMAStream = DMA2_Stream7,
|
||||||
.dev = USART1,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART1_RX_PIN),
|
{ DEFIO_TAG_E(PA10), DEFIO_TAG_E(PA9) },
|
||||||
.tx = IO_TAG(UART1_TX_PIN),
|
{ DEFIO_TAG_E(PB7), DEFIO_TAG_E(PB6) },
|
||||||
|
},
|
||||||
.af = GPIO_AF7_USART1,
|
.af = GPIO_AF7_USART1,
|
||||||
#ifdef UART1_AHB1_PERIPHERALS
|
#ifdef UART1_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART1_AHB1_PERIPHERALS,
|
||||||
|
@ -76,20 +61,22 @@ static uartDevice_t uart1 =
|
||||||
.rxIrq = USART1_IRQn,
|
.rxIrq = USART1_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART1
|
.rxPriority = NVIC_PRIO_SERIALUART1
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART2
|
#ifdef USE_UART2
|
||||||
static uartDevice_t uart2 =
|
{
|
||||||
{
|
.device = UARTDEV_2,
|
||||||
|
.reg = USART2,
|
||||||
.DMAChannel = DMA_CHANNEL_4,
|
.DMAChannel = DMA_CHANNEL_4,
|
||||||
#ifdef USE_UART2_RX_DMA
|
#ifdef USE_UART2_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream5,
|
.rxDMAStream = DMA1_Stream5,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream6,
|
.txDMAStream = DMA1_Stream6,
|
||||||
.dev = USART2,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART2_RX_PIN),
|
{ DEFIO_TAG_E(PA3), DEFIO_TAG_E(PA2) },
|
||||||
.tx = IO_TAG(UART2_TX_PIN),
|
{ DEFIO_TAG_E(PD6), DEFIO_TAG_E(PD5) },
|
||||||
|
},
|
||||||
.af = GPIO_AF7_USART2,
|
.af = GPIO_AF7_USART2,
|
||||||
#ifdef UART2_AHB1_PERIPHERALS
|
#ifdef UART2_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART2_AHB1_PERIPHERALS,
|
||||||
|
@ -99,20 +86,23 @@ static uartDevice_t uart2 =
|
||||||
.rxIrq = USART2_IRQn,
|
.rxIrq = USART2_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART2
|
.rxPriority = NVIC_PRIO_SERIALUART2
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART3
|
#ifdef USE_UART3
|
||||||
static uartDevice_t uart3 =
|
{
|
||||||
{
|
.device = UARTDEV_3,
|
||||||
|
.reg = USART3,
|
||||||
.DMAChannel = DMA_CHANNEL_4,
|
.DMAChannel = DMA_CHANNEL_4,
|
||||||
#ifdef USE_UART3_RX_DMA
|
#ifdef USE_UART3_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream1,
|
.rxDMAStream = DMA1_Stream1,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream3,
|
.txDMAStream = DMA1_Stream3,
|
||||||
.dev = USART3,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART3_RX_PIN),
|
{ DEFIO_TAG_E(PB11), DEFIO_TAG_E(PB10) },
|
||||||
.tx = IO_TAG(UART3_TX_PIN),
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
{ DEFIO_TAG_E(PD9), DEFIO_TAG_E(PD8) },
|
||||||
|
},
|
||||||
.af = GPIO_AF7_USART3,
|
.af = GPIO_AF7_USART3,
|
||||||
#ifdef UART3_AHB1_PERIPHERALS
|
#ifdef UART3_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART3_AHB1_PERIPHERALS,
|
||||||
|
@ -122,20 +112,22 @@ static uartDevice_t uart3 =
|
||||||
.rxIrq = USART3_IRQn,
|
.rxIrq = USART3_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART3
|
.rxPriority = NVIC_PRIO_SERIALUART3
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART4
|
#ifdef USE_UART4
|
||||||
static uartDevice_t uart4 =
|
{
|
||||||
{
|
.device = UARTDEV_4,
|
||||||
|
.reg = UART4,
|
||||||
.DMAChannel = DMA_CHANNEL_4,
|
.DMAChannel = DMA_CHANNEL_4,
|
||||||
#ifdef USE_UART4_RX_DMA
|
#ifdef USE_UART4_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream2,
|
.rxDMAStream = DMA1_Stream2,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream4,
|
.txDMAStream = DMA1_Stream4,
|
||||||
.dev = UART4,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART4_RX_PIN),
|
{ DEFIO_TAG_E(PA1), DEFIO_TAG_E(PA0) },
|
||||||
.tx = IO_TAG(UART4_TX_PIN),
|
{ DEFIO_TAG_E(PC11), DEFIO_TAG_E(PC10) },
|
||||||
|
},
|
||||||
.af = GPIO_AF8_UART4,
|
.af = GPIO_AF8_UART4,
|
||||||
#ifdef UART4_AHB1_PERIPHERALS
|
#ifdef UART4_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART4_AHB1_PERIPHERALS,
|
||||||
|
@ -145,20 +137,21 @@ static uartDevice_t uart4 =
|
||||||
.rxIrq = UART4_IRQn,
|
.rxIrq = UART4_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART4
|
.rxPriority = NVIC_PRIO_SERIALUART4
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART5
|
#ifdef USE_UART5
|
||||||
static uartDevice_t uart5 =
|
{
|
||||||
{
|
.device = UARTDEV_5,
|
||||||
|
.reg = UART5,
|
||||||
.DMAChannel = DMA_CHANNEL_4,
|
.DMAChannel = DMA_CHANNEL_4,
|
||||||
#ifdef USE_UART5_RX_DMA
|
#ifdef USE_UART5_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream0,
|
.rxDMAStream = DMA1_Stream0,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream7,
|
.txDMAStream = DMA1_Stream7,
|
||||||
.dev = UART5,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART5_RX_PIN),
|
{ DEFIO_TAG_E(PD2), DEFIO_TAG_E(PC12) },
|
||||||
.tx = IO_TAG(UART5_TX_PIN),
|
},
|
||||||
.af = GPIO_AF8_UART5,
|
.af = GPIO_AF8_UART5,
|
||||||
#ifdef UART5_AHB1_PERIPHERALS
|
#ifdef UART5_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART5_AHB1_PERIPHERALS,
|
||||||
|
@ -168,20 +161,22 @@ static uartDevice_t uart5 =
|
||||||
.rxIrq = UART5_IRQn,
|
.rxIrq = UART5_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART5
|
.rxPriority = NVIC_PRIO_SERIALUART5
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART6
|
#ifdef USE_UART6
|
||||||
static uartDevice_t uart6 =
|
{
|
||||||
{
|
.device = UARTDEV_6,
|
||||||
|
.reg = USART6,
|
||||||
.DMAChannel = DMA_CHANNEL_5,
|
.DMAChannel = DMA_CHANNEL_5,
|
||||||
#ifdef USE_UART6_RX_DMA
|
#ifdef USE_UART6_RX_DMA
|
||||||
.rxDMAStream = DMA2_Stream1,
|
.rxDMAStream = DMA2_Stream1,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA2_Stream6,
|
.txDMAStream = DMA2_Stream6,
|
||||||
.dev = USART6,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART6_RX_PIN),
|
{ DEFIO_TAG_E(PC7), DEFIO_TAG_E(PC6) },
|
||||||
.tx = IO_TAG(UART6_TX_PIN),
|
{ DEFIO_TAG_E(PG9), DEFIO_TAG_E(PG14) },
|
||||||
|
},
|
||||||
.af = GPIO_AF8_USART6,
|
.af = GPIO_AF8_USART6,
|
||||||
#ifdef UART6_AHB1_PERIPHERALS
|
#ifdef UART6_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART6_AHB1_PERIPHERALS,
|
||||||
|
@ -191,20 +186,22 @@ static uartDevice_t uart6 =
|
||||||
.rxIrq = USART6_IRQn,
|
.rxIrq = USART6_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART6
|
.rxPriority = NVIC_PRIO_SERIALUART6
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART7
|
#ifdef USE_UART7
|
||||||
static uartDevice_t uart7 =
|
{
|
||||||
{
|
.device = UARTDEV_7,
|
||||||
|
.reg = UART7,
|
||||||
.DMAChannel = DMA_CHANNEL_5,
|
.DMAChannel = DMA_CHANNEL_5,
|
||||||
#ifdef USE_UART7_RX_DMA
|
#ifdef USE_UART7_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream3,
|
.rxDMAStream = DMA1_Stream3,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream1,
|
.txDMAStream = DMA1_Stream1,
|
||||||
.dev = UART7,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART7_RX_PIN),
|
{ DEFIO_TAG_E(PE7), DEFIO_TAG_E(PE8) },
|
||||||
.tx = IO_TAG(UART7_TX_PIN),
|
{ DEFIO_TAG_E(PF6), DEFIO_TAG_E(PF7) },
|
||||||
|
},
|
||||||
.af = GPIO_AF8_UART7,
|
.af = GPIO_AF8_UART7,
|
||||||
#ifdef UART7_AHB1_PERIPHERALS
|
#ifdef UART7_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART7_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART7_AHB1_PERIPHERALS,
|
||||||
|
@ -214,19 +211,21 @@ static uartDevice_t uart7 =
|
||||||
.rxIrq = UART7_IRQn,
|
.rxIrq = UART7_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART7_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART7
|
.rxPriority = NVIC_PRIO_SERIALUART7
|
||||||
};
|
},
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_UART8
|
#ifdef USE_UART8
|
||||||
static uartDevice_t uart8 =
|
{
|
||||||
{
|
.device = UARTDEV_8,
|
||||||
|
.reg = UART8,
|
||||||
.DMAChannel = DMA_CHANNEL_5,
|
.DMAChannel = DMA_CHANNEL_5,
|
||||||
#ifdef USE_UART8_RX_DMA
|
#ifdef USE_UART8_RX_DMA
|
||||||
.rxDMAStream = DMA1_Stream6,
|
.rxDMAStream = DMA1_Stream6,
|
||||||
#endif
|
#endif
|
||||||
.txDMAStream = DMA1_Stream0,
|
.txDMAStream = DMA1_Stream0,
|
||||||
.dev = UART8,
|
.pinPair = {
|
||||||
.rx = IO_TAG(UART8_RX_PIN),
|
{ DEFIO_TAG_E(PE0), DEFIO_TAG_E(PE1) },
|
||||||
.tx = IO_TAG(UART8_TX_PIN),
|
},
|
||||||
.af = GPIO_AF8_UART8,
|
.af = GPIO_AF8_UART8,
|
||||||
#ifdef UART8_AHB1_PERIPHERALS
|
#ifdef UART8_AHB1_PERIPHERALS
|
||||||
.rcc_ahb1 = UART8_AHB1_PERIPHERALS,
|
.rcc_ahb1 = UART8_AHB1_PERIPHERALS,
|
||||||
|
@ -236,51 +235,7 @@ static uartDevice_t uart8 =
|
||||||
.rxIrq = UART8_IRQn,
|
.rxIrq = UART8_IRQn,
|
||||||
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
|
.txPriority = NVIC_PRIO_SERIALUART8_TXDMA,
|
||||||
.rxPriority = NVIC_PRIO_SERIALUART8
|
.rxPriority = NVIC_PRIO_SERIALUART8
|
||||||
};
|
},
|
||||||
#endif
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
static uartDevice_t* uartHardwareMap[] = {
|
|
||||||
#ifdef USE_UART1
|
|
||||||
&uart1,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART2
|
|
||||||
&uart2,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART3
|
|
||||||
&uart3,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART4
|
|
||||||
&uart4,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART5
|
|
||||||
&uart5,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART6
|
|
||||||
&uart6,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART7
|
|
||||||
&uart7,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
|
||||||
#ifdef USE_UART8
|
|
||||||
&uart8,
|
|
||||||
#else
|
|
||||||
NULL,
|
|
||||||
#endif
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
|
@ -361,140 +316,76 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
HAL_DMA_IRQHandler(&s->txDMAHandle);
|
HAL_DMA_IRQHandler(&s->txDMAHandle);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
// XXX Should serialUART be consolidated?
|
||||||
|
|
||||||
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||||
{
|
{
|
||||||
uartPort_t *s;
|
uartDevice_t *uartdev = uartDevmap[device];
|
||||||
|
if (!uartdev) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
uartDevice_t *uart = uartHardwareMap[device];
|
uartPort_t *s = &(uartdev->port);
|
||||||
if (!uart) return NULL;
|
|
||||||
|
|
||||||
s = &(uart->port);
|
|
||||||
s->port.vTable = uartVTable;
|
s->port.vTable = uartVTable;
|
||||||
|
|
||||||
s->port.baudRate = baudRate;
|
s->port.baudRate = baudRate;
|
||||||
|
|
||||||
s->port.rxBuffer = uart->rxBuffer;
|
s->port.rxBuffer = uartdev->rxBuffer;
|
||||||
s->port.txBuffer = uart->txBuffer;
|
s->port.txBuffer = uartdev->txBuffer;
|
||||||
s->port.rxBufferSize = sizeof(uart->rxBuffer);
|
s->port.rxBufferSize = ARRAYLEN(uartdev->rxBuffer);
|
||||||
s->port.txBufferSize = sizeof(uart->txBuffer);
|
s->port.txBufferSize = ARRAYLEN(uartdev->txBuffer);
|
||||||
|
|
||||||
s->USARTx = uart->dev;
|
const uartHardware_t *hardware = uartdev->hardware;
|
||||||
if (uart->rxDMAStream) {
|
|
||||||
s->rxDMAChannel = uart->DMAChannel;
|
s->USARTx = hardware->reg;
|
||||||
s->rxDMAStream = uart->rxDMAStream;
|
|
||||||
|
if (hardware->rxDMAStream) {
|
||||||
|
s->rxDMAChannel = hardware->DMAChannel;
|
||||||
|
s->rxDMAStream = hardware->rxDMAStream;
|
||||||
}
|
}
|
||||||
s->txDMAChannel = uart->DMAChannel;
|
s->txDMAChannel = hardware->DMAChannel;
|
||||||
s->txDMAStream = uart->txDMAStream;
|
s->txDMAStream = hardware->txDMAStream;
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
|
|
||||||
s->Handle.Instance = uart->dev;
|
s->Handle.Instance = hardware->reg;
|
||||||
|
|
||||||
IO_t tx = IOGetByTag(uart->tx);
|
IO_t txIO = IOGetByTag(uartdev->tx);
|
||||||
IO_t rx = IOGetByTag(uart->rx);
|
IO_t rxIO = IOGetByTag(uartdev->rx);
|
||||||
|
|
||||||
if ((options & SERIAL_BIDIR) && tx) {
|
if ((options & SERIAL_BIDIR) && txIO) {
|
||||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
// XXX BIDIR_PP handling is missing
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
IOConfigGPIOAF(txIO, IOCFG_AF_PP, hardware->af);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if ((mode & MODE_TX) && tx) {
|
if ((mode & MODE_TX) && txIO) {
|
||||||
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
IOInit(txIO, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(txIO, IOCFG_AF_PP, hardware->af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if ((mode & MODE_RX) && rx) {
|
if ((mode & MODE_RX) && rxIO) {
|
||||||
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
IOInit(rxIO, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(rxIO, IOCFG_AF_PP, hardware->af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
dmaInit(uart->txIrq, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
dmaInit(hardware->txIrq, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
dmaSetHandler(uart->txIrq, dmaIRQHandler, uart->txPriority, (uint32_t)uart);
|
dmaSetHandler(hardware->txIrq, dmaIRQHandler, hardware->txPriority, (uint32_t)uartdev);
|
||||||
|
|
||||||
|
|
||||||
//HAL_NVIC_SetPriority(uart->txIrq, NVIC_PRIORITY_BASE(uart->txPriority), NVIC_PRIORITY_SUB(uart->txPriority));
|
//HAL_NVIC_SetPriority(hardware->txIrq, NVIC_PRIORITY_BASE(hardware->txPriority), NVIC_PRIORITY_SUB(hardware->txPriority));
|
||||||
//HAL_NVIC_EnableIRQ(uart->txIrq);
|
//HAL_NVIC_EnableIRQ(hardware->txIrq);
|
||||||
|
|
||||||
if(!s->rxDMAChannel)
|
if(!s->rxDMAChannel)
|
||||||
{
|
{
|
||||||
HAL_NVIC_SetPriority(uart->rxIrq, NVIC_PRIORITY_BASE(uart->rxPriority), NVIC_PRIORITY_SUB(uart->rxPriority));
|
HAL_NVIC_SetPriority(hardware->rxIrq, NVIC_PRIORITY_BASE(hardware->rxPriority), NVIC_PRIORITY_SUB(hardware->rxPriority));
|
||||||
HAL_NVIC_EnableIRQ(uart->rxIrq);
|
HAL_NVIC_EnableIRQ(hardware->rxIrq);
|
||||||
}
|
}
|
||||||
|
|
||||||
return s;
|
return s;
|
||||||
}
|
}
|
||||||
|
#endif // USE_UART
|
||||||
#ifdef USE_UART1
|
|
||||||
// USART1 Rx/Tx IRQ Handler
|
|
||||||
void USART1_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART2
|
|
||||||
// USART2 Rx/Tx IRQ Handler
|
|
||||||
void USART2_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
// USART3 Rx/Tx IRQ Handler
|
|
||||||
void USART3_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART4
|
|
||||||
// UART4 Rx/Tx IRQ Handler
|
|
||||||
void UART4_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART5
|
|
||||||
// UART5 Rx/Tx IRQ Handler
|
|
||||||
void UART5_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART6
|
|
||||||
// USART6 Rx/Tx IRQ Handler
|
|
||||||
void USART6_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART7
|
|
||||||
// UART7 Rx/Tx IRQ Handler
|
|
||||||
void UART7_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_7]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART8
|
|
||||||
// UART8 Rx/Tx IRQ Handler
|
|
||||||
void UART8_IRQHandler(void)
|
|
||||||
{
|
|
||||||
uartPort_t *s = &(uartHardwareMap[UARTDEV_8]->port);
|
|
||||||
uartIrqHandler(s);
|
|
||||||
}
|
|
||||||
#endif
|
|
||||||
|
|
|
@ -52,7 +52,6 @@
|
||||||
#include "drivers/rx_spi.h"
|
#include "drivers/rx_spi.h"
|
||||||
#include "drivers/sdcard.h"
|
#include "drivers/sdcard.h"
|
||||||
#include "drivers/sensor.h"
|
#include "drivers/sensor.h"
|
||||||
#include "drivers/serial.h"
|
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
|
@ -150,7 +149,6 @@ PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
|
||||||
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
|
||||||
#endif
|
#endif
|
||||||
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
|
||||||
PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
|
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
||||||
|
@ -249,196 +247,6 @@ void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
|
|
||||||
// Default pin (NONE).
|
|
||||||
// XXX Does this mess belong here???
|
|
||||||
#ifdef USE_UART1
|
|
||||||
# if !defined(UART1_RX_PIN)
|
|
||||||
# define UART1_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART1_TX_PIN)
|
|
||||||
# define UART1_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART2
|
|
||||||
# if !defined(UART2_RX_PIN)
|
|
||||||
# define UART2_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART2_TX_PIN)
|
|
||||||
# define UART2_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART3
|
|
||||||
# if !defined(UART3_RX_PIN)
|
|
||||||
# define UART3_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART3_TX_PIN)
|
|
||||||
# define UART3_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART4
|
|
||||||
# if !defined(UART4_RX_PIN)
|
|
||||||
# define UART4_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART4_TX_PIN)
|
|
||||||
# define UART4_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART5
|
|
||||||
# if !defined(UART5_RX_PIN)
|
|
||||||
# define UART5_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART5_TX_PIN)
|
|
||||||
# define UART5_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART6
|
|
||||||
# if !defined(UART6_RX_PIN)
|
|
||||||
# define UART6_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART6_TX_PIN)
|
|
||||||
# define UART6_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART7
|
|
||||||
# if !defined(UART7_RX_PIN)
|
|
||||||
# define UART7_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART7_TX_PIN)
|
|
||||||
# define UART7_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_UART8
|
|
||||||
# if !defined(UART8_RX_PIN)
|
|
||||||
# define UART8_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(UART8_TX_PIN)
|
|
||||||
# define UART8_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_SOFTSERIAL1
|
|
||||||
# if !defined(SOFTSERIAL1_RX_PIN)
|
|
||||||
# define SOFTSERIAL1_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(SOFTSERIAL1_TX_PIN)
|
|
||||||
# define SOFTSERIAL1_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef USE_SOFTSERIAL2
|
|
||||||
# if !defined(SOFTSERIAL2_RX_PIN)
|
|
||||||
# define SOFTSERIAL2_RX_PIN NONE
|
|
||||||
# endif
|
|
||||||
# if !defined(SOFTSERIAL2_TX_PIN)
|
|
||||||
# define SOFTSERIAL2_TX_PIN NONE
|
|
||||||
# endif
|
|
||||||
#endif
|
|
||||||
|
|
||||||
void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
|
|
||||||
{
|
|
||||||
for (int port = 0 ; port < SERIAL_PORT_MAX_INDEX ; port++) {
|
|
||||||
serialPinConfig->ioTagRx[port] = IO_TAG(NONE);
|
|
||||||
serialPinConfig->ioTagTx[port] = IO_TAG(NONE);
|
|
||||||
}
|
|
||||||
|
|
||||||
for (int index = 0 ; index < SERIAL_PORT_COUNT ; index++) {
|
|
||||||
switch (serialPortIdentifiers[index]) {
|
|
||||||
case SERIAL_PORT_USART1:
|
|
||||||
#ifdef USE_UART1
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART1
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART1)] = IO_TAG(INVERTER_PIN_UART1);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USART2:
|
|
||||||
#ifdef USE_UART2
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART2
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART2)] = IO_TAG(INVERTER_PIN_UART2);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USART3:
|
|
||||||
#ifdef USE_UART3
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART3
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART3)] = IO_TAG(INVERTER_PIN_UART3);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_UART4:
|
|
||||||
#ifdef USE_UART4
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART4
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART4)] = IO_TAG(INVERTER_PIN_UART4);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_UART5:
|
|
||||||
#ifdef USE_UART5
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART5
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART5)] = IO_TAG(INVERTER_PIN_UART5);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USART6:
|
|
||||||
#ifdef USE_UART6
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_TX_PIN);
|
|
||||||
#ifdef INVERTER_PIN_UART6
|
|
||||||
serialPinConfig->ioTagInverter[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART6)] = IO_TAG(INVERTER_PIN_UART6);
|
|
||||||
#endif
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USART7:
|
|
||||||
#ifdef USE_UART7
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_TX_PIN);
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USART8:
|
|
||||||
#ifdef USE_UART8
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_TX_PIN);
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_SOFTSERIAL1:
|
|
||||||
#ifdef USE_SOFTSERIAL1
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_TX_PIN);
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_SOFTSERIAL2:
|
|
||||||
#ifdef USE_SOFTSERIAL2
|
|
||||||
serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_RX_PIN);
|
|
||||||
serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_TX_PIN);
|
|
||||||
#endif
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_USB_VCP:
|
|
||||||
break;
|
|
||||||
case SERIAL_PORT_NONE:
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
}
|
|
||||||
}
|
|
||||||
|
|
||||||
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
|
#ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
|
||||||
#define FIRST_PORT_INDEX 1
|
#define FIRST_PORT_INDEX 1
|
||||||
#define SECOND_PORT_INDEX 0
|
#define SECOND_PORT_INDEX 0
|
||||||
|
|
|
@ -281,6 +281,10 @@ void init(void)
|
||||||
busSwitchInit();
|
busSwitchInit();
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_UART
|
||||||
|
uartPinConfigure(serialPinConfig());
|
||||||
|
#endif
|
||||||
|
|
||||||
#if defined(AVOID_UART1_FOR_PWM_PPM)
|
#if defined(AVOID_UART1_FOR_PWM_PPM)
|
||||||
serialInit(feature(FEATURE_SOFTSERIAL),
|
serialInit(feature(FEATURE_SOFTSERIAL),
|
||||||
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
|
feature(FEATURE_RX_PPM) || feature(FEATURE_RX_PARALLEL_PWM) ? SERIAL_PORT_USART1 : SERIAL_PORT_NONE);
|
||||||
|
|
|
@ -32,17 +32,12 @@
|
||||||
|
|
||||||
#include "drivers/system.h"
|
#include "drivers/system.h"
|
||||||
#include "drivers/serial.h"
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/serial_uart.h"
|
||||||
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
#if defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2)
|
||||||
#include "drivers/serial_softserial.h"
|
#include "drivers/serial_softserial.h"
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_UART (defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) || defined(USE_UART7) || defined(USE_UART8))
|
#define USE_SERIAL (defined(USE_UART) || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
||||||
|
|
||||||
#define USE_SERIAL (USE_UART || defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
|
|
||||||
|
|
||||||
#if USE_UART
|
|
||||||
#include "drivers/serial_uart.h"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#include "drivers/light_led.h"
|
#include "drivers/light_led.h"
|
||||||
|
|
||||||
|
|
|
@ -59,14 +59,14 @@
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 0
|
#define USABLE_TIMER_CHANNEL_COUNT 0
|
||||||
|
|
||||||
#define USE_UART1
|
//#define USE_UART1
|
||||||
#define USE_UART2
|
//#define USE_UART2
|
||||||
#define USE_UART3
|
//#define USE_UART3
|
||||||
#define USE_UART4
|
//#define USE_UART4
|
||||||
#define USE_UART5
|
//#define USE_UART5
|
||||||
#define USE_UART6
|
//#define USE_UART6
|
||||||
#define USE_UART7
|
//#define USE_UART7
|
||||||
#define USE_UART8
|
//#define USE_UART8
|
||||||
|
|
||||||
//#define USE_SOFTSERIAL1
|
//#define USE_SOFTSERIAL1
|
||||||
//#define USE_SOFTSERIAL2
|
//#define USE_SOFTSERIAL2
|
||||||
|
|
Loading…
Reference in New Issue