1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-24 16:55:36 +03:00

get GPIO and USART ports working.

The STM32F3DISCOVERY board would crash when setting GPIOA Pin_13 or
Pin_14 to analog mode so they are excluded in the gpio initialisation.

The USART GPIO configuration did not work when using the F10x code.  The
USART status and DMA registers are different too.
This commit is contained in:
Dominic Clifton 2014-04-25 15:19:28 +01:00
parent 2cc3a50c01
commit 8d9ce86a5a
9 changed files with 3720 additions and 3 deletions

View file

@ -1,5 +1,6 @@
#pragma once
#ifdef STM32F10X_MD
typedef enum
{
Mode_AIN = 0x0,
@ -11,6 +12,45 @@ typedef enum
Mode_AF_OD = 0x1C,
Mode_AF_PP = 0x18
} GPIO_Mode;
#endif
#ifdef STM32F303xC
/*
typedef enum
{
GPIO_Mode_IN = 0x00, // GPIO Input Mode
GPIO_Mode_OUT = 0x01, // GPIO Output Mode
GPIO_Mode_AF = 0x02, // GPIO Alternate function Mode
GPIO_Mode_AN = 0x03 // GPIO Analog In/Out Mode
}GPIOMode_TypeDef;
typedef enum
{
GPIO_OType_PP = 0x00,
GPIO_OType_OD = 0x01
}GPIOOType_TypeDef;
typedef enum
{
GPIO_PuPd_NOPULL = 0x00,
GPIO_PuPd_UP = 0x01,
GPIO_PuPd_DOWN = 0x02
}GPIOPuPd_TypeDef;
*/
typedef enum
{
Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF
} GPIO_Mode;
#endif
typedef enum
{

View file

@ -6,9 +6,66 @@
#include "gpio_common.h"
#define MODE_OFFSET 0
#define PUPD_OFFSET 2
#define OUTPUT_OFFSET 4
#define MODE_MASK ((1|2) << MODE_OFFSET)
#define PUPD_MASK ((1|2) << PUPD_OFFSET)
#define OUTPUT_MASK ((1|2) << OUTPUT_OFFSET)
/*
typedef enum
{
Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF
} GPIO_Mode;
*/
//#define GPIO_Speed_10MHz GPIO_Speed_Level_1 Fast Speed:10MHz
//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
{
// FIXME implement
GPIO_InitTypeDef GPIO_InitStructure;
uint32_t pinIndex;
for (pinIndex = 0; pinIndex < 16; pinIndex++) {
// are we doing this pin?
uint32_t pinMask = (0x1 << pinIndex);
if (config->pin & pinMask) {
GPIO_InitStructure.GPIO_Pin = pinMask;
GPIO_InitStructure.GPIO_Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
GPIOSpeed_TypeDef speed = GPIO_Speed_10MHz;
switch (config->speed) {
case Speed_10MHz:
speed = GPIO_Speed_Level_1;
break;
case Speed_2MHz:
speed = GPIO_Speed_Level_2;
break;
case Speed_50MHz:
speed = GPIO_Speed_Level_3;
break;
}
GPIO_InitStructure.GPIO_Speed = speed;
GPIO_InitStructure.GPIO_OType = (config->mode >> OUTPUT_OFFSET) & OUTPUT_MASK;
GPIO_InitStructure.GPIO_PuPd = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
GPIO_Init(gpio, &GPIO_InitStructure);
}
}
}
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)

View file

@ -25,7 +25,6 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
uartPort_t *s;
static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE];
static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE];
gpio_config_t gpio;
NVIC_InitTypeDef NVIC_InitStructure;
s = &uartPort1;
@ -42,8 +41,34 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
s->txDMAChannel = DMA1_Channel4;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE);
// USART1_TX PA9
// USART1_RX PA10
#ifdef STM32F303xC
#define UART1_TX_PIN GPIO_Pin_9
#define UART1_RX_PIN GPIO_Pin_10
#define UART1_GPIO GPIOA
#define UART1_TX_PINSOURCE GPIO_PinSource9
#define UART1_RX_PINSOURCE GPIO_PinSource10
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN | UART1_RX_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, GPIO_AF_7);
GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, GPIO_AF_7);
GPIO_Init(UART1_GPIO, &GPIO_InitStructure);
#endif
#ifdef STM32F10X_MD
gpio_config_t gpio;
gpio.speed = Speed_2MHz;
gpio.pin = Pin_9;
gpio.mode = Mode_AF_PP;
@ -53,6 +78,7 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode)
gpio.mode = Mode_IPU;
if (mode & MODE_RX)
gpioInit(GPIOA, &gpio);
#endif
// DMA TX Interrupt
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn;
@ -146,7 +172,6 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
if (mode & MODE_TX)
USART_InitStructure.USART_Mode |= USART_Mode_Tx;
USART_Init(USARTx, &USART_InitStructure);
USART_Cmd(USARTx, ENABLE);
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&USARTx->RDR;
@ -200,6 +225,8 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
}
}
USART_Cmd(USARTx, ENABLE);
return (serialPort_t *)s;
}

View file

@ -110,9 +110,15 @@ void systemInit(bool overclock)
RCC_ClearFlag();
// Make all GPIO in by default to save power and reduce noise
gpio.pin = Pin_All;
gpio.mode = Mode_AIN;
gpio.pin = Pin_All;
#ifdef STM32F3DISCOVERY
gpio.pin = Pin_All & ~(Pin_13|Pin_14);
gpioInit(GPIOA, &gpio);
gpio.pin = Pin_All;
#else
gpioInit(GPIOA, &gpio);
#endif
gpioInit(GPIOB, &gpio);
gpioInit(GPIOC, &gpio);

View file

@ -4,6 +4,8 @@
#ifdef STM32F3DISCOVERY
#include "stm32f30x_conf.h"
#include "stm32f30x_rcc.h"
#include "stm32f30x_gpio.h"
#include "core_cm4.h"
// FIXME use correct ID