mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-13 11:29:58 +03:00
initial pass at gpio cleanup. removed almost all dependency on stdperiphlib (remaining exti).
slightly modified initial pin configuration, but this needs rework soon anyway. couple spacing/line ending/formatting fixes in sonar driver file while fixing gpio there. git-svn-id: https://afrodevices.googlecode.com/svn/trunk/baseflight@357 7c89a4a9-59b9-e629-4cfe-3a2d53b20e61
This commit is contained in:
parent
eec35a20fd
commit
d442c9dfb6
18 changed files with 2174 additions and 2096 deletions
|
@ -348,7 +348,7 @@
|
|||
<uThumb>0</uThumb>
|
||||
<uSurpInc>0</uSurpInc>
|
||||
<VariousControls>
|
||||
<MiscControls></MiscControls>
|
||||
<MiscControls>--c99 --gnu</MiscControls>
|
||||
<Define>STM32F10X_MD,USE_STDPERIPH_DRIVER</Define>
|
||||
<Undefine></Undefine>
|
||||
<IncludePath>lib\CMSIS\CM3\CoreSupport;lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x;lib\STM32F10x_StdPeriph_Driver\inc</IncludePath>
|
||||
|
@ -637,6 +637,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_ms5611.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_gpio.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -1154,7 +1159,7 @@
|
|||
<uThumb>0</uThumb>
|
||||
<uSurpInc>0</uSurpInc>
|
||||
<VariousControls>
|
||||
<MiscControls></MiscControls>
|
||||
<MiscControls>--c99 --gnu</MiscControls>
|
||||
<Define>STM32F10X_MD,USE_STDPERIPH_DRIVER</Define>
|
||||
<Undefine></Undefine>
|
||||
<IncludePath>CoOS\portable;CoOS\kernel;lib\CMSIS\CM3\CoreSupport;lib\CMSIS\CM3\DeviceSupport\ST\STM32F10x;lib\STM32F10x_StdPeriph_Driver\inc</IncludePath>
|
||||
|
@ -1443,6 +1448,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_ms5611.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_gpio.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
@ -2433,6 +2443,11 @@
|
|||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_ms5611.c</FilePath>
|
||||
</File>
|
||||
<File>
|
||||
<FileName>drv_gpio.c</FileName>
|
||||
<FileType>1</FileType>
|
||||
<FilePath>.\src\drv_gpio.c</FilePath>
|
||||
</File>
|
||||
</Files>
|
||||
</Group>
|
||||
<Group>
|
||||
|
|
3842
obj/baseflight.hex
3842
obj/baseflight.hex
File diff suppressed because it is too large
Load diff
11
src/board.h
11
src/board.h
|
@ -20,6 +20,9 @@
|
|||
#include "printf.h"
|
||||
#endif
|
||||
|
||||
#include "drv_system.h" // timers, delays, etc
|
||||
#include "drv_gpio.h"
|
||||
|
||||
#ifndef M_PI
|
||||
#define M_PI 3.14159265358979323846f
|
||||
#endif /* M_PI */
|
||||
|
@ -102,12 +105,7 @@ typedef struct baro_t
|
|||
baroCalculateFuncPtr calculate;
|
||||
} baro_t;
|
||||
|
||||
#define digitalHi(p, i) { p->BSRR = i; }
|
||||
#define digitalLo(p, i) { p->BRR = i; }
|
||||
#define digitalToggle(p, i) { p->ODR ^= i; }
|
||||
|
||||
// Hardware definitions and GPIO
|
||||
|
||||
#ifdef FY90Q
|
||||
// FY90Q
|
||||
#define LED0_GPIO GPIOC
|
||||
|
@ -182,7 +180,6 @@ typedef struct baro_t
|
|||
|
||||
#ifdef FY90Q
|
||||
// FY90Q
|
||||
#include "drv_system.h" // timers, delays, etc
|
||||
#include "drv_adc.h"
|
||||
#include "drv_i2c.h"
|
||||
#include "drv_pwm.h"
|
||||
|
@ -191,7 +188,6 @@ typedef struct baro_t
|
|||
|
||||
#ifdef OLIMEXINO
|
||||
// OLIMEXINO
|
||||
#include "drv_system.h" // timers, delays, etc
|
||||
#include "drv_adc.h"
|
||||
#include "drv_i2c.h"
|
||||
#include "drv_adxl345.h"
|
||||
|
@ -203,7 +199,6 @@ typedef struct baro_t
|
|||
#else
|
||||
|
||||
// AfroFlight32
|
||||
#include "drv_system.h" // timers, delays, etc
|
||||
#include "drv_adc.h"
|
||||
#include "drv_adxl345.h"
|
||||
#include "drv_bmp085.h"
|
||||
|
|
|
@ -90,7 +90,7 @@ static void bmp085_calculate(int32_t *pressure, int32_t *temperature);
|
|||
|
||||
bool bmp085Detect(baro_t *baro)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
EXTI_InitTypeDef EXTI_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
uint8_t data;
|
||||
|
@ -99,13 +99,13 @@ bool bmp085Detect(baro_t *baro)
|
|||
return true;
|
||||
|
||||
// PC13, PC14 (Barometer XCLR reset output, EOC input)
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_14;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
gpio.pin = Pin_14;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
BARO_ON;
|
||||
|
||||
// EXTI interrupt for barometer EOC
|
||||
|
|
33
src/drv_gpio.c
Normal file
33
src/drv_gpio.c
Normal file
|
@ -0,0 +1,33 @@
|
|||
#include "board.h"
|
||||
|
||||
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
|
||||
{
|
||||
uint32_t pinpos;
|
||||
for (pinpos = 0; pinpos < 16; pinpos++) {
|
||||
// are we doing this pin?
|
||||
if (config->pin & (0x1 << pinpos)) {
|
||||
// reference CRL or CRH, depending whether pin number is 0..7 or 8..15
|
||||
__IO uint32_t *cr = &gpio->CRL + (pinpos / 8);
|
||||
// mask out extra bits from pinmode, leaving just CNF+MODE
|
||||
uint32_t currentmode = config->mode & 0x0F;
|
||||
// offset to CNF and MODE portions of CRx register
|
||||
uint32_t shift = (pinpos % 8) * 4;
|
||||
// Read out current CRx value
|
||||
uint32_t tmp = *cr;
|
||||
// if we're in output mode, add speed too.
|
||||
if (config->mode & 0x10)
|
||||
currentmode |= config->speed;
|
||||
// Mask out 4 bits
|
||||
tmp &= ~(0xF << shift);
|
||||
// apply current pinmode
|
||||
tmp |= currentmode << shift;
|
||||
*cr = tmp;
|
||||
// Special handling for IPD/IPU
|
||||
if (config->mode == Mode_IPD) {
|
||||
gpio->ODR &= ~(1U << pinpos);
|
||||
} else if (config->mode == Mode_IPU) {
|
||||
gpio->ODR |= (1U << pinpos);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
55
src/drv_gpio.h
Normal file
55
src/drv_gpio.h
Normal file
|
@ -0,0 +1,55 @@
|
|||
#pragma once
|
||||
|
||||
typedef enum
|
||||
{
|
||||
Mode_AIN = 0x0,
|
||||
Mode_IN_FLOATING = 0x04,
|
||||
Mode_IPD = 0x28,
|
||||
Mode_IPU = 0x48,
|
||||
Mode_Out_OD = 0x14,
|
||||
Mode_Out_PP = 0x10,
|
||||
Mode_AF_OD = 0x1C,
|
||||
Mode_AF_PP = 0x18
|
||||
} GPIO_Mode;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
Speed_10MHz = 1,
|
||||
Speed_2MHz,
|
||||
Speed_50MHz
|
||||
} GPIO_Speed;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
Pin_0 = 0x0000,
|
||||
Pin_1 = 0x0001,
|
||||
Pin_2 = 0x0004,
|
||||
Pin_3 = 0x0008,
|
||||
Pin_4 = 0x0010,
|
||||
Pin_5 = 0x0020,
|
||||
Pin_6 = 0x0040,
|
||||
Pin_7 = 0x0080,
|
||||
Pin_8 = 0x0100,
|
||||
Pin_9 = 0x0200,
|
||||
Pin_10 = 0x0400,
|
||||
Pin_11 = 0x0800,
|
||||
Pin_12 = 0x1000,
|
||||
Pin_13 = 0x2000,
|
||||
Pin_14 = 0x4000,
|
||||
Pin_15 = 0x8000,
|
||||
Pin_All = 0xFFFF
|
||||
} GPIO_Pin;
|
||||
|
||||
typedef struct
|
||||
{
|
||||
uint16_t pin;
|
||||
GPIO_Mode mode;
|
||||
GPIO_Speed speed;
|
||||
} gpio_config_t;
|
||||
|
||||
#define digitalHi(p, i) { p->BSRR = i; }
|
||||
#define digitalLo(p, i) { p->BRR = i; }
|
||||
#define digitalToggle(p, i) { p->ODR ^= i; }
|
||||
#define digitalIn(p, i) (p->IDR & i)
|
||||
|
||||
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config);
|
|
@ -25,13 +25,11 @@ void ECHO_EXTI_IRQHandler(void)
|
|||
{
|
||||
static uint32_t timing_start;
|
||||
uint32_t timing_stop;
|
||||
if(GPIO_ReadInputDataBit(GPIOB, echo_pin) != 0)
|
||||
if (digitalIn(GPIOB, echo_pin) != 0) {
|
||||
timing_start = micros();
|
||||
else
|
||||
{
|
||||
} else {
|
||||
timing_stop = micros();
|
||||
if(timing_stop > timing_start)
|
||||
{
|
||||
if (timing_stop > timing_start) {
|
||||
// The speed of sound is 340 m/s or approx. 29 microseconds per centimeter.
|
||||
// The ping travels out and back, so to find the distance of the
|
||||
// object we take half of the distance traveled.
|
||||
|
@ -57,24 +55,23 @@ void EXTI9_5_IRQHandler(void)
|
|||
|
||||
void hcsr04_init(sonar_config_t config)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
EXTI_InitTypeDef EXTIInit;
|
||||
|
||||
// enable AFIO for EXTI support - already done is drv_system.c
|
||||
// RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO | RCC_APB2Periph, ENABLE);
|
||||
|
||||
switch(config)
|
||||
{
|
||||
switch(config) {
|
||||
case sonar_pwm56:
|
||||
trigger_pin = GPIO_Pin_8; // PWM5 (PB8) - 5v tolerant
|
||||
echo_pin = GPIO_Pin_9; // PWM6 (PB9) - 5v tolerant
|
||||
trigger_pin = Pin_8; // PWM5 (PB8) - 5v tolerant
|
||||
echo_pin = Pin_9; // PWM6 (PB9) - 5v tolerant
|
||||
exti_line = EXTI_Line9;
|
||||
exti_pin_source = GPIO_PinSource9;
|
||||
exti_irqn = EXTI9_5_IRQn;
|
||||
break;
|
||||
case sonar_rc78:
|
||||
trigger_pin = GPIO_Pin_0; // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
||||
echo_pin = GPIO_Pin_1; // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
||||
trigger_pin = Pin_0; // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
|
||||
echo_pin = Pin_1; // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
|
||||
exti_line = EXTI_Line1;
|
||||
exti_pin_source = GPIO_PinSource1;
|
||||
exti_irqn = EXTI1_IRQn;
|
||||
|
@ -82,15 +79,15 @@ void hcsr04_init(sonar_config_t config)
|
|||
}
|
||||
|
||||
// tp - trigger pin
|
||||
GPIO_InitStructure.GPIO_Pin = trigger_pin;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = trigger_pin;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
// ep - echo pin
|
||||
GPIO_InitStructure.GPIO_Pin = echo_pin;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = echo_pin;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
// setup external interrupt on echo pin
|
||||
GPIO_EXTILineConfig(GPIO_PortSourceGPIOB, exti_pin_source);
|
||||
|
@ -113,8 +110,7 @@ void hcsr04_get_distance(volatile int16_t* distance)
|
|||
{
|
||||
uint32_t current_time = millis();
|
||||
|
||||
if( current_time < (last_measurement + 60) )
|
||||
{
|
||||
if (current_time < (last_measurement + 60)) {
|
||||
// the repeat interval of trig signal should be greater than 60ms
|
||||
// to avoid interference between connective measurements.
|
||||
return;
|
||||
|
@ -123,10 +119,9 @@ void hcsr04_get_distance(volatile int16_t* distance)
|
|||
last_measurement = current_time;
|
||||
distance_ptr = distance;
|
||||
|
||||
GPIO_SetBits(GPIOB, trigger_pin);
|
||||
digitalHi(GPIOB, trigger_pin);
|
||||
// The width of trig signal must be greater than 10us
|
||||
delayMicroseconds(11);
|
||||
GPIO_ResetBits(GPIOB, trigger_pin);
|
||||
digitalLo(GPIOB, trigger_pin);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -35,7 +35,7 @@ bool hmc5883lDetect(int8_t *align)
|
|||
|
||||
void hmc5883lInit(float *calibrationGain)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
float magGain[3];
|
||||
int16_t magADC[3];
|
||||
int i;
|
||||
|
@ -43,10 +43,10 @@ void hmc5883lInit(float *calibrationGain)
|
|||
bool bret = true; // Error indicator
|
||||
|
||||
// PB12 - MAG_DRDY output on rev4 hardware
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_12;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
delay(50);
|
||||
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
|
||||
|
|
|
@ -254,14 +254,14 @@ void i2c_ev_handler(void)
|
|||
void i2cInit(I2C_TypeDef *I2C)
|
||||
{
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
I2C_InitTypeDef I2C_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_10 | Pin_11;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
I2Cx = I2C;
|
||||
|
||||
|
@ -303,45 +303,44 @@ uint16_t i2cGetErrorCounter(void)
|
|||
|
||||
static void i2cUnstick(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
uint8_t i;
|
||||
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_10 | Pin_11;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_OD;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_10 | GPIO_Pin_11);
|
||||
digitalHi(GPIOB, Pin_10 | Pin_11);
|
||||
for (i = 0; i < 8; i++) {
|
||||
// Wait for any clock stretching to finish
|
||||
while (!GPIO_ReadInputDataBit(GPIOB, GPIO_Pin_10))
|
||||
while (!digitalIn(GPIOB, Pin_10))
|
||||
delayMicroseconds(10);
|
||||
|
||||
// Pull low
|
||||
GPIO_ResetBits(GPIOB, GPIO_Pin_10); //Set bus low
|
||||
digitalLo(GPIOB, Pin_10); // Set bus low
|
||||
delayMicroseconds(10);
|
||||
// Release high again
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_10); //Set bus high
|
||||
digitalHi(GPIOB, Pin_10); // Set bus high
|
||||
delayMicroseconds(10);
|
||||
}
|
||||
|
||||
// Generate a start then stop condition
|
||||
// SCL PB10
|
||||
// SDA PB11
|
||||
|
||||
GPIO_ResetBits(GPIOB, GPIO_Pin_11); // Set bus data low
|
||||
digitalLo(GPIOB, Pin_11); // Set bus data low
|
||||
delayMicroseconds(10);
|
||||
GPIO_ResetBits(GPIOB, GPIO_Pin_10); // Set bus scl low
|
||||
digitalLo(GPIOB, Pin_10); // Set bus scl low
|
||||
delayMicroseconds(10);
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_10); // Set bus scl high
|
||||
digitalHi(GPIOB, Pin_10); // Set bus scl high
|
||||
delayMicroseconds(10);
|
||||
GPIO_SetBits(GPIOB, GPIO_Pin_11); // Set bus sda high
|
||||
digitalHi(GPIOB, Pin_11); // Set bus sda high
|
||||
|
||||
// Init pins
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_OD;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_10 | Pin_11;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_AF_OD;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -131,12 +131,12 @@ static uint8_t I2C_ReceiveByte(void)
|
|||
|
||||
void i2cInit(I2C_TypeDef * I2C)
|
||||
{
|
||||
GPIO_InitTypeDef gpio;
|
||||
GPIO_Config gpio;
|
||||
|
||||
gpio.GPIO_Pin = GPIO_Pin_10 | GPIO_Pin_11;
|
||||
gpio.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
gpio.GPIO_Mode = GPIO_Mode_Out_OD;
|
||||
GPIO_Init(GPIOB, &gpio);
|
||||
gpio.pin = Pin_10 | Pin_11;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_OD;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
}
|
||||
|
||||
bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
|
||||
|
|
|
@ -72,14 +72,14 @@ bool mma8452Detect(sensor_t *acc)
|
|||
|
||||
static void mma8452Init(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
|
||||
// PA5 - ACC_INT2 output on rev3/4 hardware
|
||||
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_5;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_5;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff
|
||||
i2cWrite(MMA8452_ADDRESS, MMA8452_XYZ_DATA_CFG, MMA8452_FS_RANGE_8G);
|
||||
|
|
|
@ -266,13 +266,13 @@ static void mpu6050AccAlign(int16_t *accData)
|
|||
|
||||
static void mpu6050GyroInit(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
|
||||
// PB13 - MPU_INT output on rev4 hardware
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN_FLOATING;
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_IN_FLOATING;
|
||||
gpioInit(GPIOB, &gpio);
|
||||
|
||||
#ifndef MPU6050_DMP
|
||||
i2cWrite(MPU6050_ADDRESS, MPU_RA_PWR_MGMT_1, 0x80); //PWR_MGMT_1 -- DEVICE_RESET 1
|
||||
|
|
|
@ -36,16 +36,16 @@ static uint8_t ms5611_osr = CMD_ADC_4096;
|
|||
|
||||
bool ms5611Detect(baro_t *baro)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
bool ack = false;
|
||||
uint8_t sig;
|
||||
int i;
|
||||
|
||||
// PC13 (BMP085's XCLR reset input, which we use to disable it)
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_13;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_PP;
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_13;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_Out_PP;
|
||||
gpioInit(GPIOC, &gpio);
|
||||
BMP085_OFF;
|
||||
|
||||
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
|
||||
|
|
|
@ -266,16 +266,15 @@ static void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
|||
|
||||
static void pwmGPIOConfig(GPIO_TypeDef *gpio, uint32_t pin, uint8_t input)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t cfg;
|
||||
|
||||
GPIO_StructInit(&GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = pin;
|
||||
cfg.pin = pin;
|
||||
if (input)
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPD;
|
||||
cfg.mode = Mode_IPD;
|
||||
else
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_Init(gpio, &GPIO_InitStructure);
|
||||
cfg.mode = Mode_AF_PP;
|
||||
cfg.speed = Speed_2MHz;
|
||||
gpioInit(gpio, &cfg);
|
||||
}
|
||||
|
||||
static pwmPortData_t *pwmOutConfig(uint8_t port, uint16_t period, uint16_t value)
|
||||
|
|
|
@ -1,12 +1,5 @@
|
|||
#include "board.h"
|
||||
|
||||
typedef struct gpio_config_t
|
||||
{
|
||||
GPIO_TypeDef *gpio;
|
||||
uint16_t pin;
|
||||
GPIOMode_TypeDef mode;
|
||||
} gpio_config_t;
|
||||
|
||||
// cycles per microsecond
|
||||
static volatile uint32_t usTicks = 0;
|
||||
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.
|
||||
|
@ -44,17 +37,28 @@ uint32_t millis(void)
|
|||
|
||||
void systemInit(void)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
uint32_t i;
|
||||
|
||||
gpio_config_t gpio_cfg[] = {
|
||||
{ LED0_GPIO, LED0_PIN, GPIO_Mode_Out_PP },
|
||||
{ LED1_GPIO, LED1_PIN, GPIO_Mode_Out_PP },
|
||||
struct {
|
||||
GPIO_TypeDef *gpio;
|
||||
gpio_config_t cfg;
|
||||
} gpio_setup[] = {
|
||||
{
|
||||
.gpio = LED0_GPIO,
|
||||
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
|
||||
},
|
||||
{
|
||||
.gpio = LED1_GPIO,
|
||||
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
|
||||
},
|
||||
#ifdef BUZZER
|
||||
{ BEEP_GPIO, BEEP_PIN, GPIO_Mode_Out_OD },
|
||||
{
|
||||
.gpio = BEEP_GPIO,
|
||||
.cfg = { BEEP_PIN, Mode_Out_OD, Speed_2MHz }
|
||||
},
|
||||
#endif
|
||||
};
|
||||
uint8_t gpio_count = sizeof(gpio_cfg) / sizeof(gpio_cfg[0]);
|
||||
gpio_config_t gpio;
|
||||
uint32_t i;
|
||||
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
|
||||
|
||||
// This is needed because some shit inside Keil startup fucks with SystemCoreClock, setting it back to 72MHz even on HSI.
|
||||
SystemCoreClockUpdate();
|
||||
|
@ -66,22 +70,19 @@ void systemInit(void)
|
|||
RCC_ClearFlag();
|
||||
|
||||
// Make all GPIO in by default to save power and reduce noise
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AIN;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOB, &GPIO_InitStructure);
|
||||
GPIO_Init(GPIOC, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_All;
|
||||
gpio.mode = Mode_AIN;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpioInit(GPIOB, &gpio);
|
||||
gpioInit(GPIOC, &gpio);
|
||||
|
||||
// Turn off JTAG port 'cause we're using the GPIO for leds
|
||||
GPIO_PinRemapConfig(GPIO_Remap_SWJ_JTAGDisable, ENABLE);
|
||||
#define AFIO_MAPR_SWJ_CFG_NO_JTAG_SW (0x2 << 24)
|
||||
AFIO->MAPR |= AFIO_MAPR_SWJ_CFG_NO_JTAG_SW;
|
||||
|
||||
// Configure gpio
|
||||
for (i = 0; i < gpio_count; i++) {
|
||||
GPIO_InitStructure.GPIO_Pin = gpio_cfg[i].pin;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = gpio_cfg[i].mode;
|
||||
GPIO_Init(gpio_cfg[i].gpio, &GPIO_InitStructure);
|
||||
}
|
||||
for (i = 0; i < gpio_count; i++)
|
||||
gpioInit(gpio_setup[i].gpio, &gpio_setup[i].cfg);
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
|
|
@ -41,20 +41,20 @@ void DMA1_Channel4_IRQHandler(void)
|
|||
|
||||
void uartInit(uint32_t speed)
|
||||
{
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
USART_InitTypeDef USART_InitStructure;
|
||||
DMA_InitTypeDef DMA_InitStructure;
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
|
||||
// USART1_TX PA9
|
||||
// USART1_RX PA10
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_9;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_10;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
gpio.pin = Pin_9;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpio.pin = Pin_10;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
// DMA TX Interrupt
|
||||
NVIC_InitStructure.NVIC_IRQChannel = DMA1_Channel4_IRQn;
|
||||
|
@ -183,7 +183,7 @@ static void uart2Open(uint32_t speed)
|
|||
void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly)
|
||||
{
|
||||
NVIC_InitTypeDef NVIC_InitStructure;
|
||||
GPIO_InitTypeDef GPIO_InitStructure;
|
||||
gpio_config_t gpio;
|
||||
|
||||
RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE);
|
||||
|
||||
|
@ -197,14 +197,14 @@ void uart2Init(uint32_t speed, uartReceiveCallbackPtr func, bool rxOnly)
|
|||
|
||||
// USART2_TX PA2
|
||||
// USART2_RX PA3
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_2;
|
||||
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_2MHz;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF_PP;
|
||||
gpio.pin = GPIO_Pin_2;
|
||||
gpio.speed = Speed_2MHz;
|
||||
gpio.mode = Mode_AF_PP;
|
||||
if (!rxOnly)
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_3;
|
||||
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IPU;
|
||||
GPIO_Init(GPIOA, &GPIO_InitStructure);
|
||||
gpioInit(GPIOA, &gpio);
|
||||
gpio.pin = Pin_3;
|
||||
gpio.mode = Mode_IPU;
|
||||
gpioInit(GPIOA, &gpio);
|
||||
|
||||
uart2Open(speed);
|
||||
USART_ITConfig(USART2, USART_IT_RXNE, ENABLE);
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue