Merge pull request #435 from blckmn/resource_rework

Moving EXTI to IO
This commit is contained in:
borisbstyle 2016-06-06 01:43:32 +02:00
commit 55d8eb57be
84 changed files with 1843 additions and 2709 deletions

View File

@ -397,7 +397,7 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/flash_m25p16.c \
drivers/gpio_stm32f10x.c \
drivers/inverter.c \
drivers/light_led_stm32f10x.c \
drivers/light_led.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f10x.c \
drivers/sonar_hcsr04.c \
@ -407,7 +407,6 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
drivers/serial_softserial.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
@ -443,7 +442,7 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
drivers/flash_m25p16.c \
drivers/gpio_stm32f10x.c \
drivers/inverter.c \
drivers/light_led_stm32f10x.c \
drivers/light_led.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f10x.c \
drivers/pwm_mapping.c \
@ -453,7 +452,6 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sonar_hcsr04.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
@ -474,7 +472,7 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/bus_spi.c \
drivers/compass_hmc5883l.c \
drivers/gpio_stm32f10x.c \
drivers/light_led_stm32f10x.c \
drivers/light_led.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f10x.c \
drivers/pwm_mapping.c \
@ -484,7 +482,6 @@ OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sonar_hcsr04.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
@ -500,13 +497,12 @@ CJMCU_SRC = \
drivers/bus_i2c_stm32f10x.c \
drivers/compass_hmc5883l.c \
drivers/gpio_stm32f10x.c \
drivers/light_led_stm32f10x.c \
drivers/light_led.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rx.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
@ -532,7 +528,7 @@ CC3D_SRC = \
drivers/flash_m25p16.c \
drivers/gpio_stm32f10x.c \
drivers/inverter.c \
drivers/light_led_stm32f10x.c \
drivers/light_led.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f10x.c \
drivers/pwm_mapping.c \
@ -542,7 +538,6 @@ CC3D_SRC = \
drivers/serial_uart.c \
drivers/serial_uart_stm32f10x.c \
drivers/sonar_hcsr04.c \
drivers/sound_beeper_stm32f10x.c \
drivers/system_stm32f10x.c \
drivers/timer.c \
drivers/timer_stm32f10x.c \
@ -559,13 +554,12 @@ STM32F30x_COMMON_SRC += \
drivers/bus_spi.c \
drivers/display_ug2864hsweg01.h \
drivers/gpio_stm32f30x.c \
drivers/light_led_stm32f30x.c \
drivers/light_led.c \
drivers/pwm_mapping.c \
drivers/pwm_output.c \
drivers/pwm_rx.c \
drivers/serial_uart.c \
drivers/serial_uart_stm32f30x.c \
drivers/sound_beeper_stm32f30x.c \
drivers/system_stm32f30x.c \
drivers/timer.c \
drivers/timer_stm32f30x.c

View File

@ -947,6 +947,8 @@ void ADC_AnalogWatchdog3SingleChannelConfig(ADC_TypeDef* ADCx, uint8_t ADC_Chann
*/
void ADC_TempSensorCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
{
(void)(ADCx);
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));
@ -1012,6 +1014,7 @@ void ADC_VrefintCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
*/
void ADC_VbatCmd(ADC_TypeDef* ADCx, FunctionalState NewState)
{
(void)ADCx;
/* Check the parameters */
assert_param(IS_FUNCTIONAL_STATE(NewState));

View File

@ -250,6 +250,7 @@ void HRTIM_SimpleBase_Init(HRTIM_TypeDef* HRTIMx, uint32_t TimerIdx, HRTIM_BaseI
*/
void HRTIM_DeInit(HRTIM_TypeDef* HRTIMx)
{
(void)HRTIMx;
/* Check the parameters */
RCC_APB2PeriphResetCmd(RCC_APB2Periph_HRTIM1, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_HRTIM1, DISABLE);
@ -633,6 +634,7 @@ void HRTIM_SimpleCaptureStart(HRTIM_TypeDef * HRTIMx,
uint32_t TimerIdx,
uint32_t CaptureChannel)
{
(void)CaptureChannel;
/* Enable the timer counter */
__HRTIM_ENABLE(HRTIMx, TimerIdxToTimerId[TimerIdx]);
@ -3211,6 +3213,7 @@ uint32_t HRTIM_WaveformGetOutputState(HRTIM_TypeDef * HRTIMx,
uint32_t TimerIdx,
uint32_t Output)
{
(void)(TimerIdx);
uint32_t output_bit = 0;
uint32_t output_state = HRTIM_OUTPUTSTATE_IDLE;

View File

@ -469,6 +469,7 @@ void SYSCFG_SRAMWRPEnable(uint32_t SYSCFG_SRAMWRP)
*/
FlagStatus SYSCFG_GetFlagStatus(uint32_t SYSCFG_Flag)
{
(void)SYSCFG_Flag;
FlagStatus bitstatus = RESET;
/* Check the parameter */

View File

@ -17,6 +17,10 @@
#pragma once
#ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE
#endif
extern uint16_t acc_1G; // FIXME move into acc_t
typedef struct gyro_s {

View File

@ -66,7 +66,7 @@ bool adxl345Detect(drv_adxl345_config_t *init, acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(ADXL345_ADDRESS, 0x00, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xE5)
return false;
@ -82,14 +82,14 @@ static void adxl345Init(void)
{
if (useFifo) {
uint8_t fifoDepth = 16;
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
i2cWrite(ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_400);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_FIFO_CTL, (fifoDepth & 0x1F) | ADXL345_FIFO_STREAM);
} else {
i2cWrite(ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_POWER_CTL, ADXL345_POWER_MEAS);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_FORMAT, ADXL345_FULL_RANGE | ADXL345_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_BW_RATE, ADXL345_RATE_100);
}
acc_1G = 265; // 3.3V operation // FIXME verify this is supposed to be 265, not 256. Typo?
}
@ -110,7 +110,7 @@ static bool adxl345Read(int16_t *accelData)
do {
i++;
if (!i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_OUT, 8, buf)) {
return false;
}
@ -125,7 +125,7 @@ static bool adxl345Read(int16_t *accelData)
acc_samples = i;
} else {
if (!i2cRead(ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, ADXL345_ADDRESS, ADXL345_DATA_OUT, 6, buf)) {
return false;
}

View File

@ -40,7 +40,7 @@ bool bma280Detect(acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(BMA280_ADDRESS, 0x00, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, 0x00, 1, &sig);
if (!ack || sig != 0xFB)
return false;
@ -51,8 +51,8 @@ bool bma280Detect(acc_t *acc)
static void bma280Init(void)
{
i2cWrite(BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
i2cWrite(BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_RANGE, 0x08); // +-8g range
i2cWrite(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_PMU_BW, 0x0E); // 500Hz BW
acc_1G = 512 * 8;
}
@ -61,7 +61,7 @@ static bool bma280Read(int16_t *accelData)
{
uint8_t buf[6];
if (!i2cRead(BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, BMA280_ADDRESS, BMA280_ACC_X_LSB, 6, buf)) {
return false;
}

View File

@ -63,7 +63,7 @@ bool l3g4200dDetect(gyro_t *gyro)
delay(25);
i2cRead(L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_WHO_AM_I, 1, &deviceid);
if (deviceid != L3G4200D_ID)
return false;
@ -100,12 +100,12 @@ static void l3g4200dInit(uint8_t lpf)
delay(100);
ack = i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
ack = i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG4, L3G4200D_FS_SEL_2000DPS);
if (!ack)
failureMode(FAILURE_ACC_INIT);
delay(5);
i2cWrite(L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
i2cWrite(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_CTRL_REG1, L3G4200D_POWER_ON | mpuLowPassFilter);
}
// Read 3 gyro values into user-provided buffer. No overrun checking is done.
@ -113,7 +113,7 @@ static bool l3g4200dRead(int16_t *gyroADC)
{
uint8_t buf[6];
if (!i2cRead(L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, L3G4200D_ADDRESS, L3G4200D_AUTOINCR | L3G4200D_GYRO_OUT, 6, buf)) {
return false;
}

View File

@ -115,15 +115,15 @@ int32_t accelSummedSamples500Hz[3];
void lsm303dlhcAccInit(void)
{
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG5_A, BOOT);
delay(100);
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG1_A, ODR_1344_HZ | AXES_ENABLE);
delay(10);
i2cWrite(LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
i2cWrite(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, CTRL_REG4_A, FULLSCALE_4G);
delay(100);
@ -135,7 +135,7 @@ static bool lsm303dlhcAccRead(int16_t *gyroADC)
{
uint8_t buf[6];
bool ack = i2cRead(LSM303DLHC_ACCEL_ADDRESS, AUTO_INCREMENT_ENABLE | OUT_X_L_A, 6, buf);
bool ack = i2cRead(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, AUTO_INCREMENT_ENABLE | OUT_X_L_A, 6, buf);
if (!ack) {
return false;
@ -160,7 +160,7 @@ bool lsm303dlhcAccDetect(acc_t *acc)
bool ack;
uint8_t status;
ack = i2cRead(LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_REG_A, 1, &status);
ack = i2cRead(MPU_I2C_INSTANCE, LSM303DLHC_ACCEL_ADDRESS, LSM303DLHC_STATUS_REG_A, 1, &status);
if (!ack)
return false;

View File

@ -28,6 +28,10 @@
#include "accgyro.h"
#include "accgyro_mma845x.h"
#ifndef MMA8452_I2C_INSTANCE
#define MMA8452_I2C_INSTANCE I2CDEV_1
#endif
// MMA8452QT, Standard address 0x1C
// ACC_INT2 routed to PA5
@ -85,7 +89,7 @@ bool mma8452Detect(acc_t *acc)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
ack = i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_WHO_AM_I, 1, &sig);
if (!ack || (sig != MMA8452_DEVICE_SIGNATURE && sig != MMA8451_DEVICE_SIGNATURE))
return false;
@ -101,33 +105,26 @@ static inline void mma8451ConfigureInterrupt(void)
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
// 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_config_t gpio;
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
gpio.pin = Pin_5;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(GPIOA, &gpio);
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_SYSTEM, RESOURCE_I2C);
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
#endif
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH)
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG4, MMA8452_CTRL_REG4_INT_EN_DRDY); // Enable DRDY interrupt (unused by this driver)
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG5, 0); // DRDY routed to INT2
}
static void mma8452Init(void)
{
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);
i2cWrite(MMA8452_ADDRESS, MMA8452_HP_FILTER_CUTOFF, MMA8452_HPF_CUTOFF_LV4);
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG2, MMA8452_CTRL_REG2_MODS_HR | MMA8452_CTRL_REG2_MODS_HR << 3); // High resolution measurement in both sleep and active modes
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG1, 0); // Put device in standby to configure stuff
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_XYZ_DATA_CFG, MMA8452_FS_RANGE_8G);
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_HP_FILTER_CUTOFF, MMA8452_HPF_CUTOFF_LV4);
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG2, MMA8452_CTRL_REG2_MODS_HR | MMA8452_CTRL_REG2_MODS_HR << 3); // High resolution measurement in both sleep and active modes
mma8451ConfigureInterrupt();
i2cWrite(MMA8452_ADDRESS, MMA8452_CTRL_REG1, MMA8452_CTRL_REG1_LNOISE | MMA8452_CTRL_REG1_ACTIVE); // Turn on measurements, low noise at max scale mode, Data Rate 800Hz. LNoise mode makes range +-4G.
i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG1, MMA8452_CTRL_REG1_LNOISE | MMA8452_CTRL_REG1_ACTIVE); // Turn on measurements, low noise at max scale mode, Data Rate 800Hz. LNoise mode makes range +-4G.
acc_1G = 256;
}
@ -136,7 +133,7 @@ static bool mma8452Read(int16_t *accelData)
{
uint8_t buf[6];
if (!i2cRead(MMA8452_ADDRESS, MMA8452_OUT_X_MSB, 6, buf)) {
if (!i2cRead(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_OUT_X_MSB, 6, buf)) {
return false;
}

View File

@ -56,6 +56,10 @@ static volatile bool mpuDataReady;
static bool detectSPISensorsAndUpdateDetectionResult(void);
#endif
#ifndef MPU_I2C_INSTANCE
#define MPU_I2C_INSTANCE I2C_DEVICE
#endif
mpuDetectionResult_t mpuDetectionResult;
mpuConfiguration_t mpuConfiguration;
@ -191,121 +195,61 @@ static void mpu6050FindRevision(void)
}
}
void MPU_DATA_READY_EXTI_Handler(void)
extiCallbackRec_t mpuIntCallbackRec;
void mpuIntExtiHandler(extiCallbackRec_t *cb)
{
if (EXTI_GetITStatus(mpuIntExtiConfig->exti_line) == RESET) {
return;
}
EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line);
UNUSED(cb);
mpuDataReady = true;
#ifdef DEBUG_MPU_DATA_READY_INTERRUPT
// Measure the delta in micro seconds between calls to the interrupt handler
static uint32_t lastCalledAt = 0;
static int32_t callDelta = 0;
uint32_t now = micros();
callDelta = now - lastCalledAt;
//UNUSED(callDelta);
uint32_t callDelta = now - lastCalledAt;
debug[0] = callDelta;
lastCalledAt = now;
#endif
}
void configureMPUDataReadyInterruptHandling(void)
{
#ifdef USE_MPU_DATA_READY_SIGNAL
#ifdef STM32F10X
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
#ifdef STM32F303xC
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
#ifdef STM32F10X
gpioExtiLineConfig(mpuIntExtiConfig->exti_port_source, mpuIntExtiConfig->exti_pin_source);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(mpuIntExtiConfig->exti_port_source, mpuIntExtiConfig->exti_pin_source);
#endif
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = GPIO_ReadInputDataBit(mpuIntExtiConfig->gpioPort, mpuIntExtiConfig->gpioPin);
if (status) {
return;
}
#endif
registerExtiCallbackHandler(mpuIntExtiConfig->exti_irqn, MPU_DATA_READY_EXTI_Handler);
EXTI_ClearITPendingBit(mpuIntExtiConfig->exti_line);
EXTI_InitTypeDef EXTIInit;
EXTIInit.EXTI_Line = mpuIntExtiConfig->exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = mpuIntExtiConfig->exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_MPU_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_MPU_DATA_READY);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
#endif
}
void mpuIntExtiInit(void)
{
gpio_config_t gpio;
static bool mpuExtiInitDone = false;
static bool mpuExtiInitDone = false;
if (mpuExtiInitDone || !mpuIntExtiConfig) {
return;
}
if (mpuExtiInitDone || !mpuIntExtiConfig) {
return;
}
#if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI)
#ifdef STM32F303
if (mpuIntExtiConfig->gpioAHBPeripherals) {
RCC_AHBPeriphClockCmd(mpuIntExtiConfig->gpioAHBPeripherals, ENABLE);
}
#endif
#ifdef STM32F10X
if (mpuIntExtiConfig->gpioAPB2Peripherals) {
RCC_APB2PeriphClockCmd(mpuIntExtiConfig->gpioAPB2Peripherals, ENABLE);
}
IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->io);
#ifdef ENSURE_MPU_DATA_READY_IS_LOW
uint8_t status = IORead(mpuIntIO);
if (status) {
return;
}
#endif
gpio.pin = mpuIntExtiConfig->gpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_IN_FLOATING;
gpioInit(mpuIntExtiConfig->gpioPort, &gpio);
IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
configureMPUDataReadyInterruptHandling();
mpuExtiInitDone = true;
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising);
EXTIEnable(mpuIntIO, true);
#endif
mpuExtiInitDone = true;
}
static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data)
{
bool ack = i2cRead(MPU_ADDRESS, reg, length, data);
bool ack = i2cRead(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, length, data);
return ack;
}
static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data)
{
bool ack = i2cWrite(MPU_ADDRESS, reg, data);
bool ack = i2cWrite(MPU_I2C_INSTANCE, MPU_ADDRESS, reg, data);
return ack;
}

View File

@ -117,11 +117,15 @@
typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data);
typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data);
typedef void(*mpuResetFuncPtr)(void);
typedef struct mpuConfiguration_s {
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
mpuReadRegisterFunc read;
mpuWriteRegisterFunc write;
uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each
mpuReadRegisterFunc read;
mpuWriteRegisterFunc write;
mpuReadRegisterFunc slowread;
mpuWriteRegisterFunc verifywrite;
mpuResetFuncPtr reset;
} mpuConfiguration_t;
extern mpuConfiguration_t mpuConfiguration;

View File

@ -32,9 +32,10 @@
#include "common/maths.h"
#include "system.h"
#include "gpio.h"
#include "io.h"
#include "exti.h"
#include "bus_spi.h"
#include "gyro_sync.h"
#include "sensor.h"
@ -96,9 +97,10 @@ static bool mpuSpi6000InitDone = false;
#define MPU6000_REV_D9 0x59
#define MPU6000_REV_D10 0x5A
#define DISABLE_MPU6000 GPIO_SetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
#define ENABLE_MPU6000 GPIO_ResetBits(MPU6000_CS_GPIO, MPU6000_CS_PIN)
#define DISABLE_MPU6000 IOHi(mpuSpi6000CsPin)
#define ENABLE_MPU6000 IOLo(mpuSpi6000CsPin)
static IO_t mpuSpi6000CsPin = IO_NONE;
bool mpu6000WriteRegister(uint8_t reg, uint8_t data)
{
@ -154,6 +156,12 @@ bool mpu6000SpiDetect(void)
uint8_t in;
uint8_t attemptsRemaining = 5;
#ifdef MPU6000_CS_PIN
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
#endif
IOInit(mpuSpi6000CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_0_5625MHZ_CLOCK_DIVIDER);
mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET);

View File

@ -26,7 +26,7 @@
#include "system.h"
#include "exti.h"
#include "gpio.h"
#include "io.h"
#include "bus_spi.h"
#include "sensor.h"
@ -35,8 +35,10 @@
#include "accgyro_mpu6500.h"
#include "accgyro_spi_mpu6500.h"
#define DISABLE_MPU6500 GPIO_SetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN)
#define ENABLE_MPU6500 GPIO_ResetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN)
#define DISABLE_MPU6500 IOHi(mpuSpi6500CsPin)
#define ENABLE_MPU6500 IOLo(mpuSpi6500CsPin)
static IO_t mpuSpi6500CsPin = IO_NONE;
extern uint16_t acc_1G;
@ -68,34 +70,16 @@ static void mpu6500SpiInit(void)
return;
}
#ifdef STM32F303xC
RCC_AHBPeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE);
mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN));
IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = MPU6500_CS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(MPU6500_CS_GPIO, &GPIO_InitStructure);
#if defined(STM32F4)
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_SLOW_CLOCK);
#else
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_STANDARD_CLOCK);
#endif
#ifdef STM32F10X
RCC_APB2PeriphClockCmd(MPU6500_CS_GPIO_CLK_PERIPHERAL, ENABLE);
gpio_config_t gpio;
// CS as output
gpio.mode = Mode_Out_PP;
gpio.pin = MPU6500_CS_PIN;
gpio.speed = Speed_50MHz;
gpioInit(MPU6500_CS_GPIO, &gpio);
#endif
GPIO_SetBits(MPU6500_CS_GPIO, MPU6500_CS_PIN);
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER);
hardwareInitialised = true;
}

View File

@ -29,3 +29,7 @@ typedef struct baro_s {
baroOpFuncPtr get_up;
baroCalculateFuncPtr calculate;
} baro_t;
#ifndef BARO_I2C_INSTANCE
#define BARO_I2C_INSTANCE I2C_DEVICE
#endif

View File

@ -28,24 +28,31 @@
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#include "exti.h"
#include "io.h"
#include "barometer_bmp085.h"
#ifdef BARO
#if defined(BARO_EOC_GPIO)
#if defined(BARO_EOC_GPIO)
static IO_t eocIO;
static bool isConversionComplete = false;
static bool isEOCConnected = true;
// EXTI14 for BMP085 End of Conversion Interrupt
void BMP085_EOC_EXTI_Handler(void) {
if (EXTI_GetITStatus(EXTI_Line14) == SET) {
EXTI_ClearITPendingBit(EXTI_Line14);
isConversionComplete = true;
}
void bmp085_extiHandler(extiCallbackRec_t* cb)
{
UNUSED(cb);
isConversionComplete = true;
}
#endif
static extiCallbackRec_t bmp085_extiCallbackRec;
bool bmp085TestEOCConnected(const bmp085Config_t *config);
# endif
typedef struct {
int16_t ac1;
@ -123,28 +130,29 @@ static int32_t bmp085_get_temperature(uint32_t ut);
static int32_t bmp085_get_pressure(uint32_t up);
STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature);
static IO_t xclrIO;
#ifdef BARO_XCLR_PIN
#define BMP085_OFF digitalLo(BARO_XCLR_GPIO, BARO_XCLR_PIN);
#define BMP085_ON digitalHi(BARO_XCLR_GPIO, BARO_XCLR_PIN);
#define BMP085_OFF IOLo(xclrIO);
#define BMP085_ON IOHi(xclrIO);
#else
#define BMP085_OFF
#define BMP085_ON
#endif
void bmp085InitXCLRGpio(const bmp085Config_t *config) {
gpio_config_t gpio;
RCC_APB2PeriphClockCmd(config->gpioAPB2Peripherals, ENABLE);
gpio.pin = config->xclrGpioPin;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_Out_PP;
gpioInit(config->xclrGpioPort, &gpio);
void bmp085InitXclrIO(const bmp085Config_t *config)
{
if (!xclrIO && config && config->xclrIO) {
xclrIO = IOGetByTag(config->xclrIO);
IOInit(xclrIO, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
}
}
void bmp085Disable(const bmp085Config_t *config)
{
bmp085InitXCLRGpio(config);
bmp085InitXclrIO(config);
BMP085_OFF;
}
@ -152,39 +160,25 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
{
uint8_t data;
bool ack;
#if defined(BARO_EOC_GPIO)
IO_t eocIO = IO_NONE;
#endif
if (bmp085InitDone)
return true;
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
if (config) {
EXTI_InitTypeDef EXTI_InitStructure;
NVIC_InitTypeDef NVIC_InitStructure;
gpio_config_t gpio;
bmp085InitXCLRGpio(config);
gpio.pin = config->eocGpioPin;
gpio.mode = Mode_IPD;
gpioInit(config->eocGpioPort, &gpio);
BMP085_ON;
registerExtiCallbackHandler(EXTI15_10_IRQn, BMP085_EOC_EXTI_Handler);
bmp085InitXclrIO(config);
BMP085_ON; // enable baro
#if defined(BARO_EOC_GPIO) && defined(USE_EXTI)
if (config && config->eocIO) {
eocIO = IOGetByTag(config->eocIO);
// EXTI interrupt for barometer EOC
gpioExtiLineConfig(GPIO_PortSourceGPIOC, GPIO_PinSource14);
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
EXTI_InitStructure.EXTI_Mode = EXTI_Mode_Interrupt;
EXTI_InitStructure.EXTI_Trigger = EXTI_Trigger_Rising;
EXTI_InitStructure.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTI_InitStructure);
// Enable and set EXTI10-15 Interrupt to the lowest priority
NVIC_InitStructure.NVIC_IRQChannel = EXTI15_10_IRQn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_BARO_EXT);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_BARO_EXT);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
IOInit(eocIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
IOConfigGPIO(eocIO, Mode_IN_FLOATING);
EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler);
EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, EXTI_Trigger_Rising);
EXTIEnable(eocIO, true);
}
#else
UNUSED(config);
@ -192,13 +186,13 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
delay(20); // datasheet says 10ms, we'll be careful and do 20.
ack = i2cRead(BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */
if (ack) {
bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID);
bmp085.oversampling_setting = 3;
if (bmp085.chip_id == BMP085_CHIP_ID) { /* get bitslice */
i2cRead(BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_VERSION_REG, 1, &data); /* read Version reg */
bmp085.ml_version = BMP085_GET_BITSLICE(data, BMP085_ML_VERSION); /* get ML Version */
bmp085.al_version = BMP085_GET_BITSLICE(data, BMP085_AL_VERSION); /* get AL Version */
bmp085_get_cal_param(); /* readout bmp085 calibparam structure */
@ -218,13 +212,8 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
}
#if defined(BARO_EOC_GPIO)
EXTI_InitTypeDef EXTI_InitStructure;
EXTI_StructInit(&EXTI_InitStructure);
EXTI_InitStructure.EXTI_Line = EXTI_Line14;
EXTI_InitStructure.EXTI_LineCmd = DISABLE;
EXTI_Init(&EXTI_InitStructure);
unregisterExtiCallbackHandler(EXTI15_10_IRQn, BMP085_EOC_EXTI_Handler);
if (eocIO)
EXTIRelease(eocIO);
#endif
BMP085_OFF;
@ -290,7 +279,7 @@ static void bmp085_start_ut(void)
#if defined(BARO_EOC_GPIO)
isConversionComplete = false;
#endif
i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, BMP085_T_MEASURE);
}
static void bmp085_get_ut(void)
@ -304,7 +293,7 @@ static void bmp085_get_ut(void)
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 2, data);
bmp085_ut = (data[0] << 8) | data[1];
}
@ -318,7 +307,7 @@ static void bmp085_start_up(void)
isConversionComplete = false;
#endif
i2cWrite(BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
i2cWrite(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CTRL_MEAS_REG, ctrl_reg_data);
}
/** read out up for pressure conversion
@ -336,7 +325,7 @@ static void bmp085_get_up(void)
}
#endif
i2cRead(BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_ADC_OUT_MSB_REG, 3, data);
bmp085_up = (((uint32_t) data[0] << 16) | ((uint32_t) data[1] << 8) | (uint32_t) data[2])
>> (8 - bmp085.oversampling_setting);
}
@ -356,7 +345,7 @@ STATIC_UNIT_TESTED void bmp085_calculate(int32_t *pressure, int32_t *temperature
static void bmp085_get_cal_param(void)
{
uint8_t data[22];
i2cRead(BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_PROM_START__ADDR, BMP085_PROM_DATA__LEN, data);
/*parameters AC1-AC6*/
bmp085.cal_param.ac1 = (data[0] << 8) | data[1];
@ -379,16 +368,18 @@ static void bmp085_get_cal_param(void)
#if defined(BARO_EOC_GPIO)
bool bmp085TestEOCConnected(const bmp085Config_t *config)
{
if (!bmp085InitDone) {
UNUSED(config);
if (!bmp085InitDone && eocIO) {
bmp085_start_ut();
delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure
// conversion should have finished now so check if EOC is high
uint8_t status = GPIO_ReadInputDataBit(config->eocGpioPort, config->eocGpioPin);
uint8_t status = IORead(eocIO);
if (status) {
return true;
}
}
}
return false; // assume EOC is not connected
}
#endif

View File

@ -18,11 +18,8 @@
#pragma once
typedef struct bmp085Config_s {
uint32_t gpioAPB2Peripherals;
uint16_t xclrGpioPin;
GPIO_TypeDef *xclrGpioPort;
uint16_t eocGpioPin;
GPIO_TypeDef *eocGpioPort;
ioTag_t xclrIO;
ioTag_t eocIO;
} bmp085Config_t;
bool bmp085Detect(const bmp085Config_t *config, baro_t *baro);

View File

@ -83,14 +83,14 @@ bool bmp280Detect(baro_t *baro)
// set oversampling + power mode (forced), and start sampling
bmp280WriteRegister(BMP280_CTRL_MEAS_REG, BMP280_MODE);
#else
i2cRead(BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CHIP_ID_REG, 1, &bmp280_chip_id); /* read Chip Id */
if (bmp280_chip_id != BMP280_DEFAULT_CHIP_ID)
return false;
// read calibration
i2cRead(BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_TEMPERATURE_CALIB_DIG_T1_LSB_REG, 24, (uint8_t *)&bmp280_cal);
// set oversampling + power mode (forced), and start sampling
i2cWrite(BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
#endif
bmp280InitDone = true;
@ -129,7 +129,7 @@ static void bmp280_start_up(void)
{
// start measurement
// set oversampling + power mode (forced), and start sampling
i2cWrite(BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
i2cWrite(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_CTRL_MEAS_REG, BMP280_MODE);
}
static void bmp280_get_up(void)
@ -137,7 +137,7 @@ static void bmp280_get_up(void)
uint8_t data[BMP280_DATA_FRAME_SIZE];
// read data from sensor
i2cRead(BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
i2cRead(BARO_I2C_INSTANCE, BMP280_I2C_ADDR, BMP280_PRESSURE_MSB_REG, BMP280_DATA_FRAME_SIZE, data);
bmp280_up = (int32_t)((((uint32_t)(data[0])) << 12) | (((uint32_t)(data[1])) << 4) | ((uint32_t)data[2] >> 4));
bmp280_ut = (int32_t)((((uint32_t)(data[3])) << 12) | (((uint32_t)(data[4])) << 4) | ((uint32_t)data[5] >> 4));
}

View File

@ -67,7 +67,7 @@ bool ms5611Detect(baro_t *baro)
delay(10); // No idea how long the chip takes to power-up, but let's make it 10ms
ack = i2cRead(MS5611_ADDR, CMD_PROM_RD, 1, &sig);
ack = i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD, 1, &sig);
if (!ack)
return false;
@ -93,14 +93,14 @@ bool ms5611Detect(baro_t *baro)
static void ms5611_reset(void)
{
i2cWrite(MS5611_ADDR, CMD_RESET, 1);
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_RESET, 1);
delayMicroseconds(2800);
}
static uint16_t ms5611_prom(int8_t coef_num)
{
uint8_t rxbuf[2] = { 0, 0 };
i2cRead(MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_PROM_RD + coef_num * 2, 2, rxbuf); // send PROM READ command
return rxbuf[0] << 8 | rxbuf[1];
}
@ -137,13 +137,13 @@ STATIC_UNIT_TESTED int8_t ms5611_crc(uint16_t *prom)
static uint32_t ms5611_read_adc(void)
{
uint8_t rxbuf[3];
i2cRead(MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
i2cRead(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_READ, 3, rxbuf); // read ADC
return (rxbuf[0] << 16) | (rxbuf[1] << 8) | rxbuf[2];
}
static void ms5611_start_ut(void)
{
i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D2 + ms5611_osr, 1); // D2 (temperature) conversion start!
}
static void ms5611_get_ut(void)
@ -153,7 +153,7 @@ static void ms5611_get_ut(void)
static void ms5611_start_up(void)
{
i2cWrite(MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
i2cWrite(BARO_I2C_INSTANCE, MS5611_ADDR, CMD_ADC_CONV + CMD_ADC_D1 + ms5611_osr, 1); // D1 (pressure) conversion start!
}
static void ms5611_get_up(void)

View File

@ -21,14 +21,48 @@
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_DEFAULT_TIMEOUT I2C_SHORT_TIMEOUT
#include "drivers/io.h"
#include "drivers/rcc.h"
#ifndef I2C_DEVICE
#define I2C_DEVICE I2CINVALID
#endif
typedef enum I2CDevice {
I2CDEV_1,
I2CINVALID = -1,
I2CDEV_1 = 0,
I2CDEV_2,
I2CDEV_MAX = I2CDEV_2,
I2CDEV_3,
I2CDEV_MAX = I2CDEV_3,
} I2CDevice;
void i2cInit(I2CDevice index);
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data);
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data);
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf);
typedef struct i2cDevice_s {
I2C_TypeDef *dev;
ioTag_t scl;
ioTag_t sda;
rccPeriphTag_t rcc;
bool overClock;
#if !defined(STM32F303xC)
uint8_t ev_irq;
uint8_t er_irq;
#endif
} i2cDevice_t;
typedef struct i2cState_s {
volatile bool error;
volatile bool busy;
volatile uint8_t addr;
volatile uint8_t reg;
volatile uint8_t bytes;
volatile uint8_t writing;
volatile uint8_t reading;
volatile uint8_t* write_p;
volatile uint8_t* read_p;
} i2cState_t;
void i2cInit(I2CDevice device);
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data);
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data);
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf);
uint16_t i2cGetErrorCounter(void);

View File

@ -21,246 +21,246 @@
#include <platform.h>
#include "build_config.h"
#include "gpio.h"
#include "bus_i2c.h"
#include "drivers/io.h"
// Software I2C driver, using same pins as hardware I2C, with hw i2c module disabled.
// Can be configured for I2C2 pinout (SCL: PB10, SDA: PB11) or I2C1 pinout (SCL: PB6, SDA: PB7)
#ifdef SOFT_I2C
#ifdef SOFT_I2C_PB1011
#define SCL_H GPIOB->BSRR = Pin_10
#define SCL_L GPIOB->BRR = Pin_10
static IO_t scl;
static IO_t sda;
static volatile uint16_t i2cErrorCount = 0;
#define SDA_H GPIOB->BSRR = Pin_11
#define SDA_L GPIOB->BRR = Pin_11
#define SCL_H IOHi(scl)
#define SCL_L IOLo(scl)
#define SCL_read (GPIOB->IDR & Pin_10)
#define SDA_read (GPIOB->IDR & Pin_11)
#define I2C_PINS (Pin_10 | Pin_11)
#define I2C_GPIO GPIOB
#endif
#define SDA_H IOHi(sda)
#define SDA_L IOLo(sda)
#ifdef SOFT_I2C_PB67
#define SCL_H GPIOB->BSRR = Pin_6
#define SCL_L GPIOB->BRR = Pin_6
#define SCL_read IORead(scl)
#define SDA_read IORead(sda)
#define SDA_H GPIOB->BSRR = Pin_7
#define SDA_L GPIOB->BRR = Pin_7
#define SCL_read (GPIOB->IDR & Pin_6)
#define SDA_read (GPIOB->IDR & Pin_7)
#define I2C_PINS (Pin_6 | Pin_7)
#define I2C_GPIO GPIOB
#endif
#ifndef SCL_H
#error Need to define SOFT_I2C_PB1011 or SOFT_I2C_PB67 (see board.h)
#if !defined(SOFT_I2C_SCL) || !defined(SOFT_I2C_SDA)
#error "Must define the software i2c pins (SOFT_I2C_SCL and SOFT_I2C_SDA) in target.h"
#endif
static void I2C_delay(void)
{
volatile int i = 7;
while (i) {
i--;
}
volatile int i = 7;
while (i) {
i--;
}
}
static bool I2C_Start(void)
{
SDA_H;
SCL_H;
I2C_delay();
if (!SDA_read) {
return false;
}
SDA_L;
I2C_delay();
if (SDA_read) {
return false;
SDA_H;
SCL_H;
I2C_delay();
if (!SDA_read) {
return false;
}
SDA_L;
I2C_delay();
return true;
SDA_L;
I2C_delay();
if (SDA_read) {
return false;
}
SDA_L;
I2C_delay();
return true;
}
static void I2C_Stop(void)
{
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SDA_H;
I2C_delay();
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SDA_H;
I2C_delay();
}
static void I2C_Ack(void)
{
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
SCL_L;
I2C_delay();
SDA_L;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
}
static void I2C_NoAck(void)
{
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
SCL_L;
I2C_delay();
}
static bool I2C_WaitAck(void)
{
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
SCL_L;
return false;
}
SCL_L;
return true;
SCL_L;
I2C_delay();
SDA_H;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
SCL_L;
return false;
}
SCL_L;
return true;
}
static void I2C_SendByte(uint8_t byte)
{
uint8_t i = 8;
while (i--) {
SCL_L;
I2C_delay();
if (byte & 0x80) {
SDA_H;
} else {
SDA_L;
}
byte <<= 1;
I2C_delay();
SCL_H;
I2C_delay();
}
SCL_L;
uint8_t i = 8;
while (i--) {
SCL_L;
I2C_delay();
if (byte & 0x80) {
SDA_H;
}
else {
SDA_L;
}
byte <<= 1;
I2C_delay();
SCL_H;
I2C_delay();
}
SCL_L;
}
static uint8_t I2C_ReceiveByte(void)
{
uint8_t i = 8;
uint8_t byte = 0;
uint8_t i = 8;
uint8_t byte = 0;
SDA_H;
while (i--) {
byte <<= 1;
SCL_L;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
byte |= 0x01;
}
}
SCL_L;
return byte;
}
void i2cInit(I2C_TypeDef * I2C)
{
gpio_config_t gpio;
gpio.pin = I2C_PINS;
gpio.speed = Speed_2MHz;
gpio.mode = Mode_Out_OD;
gpioInit(I2C_GPIO, &gpio);
}
bool i2cWriteBuffer(uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
{
int i;
if (!I2C_Start()) {
return false;
SDA_H;
while (i--) {
byte <<= 1;
SCL_L;
I2C_delay();
SCL_H;
I2C_delay();
if (SDA_read) {
byte |= 0x01;
}
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
for (i = 0; i < len; i++) {
I2C_SendByte(data[i]);
if (!I2C_WaitAck()) {
I2C_Stop();
return false;
}
}
I2C_Stop();
return true;
SCL_L;
return byte;
}
bool i2cWrite(uint8_t addr, uint8_t reg, uint8_t data)
void i2cInit(I2CDevice device)
{
if (!I2C_Start()) {
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_SendByte(data);
I2C_WaitAck();
I2C_Stop();
return true;
UNUSED(device);
scl = IOGetByTag(IO_TAG(SOFT_I2C_SCL));
sda = IOGetByTag(IO_TAG(SOFT_I2C_SDA));
IOConfigGPIO(scl, IOCFG_OUT_OD);
IOConfigGPIO(sda, IOCFG_OUT_OD);
}
bool i2cRead(uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data)
{
if (!I2C_Start()) {
return false;
UNUSED(device);
int i;
if (!I2C_Start()) {
i2cErrorCount++;
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_Start();
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
while (len) {
*buf = I2C_ReceiveByte();
if (len == 1) {
I2C_NoAck();
} else {
I2C_Ack();
}
buf++;
len--;
}
I2C_Stop();
return true;
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
for (i = 0; i < len; i++) {
I2C_SendByte(data[i]);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
}
I2C_Stop();
return true;
}
bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data)
{
UNUSED(device);
if (!I2C_Start()) {
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_SendByte(data);
I2C_WaitAck();
I2C_Stop();
return true;
}
bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf)
{
UNUSED(device);
if (!I2C_Start()) {
return false;
}
I2C_SendByte(addr << 1 | I2C_Direction_Transmitter);
if (!I2C_WaitAck()) {
I2C_Stop();
i2cErrorCount++;
return false;
}
I2C_SendByte(reg);
I2C_WaitAck();
I2C_Start();
I2C_SendByte(addr << 1 | I2C_Direction_Receiver);
I2C_WaitAck();
while (len) {
*buf = I2C_ReceiveByte();
if (len == 1) {
I2C_NoAck();
}
else {
I2C_Ack();
}
buf++;
len--;
}
I2C_Stop();
return true;
}
uint16_t i2cGetErrorCounter(void)
{
// TODO maybe fix this, but since this is test code, doesn't matter.
return 0;
return i2cErrorCount;
}
#endif

View File

@ -23,16 +23,22 @@
#include "build_config.h"
#include "gpio.h"
#include "io.h"
#include "system.h"
#include "bus_i2c.h"
#include "nvic.h"
#include "io_impl.h"
#include "rcc.h"
#ifndef SOFT_I2C
#define CLOCKSPEED 800000 // i2c clockspeed 400kHz default (conform specs), 800kHz and 1200kHz (Betaflight default)
static void i2c_er_handler(I2CDevice device);
static void i2c_ev_handler(I2CDevice device);
static void i2cUnstick(IO_t scl, IO_t sda);
// I2C2
// SCL PB10
// SDA PB11
@ -40,329 +46,372 @@
// SCL PB6
// SDA PB7
static void i2c_er_handler(void);
static void i2c_ev_handler(void);
static void i2cUnstick(void);
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
typedef struct i2cDevice_s {
I2C_TypeDef *dev;
GPIO_TypeDef *gpio;
uint16_t scl;
uint16_t sda;
uint8_t ev_irq;
uint8_t er_irq;
uint32_t peripheral;
} i2cDevice_t;
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PB11
#endif
static const i2cDevice_t i2cHardwareMap[] = {
{ I2C1, GPIOB, Pin_6, Pin_7, I2C1_EV_IRQn, I2C1_ER_IRQn, RCC_APB1Periph_I2C1 },
{ I2C2, GPIOB, Pin_10, Pin_11, I2C2_EV_IRQn, I2C2_ER_IRQn, RCC_APB1Periph_I2C2 },
static i2cDevice_t i2cHardwareMap[] = {
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false, .ev_irq = I2C1_EV_IRQn, .er_irq = I2C1_ER_IRQn },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false, .ev_irq = I2C2_EV_IRQn, .er_irq = I2C2_ER_IRQn },
#ifdef STM32F4
{ .dev = I2C3, .scl = IO_TAG(I2C3_SCL), .sda = IO_TAG(I2C3_SDA), .rcc = RCC_APB1(I2C3), .overClock = false, .ev_irq = I2C3_EV_IRQn, .er_irq = I2C3_ER_IRQn }
#endif
};
// Copy of peripheral address for IRQ routines
static I2C_TypeDef *I2Cx = NULL;
// Copy of device index for reinit, etc purposes
static I2CDevice I2Cx_index;
void I2C1_ER_IRQHandler(void)
{
i2c_er_handler();
}
void I2C1_EV_IRQHandler(void)
{
i2c_ev_handler();
}
void I2C2_ER_IRQHandler(void)
{
i2c_er_handler();
}
void I2C2_EV_IRQHandler(void)
{
i2c_ev_handler();
}
//#define I2C_DEFAULT_TIMEOUT 30000
static volatile uint16_t i2cErrorCount = 0;
static volatile bool error = false;
static volatile bool busy;
static i2cState_t i2cState[] = {
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 },
{ false, false, 0, 0, 0, 0, 0, 0, 0 }
};
static volatile uint8_t addr;
static volatile uint8_t reg;
static volatile uint8_t bytes;
static volatile uint8_t writing;
static volatile uint8_t reading;
static volatile uint8_t* write_p;
static volatile uint8_t* read_p;
void I2C1_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_1);
}
static bool i2cHandleHardwareFailure(void)
void I2C1_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_1);
}
void I2C2_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_2);
}
void I2C2_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_2);
}
#ifdef STM32F4
void I2C3_ER_IRQHandler(void) {
i2c_er_handler(I2CDEV_3);
}
void I2C3_EV_IRQHandler(void) {
i2c_ev_handler(I2CDEV_3);
}
#endif
static bool i2cHandleHardwareFailure(I2CDevice device)
{
i2cErrorCount++;
// reinit peripheral + clock out garbage
i2cInit(I2Cx_index);
i2cInit(device);
return false;
}
bool i2cWriteBuffer(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data)
{
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
addr = addr_ << 1;
reg = reg_;
writing = 1;
reading = 0;
write_p = data;
read_p = data;
bytes = len_;
busy = 1;
error = false;
if (!I2Cx)
if (device == I2CINVALID)
return false;
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
if (timeout == 0) {
return i2cHandleHardwareFailure();
}
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
}
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
}
timeout = I2C_DEFAULT_TIMEOUT;
while (busy && --timeout > 0) { ; }
if (timeout == 0) {
return i2cHandleHardwareFailure();
}
return !error;
}
bool i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWriteBuffer(addr_, reg_, 1, &data);
}
bool i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
addr = addr_ << 1;
reg = reg_;
writing = 0;
reading = 1;
read_p = buf;
write_p = buf;
bytes = len;
busy = 1;
error = false;
if (!I2Cx)
return false;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
state->addr = addr_ << 1;
state->reg = reg_;
state->writing = 1;
state->reading = 0;
state->write_p = data;
state->read_p = data;
state->bytes = len_;
state->busy = 1;
state->error = false;
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
if (!(I2Cx->CR1 & 0x0100)) { // ensure sending a start
while (I2Cx->CR1 & 0x0200 && --timeout > 0) { ; } // wait for any stop to finish sending
if (!(I2Cx->CR1 & I2C_CR1_START)) { // ensure sending a start
while (I2Cx->CR1 & I2C_CR1_STOP && --timeout > 0) {; } // wait for any stop to finish sending
if (timeout == 0)
return i2cHandleHardwareFailure();
return i2cHandleHardwareFailure(device);
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
}
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
}
timeout = I2C_DEFAULT_TIMEOUT;
while (busy && --timeout > 0) { ; }
while (state->busy && --timeout > 0) {; }
if (timeout == 0)
return i2cHandleHardwareFailure();
return i2cHandleHardwareFailure(device);
return !error;
return !(state->error);
}
static void i2c_er_handler(void)
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data)
{
// Read the I2Cx status register
uint32_t SR1Register = I2Cx->SR1;
return i2cWriteBuffer(device, addr_, reg_, 1, &data);
}
if (SR1Register & 0x0F00) { // an error
error = true;
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
if (device == I2CINVALID)
return false;
uint32_t timeout = I2C_DEFAULT_TIMEOUT;
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
state->addr = addr_ << 1;
state->reg = reg_;
state->writing = 0;
state->reading = 1;
state->read_p = buf;
state->write_p = buf;
state->bytes = len;
state->busy = 1;
state->error = false;
if (!(I2Cx->CR2 & I2C_IT_EVT)) { // if we are restarting the driver
if (!(I2Cx->CR1 & I2C_CR1_START)) { // ensure sending a start
while (I2Cx->CR1 & I2C_CR1_STOP && --timeout > 0) {; } // wait for any stop to finish sending
if (timeout == 0)
return i2cHandleHardwareFailure(device);
I2C_GenerateSTART(I2Cx, ENABLE); // send the start for the new job
}
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, ENABLE); // allow the interrupts to fire off again
}
timeout = I2C_DEFAULT_TIMEOUT;
while (state->busy && --timeout > 0) {; }
if (timeout == 0)
return i2cHandleHardwareFailure(device);
return !(state->error);
}
static void i2c_er_handler(I2CDevice device) {
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
// Read the I2C1 status register
volatile uint32_t SR1Register = I2Cx->SR1;
if (SR1Register & 0x0F00) // an error
state->error = true;
// If AF, BERR or ARLO, abandon the current job and commence new if there are jobs
if (SR1Register & 0x0700) {
(void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
if (!(SR1Register & 0x0200) && !(I2Cx->CR1 & 0x0200)) { // if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & 0x0100) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
// TODO - busy waiting in highest priority IRQ. Maybe only set flag and handle it from main loop
while (I2Cx->CR1 & 0x0100) { ; } // wait for any start to finish sending
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
while (I2Cx->CR1 & 0x0200) { ; } // wait for stop to finish sending
i2cInit(I2Cx_index); // reset and configure the hardware
} else {
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
(void)I2Cx->SR2; // read second status register to clear ADDR if it is set (note that BTF will not be set after a NACK)
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable the RXNE/TXE interrupt - prevent the ISR tailchaining onto the ER (hopefully)
if (!(SR1Register & I2C_SR1_ARLO) && !(I2Cx->CR1 & I2C_CR1_STOP)) { // if we dont have an ARLO error, ensure sending of a stop
if (I2Cx->CR1 & I2C_CR1_START) { // We are currently trying to send a start, this is very bad as start, stop will hang the peripheral
while (I2Cx->CR1 & I2C_CR1_START) {; } // wait for any start to finish sending
I2C_GenerateSTOP(I2Cx, ENABLE); // send stop to finalise bus transaction
while (I2Cx->CR1 & I2C_CR1_STOP) {; } // wait for stop to finish sending
i2cInit(device); // reset and configure the hardware
}
else {
I2C_GenerateSTOP(I2Cx, ENABLE); // stop to free up the bus
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
}
}
}
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
busy = 0;
I2Cx->SR1 &= ~0x0F00; // reset all the error bits to clear the interrupt
state->busy = 0;
}
void i2c_ev_handler(void)
{
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
static int8_t index; // index is signed -1 == send the subaddress
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
void i2c_ev_handler(I2CDevice device) {
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
i2cState_t *state;
state = &(i2cState[device]);
static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition
static int8_t index; // index is signed -1 == send the subaddress
uint8_t SReg_1 = I2Cx->SR1; // read the status register here
if (SReg_1 & 0x0001) { // we just sent a start - EV5 in ref manual
I2Cx->CR1 &= ~0x0800; // reset the POS bit so ACK/NACK applied to the current byte
I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on
index = 0; // reset the index
if (reading && (subaddress_sent || 0xFF == reg)) { // we have sent the subaddr
subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
if (bytes == 2)
I2Cx->CR1 |= 0x0800; // set the POS bit so NACK applied to the final byte in the two byte read
I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Receiver); // send the address and set hardware mode
} else { // direction is Tx, or we havent sent the sub and rep start
I2C_Send7bitAddress(I2Cx, addr, I2C_Direction_Transmitter); // send the address and set hardware mode
if (reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
index = -1; // send a subaddress
if (SReg_1 & I2C_SR1_SB) { // we just sent a start - EV5 in ref manual
I2Cx->CR1 &= ~I2C_CR1_POS; // reset the POS bit so ACK/NACK applied to the current byte
I2C_AcknowledgeConfig(I2Cx, ENABLE); // make sure ACK is on
index = 0; // reset the index
if (state->reading && (subaddress_sent || 0xFF == state->reg)) { // we have sent the subaddr
subaddress_sent = 1; // make sure this is set in case of no subaddress, so following code runs correctly
if (state->bytes == 2)
I2Cx->CR1 |= I2C_CR1_POS; // set the POS bit so NACK applied to the final byte in the two byte read
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Receiver); // send the address and set hardware mode
}
} else if (SReg_1 & 0x0002) { // we just sent the address - EV6 in ref manual
else { // direction is Tx, or we havent sent the sub and rep start
I2C_Send7bitAddress(I2Cx, state->addr, I2C_Direction_Transmitter); // send the address and set hardware mode
if (state->reg != 0xFF) // 0xFF as subaddress means it will be ignored, in Tx or Rx mode
index = -1; // send a subaddress
}
}
else if (SReg_1 & I2C_SR1_ADDR) { // we just sent the address - EV6 in ref manual
// Read SR1,2 to clear ADDR
__DMB(); // memory fence to control hardware
if (bytes == 1 && reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
__DMB(); // memory fence to control hardware
if (state->bytes == 1 && state->reading && subaddress_sent) { // we are receiving 1 byte - EV6_3
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
__DMB();
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
(void)I2Cx->SR2; // clear ADDR after ACK is turned off
I2C_GenerateSTOP(I2Cx, ENABLE); // program the stop
final_stop = 1;
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // allow us to have an EV7
} else { // EV6 and EV6_1
}
else { // EV6 and EV6_1
(void)I2Cx->SR2; // clear the ADDR here
__DMB();
if (bytes == 2 && reading && subaddress_sent) { // rx 2 bytes - EV6_1
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
} else if (bytes == 3 && reading && subaddress_sent) // rx 3 bytes
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
else // receiving greater than three bytes, sending subaddress, or transmitting
if (state->bytes == 2 && state->reading && subaddress_sent) { // rx 2 bytes - EV6_1
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to fill
}
else if (state->bytes == 3 && state->reading && subaddress_sent) // rx 3 bytes
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // make sure RXNE disabled so we get a BTF in two bytes time
else // receiving greater than three bytes, sending subaddress, or transmitting
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE);
}
} else if (SReg_1 & 0x004) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
}
else if (SReg_1 & I2C_SR1_BTF) { // Byte transfer finished - EV7_2, EV7_3 or EV8_2
final_stop = 1;
if (reading && subaddress_sent) { // EV7_2, EV7_3
if (bytes > 2) { // EV7_2
if (state->reading && subaddress_sent) { // EV7_2, EV7_3
if (state->bytes > 2) { // EV7_2
I2C_AcknowledgeConfig(I2Cx, DISABLE); // turn off ACK
read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N-2
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
final_stop = 1; // required to fix hardware
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
I2C_ITConfig(I2Cx, I2C_IT_BUF, ENABLE); // enable TXE to allow the final EV7
} else { // EV7_3
}
else { // EV7_3
if (final_stop)
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
else
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
read_p[index++] = (uint8_t)I2Cx->DR; // read data N
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N - 1
state->read_p[index++] = (uint8_t)I2Cx->DR; // read data N
index++; // to show job completed
}
} else { // EV8_2, which may be due to a subaddress sent or a write completion
if (subaddress_sent || (writing)) {
}
else { // EV8_2, which may be due to a subaddress sent or a write completion
if (subaddress_sent || (state->writing)) {
if (final_stop)
I2C_GenerateSTOP(I2Cx, ENABLE); // program the Stop
else
I2C_GenerateSTART(I2Cx, ENABLE); // program a rep start
index++; // to show that the job is complete
} else { // We need to send a subaddress
}
else { // We need to send a subaddress
I2C_GenerateSTART(I2Cx, ENABLE); // program the repeated Start
subaddress_sent = 1; // this is set back to zero upon completion of the current task
}
}
// TODO - busy waiting in ISR
// we must wait for the start to clear, otherwise we get constant BTF
while (I2Cx->CR1 & 0x0100) { ; }
} else if (SReg_1 & 0x0040) { // Byte received - EV7
read_p[index++] = (uint8_t)I2Cx->DR;
if (bytes == (index + 3))
while (I2Cx->CR1 & 0x0100) {; }
}
else if (SReg_1 & I2C_SR1_RXNE) { // Byte received - EV7
state->read_p[index++] = (uint8_t)I2Cx->DR;
if (state->bytes == (index + 3))
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush so we can get an EV7_2
if (bytes == index) // We have completed a final EV7
if (state->bytes == index) // We have completed a final EV7
index++; // to show job is complete
} else if (SReg_1 & 0x0080) { // Byte transmitted EV8 / EV8_1
}
else if (SReg_1 & I2C_SR1_TXE) { // Byte transmitted EV8 / EV8_1
if (index != -1) { // we dont have a subaddress to send
I2Cx->DR = write_p[index++];
if (bytes == index) // we have sent all the data
I2Cx->DR = state->write_p[index++];
if (state->bytes == index) // we have sent all the data
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
} else {
}
else {
index++;
I2Cx->DR = reg; // send the subaddress
if (reading || !bytes) // if receiving or sending 0 bytes, flush now
I2Cx->DR = state->reg; // send the subaddress
if (state->reading || !(state->bytes)) // if receiving or sending 0 bytes, flush now
I2C_ITConfig(I2Cx, I2C_IT_BUF, DISABLE); // disable TXE to allow the buffer to flush
}
}
if (index == bytes + 1) { // we have completed the current job
if (index == state->bytes + 1) { // we have completed the current job
subaddress_sent = 0; // reset this here
if (final_stop) // If there is a final stop and no more jobs, bus is inactive, disable interrupts to prevent BTF
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts while bus inactive
busy = 0;
state->busy = 0;
}
}
void i2cInit(I2CDevice index)
void i2cInit(I2CDevice device)
{
if (device == I2CINVALID)
return;
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
NVIC_InitTypeDef nvic;
I2C_InitTypeDef i2c;
I2C_InitTypeDef i2cInit;
if (index > I2CDEV_MAX)
index = I2CDEV_MAX;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
IOInit(scl, OWNER_SYSTEM, RESOURCE_I2C);
IOInit(sda, OWNER_SYSTEM, RESOURCE_I2C);
// Turn on peripheral clock, save device and index
I2Cx = i2cHardwareMap[index].dev;
I2Cx_index = index;
RCC_APB1PeriphClockCmd(i2cHardwareMap[index].peripheral, ENABLE);
// Enable RCC
RCC_ClockCmd(i2c->rcc, ENABLE);
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
i2cUnstick(scl, sda);
// Init pins
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C);
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_I2C);
#else
IOConfigGPIO(scl, IOCFG_AF_OD);
IOConfigGPIO(sda, IOCFG_AF_OD);
#endif
I2C_DeInit(i2c->dev);
I2C_StructInit(&i2cInit);
I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2cInit.I2C_Mode = I2C_Mode_I2C;
i2cInit.I2C_DutyCycle = I2C_DutyCycle_2;
i2cInit.I2C_OwnAddress1 = 0;
i2cInit.I2C_Ack = I2C_Ack_Enable;
i2cInit.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
// diable I2C interrrupts first to avoid ER handler triggering
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE);
// clock out stuff to make sure slaves arent stuck
// This will also configure GPIO as AF_OD at the end
i2cUnstick();
// Init I2C peripheral
I2C_DeInit(I2Cx);
I2C_StructInit(&i2c);
I2C_ITConfig(I2Cx, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request
i2c.I2C_Mode = I2C_Mode_I2C;
i2c.I2C_DutyCycle = I2C_DutyCycle_2;
i2c.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
// Overclocking i2c, test results
// Default speed, conform specs is 400000 (400 kHz)
// 2.0* : 800kHz - worked without errors
// 3.0* : 1200kHz - worked without errors
// 3.5* : 1400kHz - failed, hangup, bootpin recovery needed
// 4.0* : 1600kHz - failed, hangup, bootpin recovery needed
i2c.I2C_ClockSpeed = CLOCKSPEED;
I2C_Cmd(I2Cx, ENABLE);
I2C_Init(I2Cx, &i2c);
if (i2c->overClock) {
i2cInit.I2C_ClockSpeed = 800000; // 800khz Maximum speed tested on various boards without issues
}
else {
i2cInit.I2C_ClockSpeed = 400000; // 400khz Operation according specs
}
I2C_Cmd(i2c->dev, ENABLE);
I2C_Init(i2c->dev, &i2cInit);
// I2C ER Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].er_irq;
nvic.NVIC_IRQChannel = i2c->er_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER);
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_ER);
nvic.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&nvic);
// I2C EV Interrupt
nvic.NVIC_IRQChannel = i2cHardwareMap[index].ev_irq;
nvic.NVIC_IRQChannel = i2c->ev_irq;
nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_EV);
nvic.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_I2C_EV);
NVIC_Init(&nvic);
@ -373,54 +422,39 @@ uint16_t i2cGetErrorCounter(void)
return i2cErrorCount;
}
static void i2cUnstick(void)
static void i2cUnstick(IO_t scl, IO_t sda)
{
GPIO_TypeDef *gpio;
gpio_config_t cfg;
uint16_t scl, sda;
int i;
int timeout = 100;
// prepare pins
gpio = i2cHardwareMap[I2Cx_index].gpio;
scl = i2cHardwareMap[I2Cx_index].scl;
sda = i2cHardwareMap[I2Cx_index].sda;
IOHi(scl);
IOHi(sda);
digitalHi(gpio, scl | sda);
cfg.pin = scl | sda;
cfg.speed = Speed_2MHz;
cfg.mode = Mode_Out_OD;
gpioInit(gpio, &cfg);
IOConfigGPIO(scl, IOCFG_OUT_OD);
IOConfigGPIO(sda, IOCFG_OUT_OD);
for (i = 0; i < 8; i++) {
// Wait for any clock stretching to finish
while (!digitalIn(gpio, scl))
while (!IORead(scl) && timeout) {
delayMicroseconds(10);
timeout--;
}
// Pull low
digitalLo(gpio, scl); // Set bus low
IOLo(scl); // Set bus low
delayMicroseconds(10);
// Release high again
digitalHi(gpio, scl); // Set bus high
IOHi(scl); // Set bus high
delayMicroseconds(10);
}
// Generate a start then stop condition
// SCL PB10
// SDA PB11
digitalLo(gpio, sda); // Set bus data low
IOLo(sda); // Set bus data low
delayMicroseconds(10);
digitalLo(gpio, scl); // Set bus scl low
IOLo(scl); // Set bus scl low
delayMicroseconds(10);
digitalHi(gpio, scl); // Set bus scl high
IOHi(scl); // Set bus scl high
delayMicroseconds(10);
digitalHi(gpio, sda); // Set bus sda high
// Init pins
cfg.pin = scl | sda;
cfg.speed = Speed_2MHz;
cfg.mode = Mode_AF_OD;
gpioInit(gpio, &cfg);
IOHi(sda); // Set bus sda high
}
#endif

View File

@ -25,303 +25,229 @@
#include "gpio.h"
#include "system.h"
#include "drivers/io_impl.h"
#include "bus_i2c.h"
#ifndef SOFT_I2C
#define I2C1_SCL_GPIO GPIOB
#define I2C1_SCL_GPIO_AF GPIO_AF_4
#define I2C1_SCL_PIN GPIO_Pin_6
#define I2C1_SCL_PIN_SOURCE GPIO_PinSource6
#define I2C1_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOB
#define I2C1_SDA_GPIO GPIOB
#define I2C1_SDA_GPIO_AF GPIO_AF_4
#define I2C1_SDA_PIN GPIO_Pin_7
#define I2C1_SDA_PIN_SOURCE GPIO_PinSource7
#define I2C1_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOB
#if !defined(I2C2_SCL_GPIO)
#define I2C2_SCL_GPIO GPIOF
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_6
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource6
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOF
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C_SHORT_TIMEOUT ((uint32_t)0x1000)
#define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT))
#define I2C_GPIO_AF GPIO_AF_4
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
#ifndef I2C1_SDA
#define I2C1_SDA PB7
#endif
#ifndef I2C2_SCL
#define I2C2_SCL PF4
#endif
#ifndef I2C2_SDA
#define I2C2_SDA PA10
#endif
static uint32_t i2cTimeout;
static volatile uint16_t i2c1ErrorCount = 0;
static volatile uint16_t i2c2ErrorCount = 0;
static volatile uint16_t i2cErrorCount = 0;
//static volatile uint16_t i2c2ErrorCount = 0;
static I2C_TypeDef *I2Cx = NULL;
static i2cDevice_t i2cHardwareMap[] = {
{ .dev = I2C1, .scl = IO_TAG(I2C1_SCL), .sda = IO_TAG(I2C1_SDA), .rcc = RCC_APB1(I2C1), .overClock = false },
{ .dev = I2C2, .scl = IO_TAG(I2C2_SCL), .sda = IO_TAG(I2C2_SDA), .rcc = RCC_APB1(I2C2), .overClock = false }
};
///////////////////////////////////////////////////////////////////////////////
// I2C TimeoutUserCallback
///////////////////////////////////////////////////////////////////////////////
uint32_t i2cTimeoutUserCallback(I2C_TypeDef *I2Cx)
uint32_t i2cTimeoutUserCallback(void)
{
if (I2Cx == I2C1) {
i2c1ErrorCount++;
} else {
i2c2ErrorCount++;
}
return false;
i2cErrorCount++;
return false;
}
void i2cInitPort(I2C_TypeDef *I2Cx)
void i2cInit(I2CDevice device)
{
GPIO_InitTypeDef GPIO_InitStructure;
I2C_InitTypeDef I2C_InitStructure;
i2cDevice_t *i2c;
i2c = &(i2cHardwareMap[device]);
if (I2Cx == I2C1) {
RCC_AHBPeriphClockCmd(I2C1_SCL_CLK_SOURCE | I2C1_SDA_CLK_SOURCE, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C1, ENABLE);
RCC_I2CCLKConfig(RCC_I2C1CLK_SYSCLK);
I2C_TypeDef *I2Cx;
I2Cx = i2c->dev;
IO_t scl = IOGetByTag(i2c->scl);
IO_t sda = IOGetByTag(i2c->sda);
RCC_ClockCmd(i2c->rcc, ENABLE);
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
IOConfigGPIOAF(scl, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
IOConfigGPIOAF(sda, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_OD, GPIO_PuPd_NOPULL), GPIO_AF_4);
GPIO_PinAFConfig(I2C1_SCL_GPIO, I2C1_SCL_PIN_SOURCE, I2C1_SCL_GPIO_AF);
GPIO_PinAFConfig(I2C1_SDA_GPIO, I2C1_SDA_PIN_SOURCE, I2C1_SDA_GPIO_AF);
I2C_InitTypeDef i2cInit = {
.I2C_Mode = I2C_Mode_I2C,
.I2C_AnalogFilter = I2C_AnalogFilter_Enable,
.I2C_DigitalFilter = 0x00,
.I2C_OwnAddress1 = 0x00,
.I2C_Ack = I2C_Ack_Enable,
.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit,
.I2C_Timing = 0x00E0257A, // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Rise 100, Fall 10.
//.I2C_Timing = 0x8000050B;
};
if (i2c->overClock) {
i2cInit.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
}
I2C_Init(I2Cx, &i2cInit);
GPIO_StructInit(&GPIO_InitStructure);
I2C_StructInit(&I2C_InitStructure);
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_InitStructure.GPIO_Pin = I2C1_SCL_PIN;
GPIO_Init(I2C1_SCL_GPIO, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = I2C1_SDA_PIN;
GPIO_Init(I2C1_SDA_GPIO, &GPIO_InitStructure);
I2C_StructInit(&I2C_InitStructure);
I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
I2C_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
I2C_InitStructure.I2C_DigitalFilter = 0x00;
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
//I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 100, Hold 10.
//I2C_InitStructure.I2C_Timing = 0x0070123D; // 800 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 50, Hold 5.
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
I2C_Init(I2C1, &I2C_InitStructure);
I2C_Cmd(I2C1, ENABLE);
}
if (I2Cx == I2C2) {
RCC_AHBPeriphClockCmd(I2C2_SCL_CLK_SOURCE | I2C2_SDA_CLK_SOURCE, ENABLE);
RCC_APB1PeriphClockCmd(RCC_APB1Periph_I2C2, ENABLE);
RCC_I2CCLKConfig(RCC_I2C2CLK_SYSCLK);
//i2cUnstick(I2Cx); // Clock out stuff to make sure slaves arent stuck
GPIO_PinAFConfig(I2C2_SCL_GPIO, I2C2_SCL_PIN_SOURCE, I2C2_SCL_GPIO_AF);
GPIO_PinAFConfig(I2C2_SDA_GPIO, I2C2_SDA_PIN_SOURCE, I2C2_SDA_GPIO_AF);
GPIO_StructInit(&GPIO_InitStructure);
I2C_StructInit(&I2C_InitStructure);
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_InitStructure.GPIO_Pin = I2C2_SCL_PIN;
GPIO_Init(I2C2_SCL_GPIO, &GPIO_InitStructure);
GPIO_InitStructure.GPIO_Pin = I2C2_SDA_PIN;
GPIO_Init(I2C2_SDA_GPIO, &GPIO_InitStructure);
I2C_StructInit(&I2C_InitStructure);
I2C_InitStructure.I2C_Mode = I2C_Mode_I2C;
I2C_InitStructure.I2C_AnalogFilter = I2C_AnalogFilter_Enable;
I2C_InitStructure.I2C_DigitalFilter = 0x00;
I2C_InitStructure.I2C_OwnAddress1 = 0x00;
I2C_InitStructure.I2C_Ack = I2C_Ack_Enable;
I2C_InitStructure.I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit;
//I2C_InitStructure.I2C_Timing = 0x00E0257A; // 400 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 100, Hold 10.
//I2C_InitStructure.I2C_Timing = 0x0070123D; // 800 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 50, Hold 5.
I2C_InitStructure.I2C_Timing = 0x00500E30; // 1000 Khz, 72Mhz Clock, Analog Filter Delay ON, Setup 40, Hold 4.
I2C_Init(I2C2, &I2C_InitStructure);
I2C_Cmd(I2C2, ENABLE);
}
}
void i2cInit(I2CDevice index)
{
if (index == I2CDEV_1) {
I2Cx = I2C1;
} else {
I2Cx = I2C2;
}
i2cInitPort(I2Cx);
I2C_Cmd(I2Cx, ENABLE);
}
uint16_t i2cGetErrorCounter(void)
{
if (I2Cx == I2C1) {
return i2c1ErrorCount;
}
return i2c2ErrorCount;
return i2cErrorCount;
}
bool i2cWrite(uint8_t addr_, uint8_t reg, uint8_t data)
bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data)
{
addr_ <<= 1;
addr_ <<= 1;
/* Test on BUSY Flag */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_Reload_Mode, I2C_Generate_Start_Write);
/* Wait until TXIS flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg);
/* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg);
/* Wait until TCR flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
{
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until TCR flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TCR) == RESET)
{
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_AutoEnd_Mode, I2C_No_StartStop);
/* Wait until TXIS flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Write data to TXDR */
I2C_SendData(I2Cx, data);
/* Write data to TXDR */
I2C_SendData(I2Cx, data);
/* Wait until STOPF flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until STOPF flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Clear STOPF flag */
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
/* Clear STOPF flag */
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
return true;
return true;
}
bool i2cRead(uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* buf)
{
addr_ <<= 1;
addr_ <<= 1;
/* Test on BUSY Flag */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
I2C_TypeDef *I2Cx;
I2Cx = i2cHardwareMap[device].dev;
/* Test on BUSY Flag */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, 1, I2C_SoftEnd_Mode, I2C_Generate_Start_Write);
/* Wait until TXIS flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until TXIS flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TXIS) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg);
/* Send Register address */
I2C_SendData(I2Cx, (uint8_t) reg);
/* Wait until TC flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until TC flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_TC) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
/* Configure slave address, nbytes, reload, end mode and start or stop generation */
I2C_TransferHandling(I2Cx, addr_, len, I2C_AutoEnd_Mode, I2C_Generate_Start_Read);
/* Wait until all data are received */
while (len) {
/* Wait until RXNE flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until all data are received */
while (len) {
/* Wait until RXNE flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_RXNE) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Read data from RXDR */
*buf = I2C_ReceiveData(I2Cx);
/* Point to the next location where the byte read will be saved */
buf++;
/* Read data from RXDR */
*buf = I2C_ReceiveData(I2Cx);
/* Point to the next location where the byte read will be saved */
buf++;
/* Decrement the read bytes counter */
len--;
}
/* Decrement the read bytes counter */
len--;
}
/* Wait until STOPF flag is set */
i2cTimeout = I2C_DEFAULT_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback(I2Cx);
}
}
/* Wait until STOPF flag is set */
i2cTimeout = I2C_LONG_TIMEOUT;
while (I2C_GetFlagStatus(I2Cx, I2C_ISR_STOPF) == RESET) {
if ((i2cTimeout--) == 0) {
return i2cTimeoutUserCallback();
}
}
/* Clear STOPF flag */
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
/* Clear STOPF flag */
I2C_ClearFlag(I2Cx, I2C_ICR_STOPCF);
/* If all operations OK */
return true;
/* If all operations OK */
return true;
}
#endif

View File

@ -22,457 +22,219 @@
#include "build_config.h"
#include "gpio.h"
#include "bus_spi.h"
#include "io.h"
#include "io_impl.h"
#include "rcc.h"
/* for F30x processors */
#if defined(STM32F303xC)
#ifndef GPIO_AF_SPI1
#define GPIO_AF_SPI1 GPIO_AF_5
#endif
#ifndef GPIO_AF_SPI2
#define GPIO_AF_SPI2 GPIO_AF_5
#endif
#ifndef GPIO_AF_SPI3
#define GPIO_AF_SPI3 GPIO_AF_6
#endif
#endif
#ifndef SPI1_SCK_PIN
#define SPI1_NSS_PIN PA4
#define SPI1_SCK_PIN PA5
#define SPI1_MISO_PIN PA6
#define SPI1_MOSI_PIN PA7
#endif
#ifndef SPI2_SCK_PIN
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#endif
#ifndef SPI3_SCK_PIN
#define SPI3_NSS_PIN PA15
#define SPI3_SCK_PIN PB3
#define SPI3_MISO_PIN PB4
#define SPI3_MOSI_PIN PB5
#endif
#ifndef SPI1_NSS_PIN
#define SPI1_NSS_PIN NONE
#endif
#ifndef SPI2_NSS_PIN
#define SPI2_NSS_PIN NONE
#endif
#ifndef SPI3_NSS_PIN
#define SPI3_NSS_PIN NONE
#endif
static spiDevice_t spiHardwareMap[] = {
#if defined(STM32F10X)
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = 0, false },
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = 0, false },
#else
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF_SPI1, false },
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF_SPI2, false },
#endif
#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF_SPI3, false }
#endif
};
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
{
if (instance == SPI1)
return SPIDEV_1;
if (instance == SPI2)
return SPIDEV_2;
if (instance == SPI3)
return SPIDEV_3;
return SPIINVALID;
}
void spiInitDevice(SPIDevice device)
{
SPI_InitTypeDef spiInit;
spiDevice_t *spi = &(spiHardwareMap[device]);
#ifdef SDCARD_SPI_INSTANCE
if (spi->dev == SDCARD_SPI_INSTANCE)
spi->sdcard = true;
#endif
// Enable SPI clock
RCC_ClockCmd(spi->rcc, ENABLE);
RCC_ResetCmd(spi->rcc, ENABLE);
IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI);
IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI);
IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI);
#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
if (spi->sdcard) {
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af);
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af);
}
else {
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af);
}
IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af);
if (spi->nss)
IOConfigGPIOAF(IOGetByTag(spi->nss), SPI_IO_CS_CFG, spi->af);
#endif
#if defined(STM32F10X)
IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_CFG);
IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_CFG);
IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_CFG);
if (spi->nss)
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
#endif
// Init SPI hardware
SPI_I2S_DeInit(spi->dev);
spiInit.SPI_Mode = SPI_Mode_Master;
spiInit.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spiInit.SPI_DataSize = SPI_DataSize_8b;
spiInit.SPI_NSS = SPI_NSS_Soft;
spiInit.SPI_FirstBit = SPI_FirstBit_MSB;
spiInit.SPI_CRCPolynomial = 7;
spiInit.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
if (spi->sdcard) {
spiInit.SPI_CPOL = SPI_CPOL_Low;
spiInit.SPI_CPHA = SPI_CPHA_1Edge;
}
else {
spiInit.SPI_CPOL = SPI_CPOL_High;
spiInit.SPI_CPHA = SPI_CPHA_2Edge;
}
#ifdef STM32F303xC
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
#endif
SPI_Init(spi->dev, &spiInit);
SPI_Cmd(spi->dev, ENABLE);
if (spi->nss)
IOHi(IOGetByTag(spi->nss));
}
bool spiInit(SPIDevice device)
{
switch (device)
{
case SPIINVALID:
return false;
case SPIDEV_1:
#ifdef USE_SPI_DEVICE_1
#ifndef SPI1_GPIO
#define SPI1_GPIO GPIOA
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOA
#define SPI1_NSS_PIN GPIO_Pin_4
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource4
#define SPI1_SCK_PIN GPIO_Pin_5
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource5
#define SPI1_MISO_PIN GPIO_Pin_6
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource6
#define SPI1_MOSI_PIN GPIO_Pin_7
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource7
#endif
void initSpi1(void)
{
// Specific to the STM32F103
// SPI1 Driver
// PA4 14 SPI1_NSS
// PA5 15 SPI1_SCK
// PA6 16 SPI1_MISO
// PA7 17 SPI1_MOSI
SPI_InitTypeDef spi;
// Enable SPI1 clock
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SPI1, ENABLE);
RCC_APB2PeriphResetCmd(RCC_APB2Periph_SPI1, ENABLE);
#ifdef STM32F303xC
GPIO_InitTypeDef GPIO_InitStructure;
RCC_AHBPeriphClockCmd(SPI1_GPIO_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI1_GPIO, SPI1_MOSI_PIN_SOURCE, GPIO_AF_5);
#ifdef SPI1_NSS_PIN_SOURCE
GPIO_PinAFConfig(SPI1_GPIO, SPI1_NSS_PIN_SOURCE, GPIO_AF_5);
#endif
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
#ifdef USE_SDCARD_SPI1
// Configure pins and pullups for SD-card use
// No pull-up needed since we drive this pin as an output
GPIO_InitStructure.GPIO_Pin = SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
GPIO_InitStructure.GPIO_Pin = SPI1_MISO_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
// In clock-low mode, STM32 manual says we should enable a pulldown to match
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
spiInitDevice(device);
return true;
#else
// General-purpose pin config
GPIO_InitStructure.GPIO_Pin = SPI1_SCK_PIN | SPI1_MISO_PIN | SPI1_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
break;
#endif
#ifdef SPI1_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI1_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI1_GPIO, &GPIO_InitStructure);
#endif
#endif
#ifdef STM32F10X
gpio_config_t gpio;
// MOSI + SCK as output
gpio.mode = Mode_AF_PP;
gpio.pin = SPI1_MOSI_PIN | SPI1_SCK_PIN;
gpio.speed = Speed_50MHz;
gpioInit(SPI1_GPIO, &gpio);
// MISO as input
gpio.pin = SPI1_MISO_PIN;
gpio.mode = Mode_IN_FLOATING;
gpioInit(SPI1_GPIO, &gpio);
#ifdef SPI1_NSS_PIN
// NSS as gpio slave select
gpio.pin = SPI1_NSS_PIN;
gpio.mode = Mode_Out_PP;
gpioInit(SPI1_GPIO, &gpio);
#endif
#endif
// Init SPI1 hardware
SPI_I2S_DeInit(SPI1);
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi.SPI_DataSize = SPI_DataSize_8b;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
#ifdef USE_SDCARD_SPI1
spi.SPI_CPOL = SPI_CPOL_Low;
spi.SPI_CPHA = SPI_CPHA_1Edge;
#else
spi.SPI_CPOL = SPI_CPOL_High;
spi.SPI_CPHA = SPI_CPHA_2Edge;
#endif
#ifdef STM32F303xC
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(SPI1, SPI_RxFIFOThreshold_QF);
#endif
SPI_Init(SPI1, &spi);
SPI_Cmd(SPI1, ENABLE);
#ifdef SPI1_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI1_GPIO, SPI1_NSS_PIN);
#endif
}
#endif
case SPIDEV_2:
#ifdef USE_SPI_DEVICE_2
#ifndef SPI2_GPIO
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN GPIO_Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN GPIO_Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN GPIO_Pin_14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
#define SPI2_MOSI_PIN GPIO_Pin_15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#endif
void initSpi2(void)
{
// Specific to the STM32F103 / STM32F303 (AF5)
// SPI2 Driver
// PB12 25 SPI2_NSS
// PB13 26 SPI2_SCK
// PB14 27 SPI2_MISO
// PB15 28 SPI2_MOSI
SPI_InitTypeDef spi;
// Enable SPI2 clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI2, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI2, ENABLE);
#ifdef STM32F303xC
GPIO_InitTypeDef GPIO_InitStructure;
RCC_AHBPeriphClockCmd(SPI2_GPIO_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_SCK_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MISO_PIN_SOURCE, GPIO_AF_5);
GPIO_PinAFConfig(SPI2_GPIO, SPI2_MOSI_PIN_SOURCE, GPIO_AF_5);
#ifdef SPI2_NSS_PIN_SOURCE
GPIO_PinAFConfig(SPI2_GPIO, SPI2_NSS_PIN_SOURCE, GPIO_AF_5);
#endif
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
#ifdef USE_SDCARD_SPI2
// Configure pins and pullups for SD-card use
// No pull-up needed since we drive this pin as an output
GPIO_InitStructure.GPIO_Pin = SPI2_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
GPIO_InitStructure.GPIO_Pin = SPI2_MISO_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
// In clock-low mode, STM32 manual says we should enable a pulldown to match
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
spiInitDevice(device);
return true;
#else
// General-purpose pin config
GPIO_InitStructure.GPIO_Pin = SPI2_SCK_PIN | SPI2_MISO_PIN | SPI2_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
break;
#endif
#ifdef SPI2_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI2_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI2_GPIO, &GPIO_InitStructure);
#endif
#endif
#ifdef STM32F10X
gpio_config_t gpio;
// MOSI + SCK as output
gpio.mode = Mode_AF_PP;
gpio.pin = SPI2_SCK_PIN | SPI2_MOSI_PIN;
gpio.speed = Speed_50MHz;
gpioInit(SPI2_GPIO, &gpio);
// MISO as input
gpio.pin = SPI2_MISO_PIN;
gpio.mode = Mode_IN_FLOATING;
gpioInit(SPI2_GPIO, &gpio);
#ifdef SPI2_NSS_PIN
// NSS as gpio slave select
gpio.pin = SPI2_NSS_PIN;
gpio.mode = Mode_Out_PP;
gpioInit(SPI2_GPIO, &gpio);
#endif
#endif
// Init SPI2 hardware
SPI_I2S_DeInit(SPI2);
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi.SPI_DataSize = SPI_DataSize_8b;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
#ifdef USE_SDCARD_SPI2
spi.SPI_CPOL = SPI_CPOL_Low;
spi.SPI_CPHA = SPI_CPHA_1Edge;
case SPIDEV_3:
#if defined(USE_SPI_DEVICE_3) && (defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE))
spiInitDevice(device);
return true;
#else
spi.SPI_CPOL = SPI_CPOL_High;
spi.SPI_CPHA = SPI_CPHA_2Edge;
break;
#endif
#ifdef STM32F303xC
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(SPI2, SPI_RxFIFOThreshold_QF);
#endif
SPI_Init(SPI2, &spi);
SPI_Cmd(SPI2, ENABLE);
#ifdef SPI2_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI2_GPIO, SPI2_NSS_PIN);
#endif
}
#endif
#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
#ifndef SPI3_GPIO
#define SPI3_GPIO GPIOB
#define SPI3_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI3_NSS_GPIO GPIOA
#define SPI3_NSS_PERIPHERAL RCC_AHBPeriph_GPIOA
#define SPI3_NSS_PIN GPIO_Pin_15
#define SPI3_NSS_PIN_SOURCE GPIO_PinSource15
#define SPI3_SCK_PIN GPIO_Pin_3
#define SPI3_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI3_MISO_PIN GPIO_Pin_4
#define SPI3_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI3_MOSI_PIN GPIO_Pin_5
#define SPI3_MOSI_PIN_SOURCE GPIO_PinSource5
#endif
void initSpi3(void)
{
// Specific to the STM32F303 (AF6)
// SPI3 Driver
// PA15 38 SPI3_NSS
// PB3 39 SPI3_SCK
// PB4 40 SPI3_MISO
// PB5 41 SPI3_MOSI
SPI_InitTypeDef spi;
// Enable SPI3 clock
RCC_APB1PeriphClockCmd(RCC_APB1Periph_SPI3, ENABLE);
RCC_APB1PeriphResetCmd(RCC_APB1Periph_SPI3, ENABLE);
GPIO_InitTypeDef GPIO_InitStructure;
RCC_AHBPeriphClockCmd(SPI3_GPIO_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_SCK_PIN_SOURCE, GPIO_AF_6);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MISO_PIN_SOURCE, GPIO_AF_6);
GPIO_PinAFConfig(SPI3_GPIO, SPI3_MOSI_PIN_SOURCE, GPIO_AF_6);
#ifdef SPI2_NSS_PIN_SOURCE
RCC_AHBPeriphClockCmd(SPI3_NNS_PERIPHERAL, ENABLE);
GPIO_PinAFConfig(SPI3_NNS_GPIO, SPI3_NSS_PIN_SOURCE, GPIO_AF_6);
#endif
// Init pins
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
#ifdef USE_SDCARD_SPI3
// Configure pins and pullups for SD-card use
// No pull-up needed since we drive this pin as an output
GPIO_InitStructure.GPIO_Pin = SPI3_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
// Prevent MISO pin from floating when SDCard is deselected (high-Z) or not connected
GPIO_InitStructure.GPIO_Pin = SPI3_MISO_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
// In clock-low mode, STM32 manual says we should enable a pulldown to match
GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_DOWN;
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
#else
// General-purpose pin config
GPIO_InitStructure.GPIO_Pin = SPI3_SCK_PIN | SPI3_MISO_PIN | SPI3_MOSI_PIN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI3_GPIO, &GPIO_InitStructure);
#endif
#ifdef SPI3_NSS_PIN
GPIO_InitStructure.GPIO_Pin = SPI3_NSS_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
GPIO_Init(SPI3_NSS_GPIO, &GPIO_InitStructure);
#endif
// Init SPI hardware
SPI_I2S_DeInit(SPI3);
spi.SPI_Mode = SPI_Mode_Master;
spi.SPI_Direction = SPI_Direction_2Lines_FullDuplex;
spi.SPI_DataSize = SPI_DataSize_8b;
spi.SPI_NSS = SPI_NSS_Soft;
spi.SPI_FirstBit = SPI_FirstBit_MSB;
spi.SPI_CRCPolynomial = 7;
spi.SPI_BaudRatePrescaler = SPI_BaudRatePrescaler_8;
#ifdef USE_SDCARD_SPI3
spi.SPI_CPOL = SPI_CPOL_Low;
spi.SPI_CPHA = SPI_CPHA_1Edge;
#else
spi.SPI_CPOL = SPI_CPOL_High;
spi.SPI_CPHA = SPI_CPHA_2Edge;
#endif
// Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(SPI3, SPI_RxFIFOThreshold_QF);
SPI_Init(SPI3, &spi);
SPI_Cmd(SPI3, ENABLE);
#ifdef SPI3_NSS_PIN
// Drive NSS high to disable connected SPI device.
GPIO_SetBits(SPI3_NSS_GPIO, SPI3_NSS_PIN);
#endif
}
#endif
bool spiInit(SPI_TypeDef *instance)
{
#if (!(defined(USE_SPI_DEVICE_1) && defined(USE_SPI_DEVICE_2) && defined(USE_SPI_DEVICE_3)))
UNUSED(instance);
#endif
#ifdef USE_SPI_DEVICE_1
if (instance == SPI1) {
initSpi1();
return true;
}
#endif
#ifdef USE_SPI_DEVICE_2
if (instance == SPI2) {
initSpi2();
return true;
}
#endif
#if defined(USE_SPI_DEVICE_3) && defined(STM32F303xC)
if (instance == SPI3) {
initSpi3();
return true;
}
#endif
return false;
}
return false;
}
uint32_t spiTimeoutUserCallback(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device == SPIINVALID)
return -1;
spiHardwareMap[device].errorCount++;
return spiHardwareMap[device].errorCount;
}
// return uint8_t value or -1 when failure
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
{
uint16_t spiTimeout = 1000;
uint16_t spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
break;
}
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET)
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
#ifdef STM32F303xC
SPI_SendData8(instance, data);
SPI_SendData8(instance, data);
#else
SPI_I2S_SendData(instance, data);
#endif
#ifdef STM32F10X
SPI_I2S_SendData(instance, data);
#endif
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET){
if ((spiTimeout--) == 0)
break;
}
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET)
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
#ifdef STM32F303xC
return ((uint8_t)SPI_ReceiveData8(instance));
#endif
#ifdef STM32F10X
return ((uint8_t)SPI_I2S_ReceiveData(instance));
return ((uint8_t)SPI_ReceiveData8(instance));
#else
return ((uint8_t)SPI_I2S_ReceiveData(instance));
#endif
}
@ -482,48 +244,47 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t data)
bool spiIsBusBusy(SPI_TypeDef *instance)
{
#ifdef STM32F303xC
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
#endif
#ifdef STM32F10X
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
return SPI_GetTransmissionFIFOStatus(instance) != SPI_TransmissionFIFOStatus_Empty || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
#else
return SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET || SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_BSY) == SET;
#endif
}
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
{
uint16_t spiTimeout = 1000;
uint16_t spiTimeout = 1000;
uint8_t b;
instance->DR;
while (len--) {
b = in ? *(in++) : 0xFF;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
break;
}
uint8_t b;
instance->DR;
while (len--) {
b = in ? *(in++) : 0xFF;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_TXE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
}
#ifdef STM32F303xC
SPI_SendData8(instance, b);
//SPI_I2S_SendData16(instance, b);
SPI_SendData8(instance, b);
//SPI_I2S_SendData16(instance, b);
#else
SPI_I2S_SendData(instance, b);
#endif
#ifdef STM32F10X
SPI_I2S_SendData(instance, b);
#endif
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
if ((spiTimeout--) == 0)
break;
}
spiTimeout = 1000;
while (SPI_I2S_GetFlagStatus(instance, SPI_I2S_FLAG_RXNE) == RESET) {
if ((spiTimeout--) == 0)
return spiTimeoutUserCallback(instance);
}
#ifdef STM32F303xC
b = SPI_ReceiveData8(instance);
//b = SPI_I2S_ReceiveData16(instance);
b = SPI_ReceiveData8(instance);
//b = SPI_I2S_ReceiveData16(instance);
#else
b = SPI_I2S_ReceiveData(instance);
#endif
#ifdef STM32F10X
b = SPI_I2S_ReceiveData(instance);
#endif
if (out)
*(out++) = b;
}
if (out)
*(out++) = b;
}
return true;
}
@ -531,55 +292,70 @@ void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
{
#define BR_CLEAR_MASK 0xFFC7
uint16_t tempRegister;
uint16_t tempRegister;
SPI_Cmd(instance, DISABLE);
SPI_Cmd(instance, DISABLE);
tempRegister = instance->CR1;
tempRegister = instance->CR1;
switch (divisor) {
case 2:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_2;
break;
switch (divisor) {
case 2:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_2;
break;
case 4:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_4;
break;
case 4:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_4;
break;
case 8:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_8;
break;
case 8:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_8;
break;
case 16:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_16;
break;
case 16:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_16;
break;
case 32:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_32;
break;
case 32:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_32;
break;
case 64:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_64;
break;
case 64:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_64;
break;
case 128:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_128;
break;
case 128:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_128;
break;
case 256:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_256;
break;
}
case 256:
tempRegister &= BR_CLEAR_MASK;
tempRegister |= SPI_BaudRatePrescaler_256;
break;
}
instance->CR1 = tempRegister;
instance->CR1 = tempRegister;
SPI_Cmd(instance, ENABLE);
SPI_Cmd(instance, ENABLE);
}
uint16_t spiGetErrorCounter(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device == SPIINVALID)
return 0;
return spiHardwareMap[device].errorCount;
}
void spiResetErrorCounter(SPI_TypeDef *instance)
{
SPIDevice device = spiDeviceByInstance(instance);
if (device != SPIINVALID)
spiHardwareMap[device].errorCount = 0;
}

View File

@ -22,9 +22,64 @@
#define SPI_18MHZ_CLOCK_DIVIDER 2
#define SPI_9MHZ_CLOCK_DIVIDER 4
bool spiInit(SPI_TypeDef *instance);
#include <stdint.h>
#include "io.h"
#include "rcc.h"
#if defined(STM32F40_41xxx) || defined (STM32F411xE) || defined(STM32F303xC)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_DOWN)
#define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL)
#elif defined(STM32F10X)
#define SPI_IO_AF_CFG IO_CONFIG(GPIO_Mode_AF_OD, GPIO_Speed_50MHz)
#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz)
#else
#error "Unknown processor"
#endif
#if defined(STM32F40_41xxx) || defined (STM32F411xE)
#define SPI_SLOW_CLOCK 128 //00.65625 MHz
#define SPI_STANDARD_CLOCK 8 //11.50000 MHz
#define SPI_FAST_CLOCK 4 //21.00000 MHz
#define SPI_ULTRAFAST_CLOCK 2 //42.00000 MHz
#else
#define SPI_SLOW_CLOCK 128 //00.56250 MHz
#define SPI_STANDARD_CLOCK 4 //09.00000 MHz
#define SPI_FAST_CLOCK 2 //18.00000 MHz
#define SPI_ULTRAFAST_CLOCK 2 //18.00000 MHz
#endif
typedef enum SPIDevice {
SPIINVALID = -1,
SPIDEV_1 = 0,
SPIDEV_2,
SPIDEV_3,
SPIDEV_MAX = SPIDEV_3,
} SPIDevice;
typedef struct SPIDevice_s {
SPI_TypeDef *dev;
ioTag_t nss;
ioTag_t sck;
ioTag_t mosi;
ioTag_t miso;
rccPeriphTag_t rcc;
uint8_t af;
volatile uint16_t errorCount;
bool sdcard;
} spiDevice_t;
bool spiInit(SPIDevice device);
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor);
uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in);
bool spiIsBusBusy(SPI_TypeDef *instance);
void spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len);
uint16_t spiGetErrorCounter(SPI_TypeDef *instance);
void spiResetErrorCounter(SPI_TypeDef *instance);

View File

@ -21,3 +21,7 @@ typedef struct mag_s {
sensorInitFuncPtr init; // initialize function
sensorReadFuncPtr read; // read 3 axis data function
} mag_t;
#ifndef MAG_I2C_INSTANCE
#define MAG_I2C_INSTANCE I2C_DEVICE
#endif

View File

@ -187,12 +187,14 @@ bool ak8963SPICompleteRead(uint8_t *buf)
#endif
#ifdef USE_I2C
bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data) {
return i2cWrite(addr_, reg_, data);
bool c_i2cWrite(uint8_t addr_, uint8_t reg_, uint8_t data)
{
return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data);
}
bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) {
return i2cRead(addr_, reg_, len, buf);
bool c_i2cRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf)
{
return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf);
}
#endif
@ -203,11 +205,11 @@ bool ak8963Detect(mag_t *mag)
#ifdef USE_I2C
// check for AK8963 on I2C bus
ack = i2cRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig);
if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H'
{
ak8963config.read = i2cRead;
ak8963config.write = i2cWrite;
ak8963config.read = c_i2cRead;
ak8963config.write = c_i2cWrite;
mag->init = ak8963Init;
mag->read = ak8963Read;

View File

@ -64,7 +64,7 @@ bool ak8975detect(mag_t *mag)
bool ack = false;
uint8_t sig = 0;
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig);
if (!ack || sig != 'H') // 0x48 / 01001000 / 'H'
return false;
@ -86,24 +86,24 @@ void ak8975Init()
UNUSED(ack);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down before entering fuse mode
delay(20);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x0F); // Enter Fuse ROM access mode
delay(10);
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975A_ASAX, 3, &buffer[0]); // Read the x-, y-, and z-axis calibration values
delay(10);
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x00); // power down after reading.
delay(10);
// Clear status registers
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
// Trigger first measurement
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01);
}
#define BIT_STATUS1_REG_DATA_READY (1 << 0)
@ -118,13 +118,13 @@ bool ak8975Read(int16_t *magData)
uint8_t status;
uint8_t buf[6];
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS1, 1, &status);
if (!ack || (status & BIT_STATUS1_REG_DATA_READY) == 0) {
return false;
}
#if 1 // USE_I2C_SINGLE_BYTE_READS
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL, 6, buf); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
#else
for (uint8_t i = 0; i < 6; i++) {
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_HXL + i, 1, &buf[i]); // read from AK8975_MAG_REG_HXL to AK8975_MAG_REG_HZH
@ -134,7 +134,7 @@ bool ak8975Read(int16_t *magData)
}
#endif
ack = i2cRead(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_STATUS2, 1, &status);
if (!ack) {
return false;
}
@ -152,6 +152,6 @@ bool ak8975Read(int16_t *magData)
magData[Z] = -(int16_t)(buf[5] << 8 | buf[4]) * 4;
ack = i2cWrite(AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
ack = i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again
return true;
}

View File

@ -204,7 +204,7 @@ bool hmc5883lDetect(mag_t* mag, const hmc5883Config_t *hmc5883ConfigToUse)
hmc5883Config = hmc5883ConfigToUse;
ack = i2cRead(MAG_ADDRESS, 0x0A, 1, &sig);
ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig);
if (!ack || sig != 'H')
return false;
@ -241,15 +241,15 @@ void hmc5883lInit(void)
}
delay(50);
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_POS_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to pos bias
// Note that the very first measurement after a gain change maintains the same gain as the previous setting.
// The new gain setting is effective from the second measurement and on.
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x60); // Set the Gain to 2.5Ga (7:5->011)
delay(100);
hmc5883lRead(magADC);
for (i = 0; i < 10; i++) { // Collect 10 samples
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1);
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -267,9 +267,9 @@ void hmc5883lInit(void)
}
// Apply the negative bias. (Same gain)
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x010 + HMC_NEG_BIAS); // Reg A DOR = 0x010 + MS1, MS0 set to negative bias.
for (i = 0; i < 10; i++) {
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 1);
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 1);
delay(50);
hmc5883lRead(magADC); // Get the raw values in case the scales have already been changed.
@ -291,9 +291,9 @@ void hmc5883lInit(void)
magGain[Z] = fabsf(660.0f * HMC58X3_Z_SELF_TEST_GAUSS * 2.0f * 10.0f / xyz_total[Z]);
// leave test mode
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2cWrite(MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2cWrite(MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFA, 0x70); // Configuration Register A -- 0 11 100 00 num samples: 8 ; output rate: 15Hz ; normal measurement mode
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_CONFB, 0x20); // Configuration Register B -- 001 00000 configuration gain 1.3Ga
i2cWrite(MAG_I2C_INSTANCE, MAG_ADDRESS, HMC58X3_R_MODE, 0x00); // Mode register -- 000000 00 continuous Conversion Mode
delay(100);
if (!bret) { // Something went wrong so get a best guess
@ -309,7 +309,7 @@ bool hmc5883lRead(int16_t *magData)
{
uint8_t buf[6];
bool ack = i2cRead(MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf);
if (!ack) {
return false;
}

View File

@ -26,6 +26,10 @@
#include "display_ug2864hsweg01.h"
#ifndef OLED_I2C_INSTANCE
#define OLED_I2C_INSTANCE I2CDEV_1
#endif
#define INVERSE_CHAR_FORMAT 0x7f // 0b01111111
#define NORMAL_CHAR_FORMAT 0x00 // 0b00000000
@ -172,12 +176,12 @@ static const uint8_t multiWiiFont[][5] = { // Refer to "Times New Roman" Font Da
static bool i2c_OLED_send_cmd(uint8_t command)
{
return i2cWrite(OLED_address, 0x80, command);
return i2cWrite(OLED_I2C_INSTANCE, OLED_address, 0x80, command);
}
static bool i2c_OLED_send_byte(uint8_t val)
{
return i2cWrite(OLED_address, 0x40, val);
return i2cWrite(OLED_I2C_INSTANCE, OLED_address, 0x40, val);
}
void i2c_OLED_clear_display(void)

View File

@ -18,25 +18,13 @@
#pragma once
#include "drivers/io.h"
// old EXTI interface, to be replaced
typedef struct extiConfig_s {
#ifdef STM32F303
uint32_t gpioAHBPeripherals;
#endif
#ifdef STM32F10X
uint32_t gpioAPB2Peripherals;
#endif
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
uint8_t exti_port_source;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
ioTag_t io;
} extiConfig_t;
// new io EXTI interface
#include "drivers/io.h"
typedef struct extiCallbackRec_s extiCallbackRec_t;
typedef void extiHandlerCallback(extiCallbackRec_t *self);

View File

@ -47,8 +47,8 @@
#define JEDEC_ID_MICRON_N25Q128 0x20ba18
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
#define DISABLE_M25P16 GPIO_SetBits(M25P16_CS_GPIO, M25P16_CS_PIN)
#define ENABLE_M25P16 GPIO_ResetBits(M25P16_CS_GPIO, M25P16_CS_PIN)
#define DISABLE_M25P16 IOHi(m25p16CsPin)
#define ENABLE_M25P16 IOLo(m25p16CsPin)
// The timeout we expect between being able to issue page program instructions
#define DEFAULT_TIMEOUT_MILLIS 6
@ -59,6 +59,8 @@
static flashGeometry_t geometry = {.pageSize = M25P16_PAGESIZE};
static IO_t m25p16CsPin = IO_NONE;
/*
* Whether we've performed an action that could have made the device busy for writes.
*
@ -195,6 +197,13 @@ static bool m25p16_readIdentification()
*/
bool m25p16_init()
{
#ifdef M25P16_CS_PIN
m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN));
#endif
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI);
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
//Maximum speed for standard READ command is 20mHz, other commands tolerate 25mHz
spiSetDivisor(M25P16_SPI_INSTANCE, SPI_18MHZ_CLOCK_DIVIDER);

View File

@ -20,26 +20,26 @@
#include "platform.h"
#ifdef INVERTER
#ifdef INVERTER
#include "gpio.h"
#include "io.h"
#include "io_impl.h"
#include "inverter.h"
static const IO_t pin = DEFIO_IO(INVERTER);
void initInverter(void)
{
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup = {
.gpio = INVERTER_GPIO,
// configure for Push-Pull
.cfg = { INVERTER_PIN, Mode_Out_PP, Speed_2MHz }
};
IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(pin, IOCFG_OUT_PP);
inverterSet(false);
}
RCC_APB2PeriphClockCmd(INVERTER_PERIPHERAL, ENABLE);
gpioInit(gpio_setup.gpio, &gpio_setup.cfg);
void inverterSet(bool on)
{
IOWrite(pin, on);
}
#endif

View File

@ -18,8 +18,9 @@
#pragma once
#ifdef INVERTER
#define INVERTER_OFF digitalLo(INVERTER_GPIO, INVERTER_PIN)
#define INVERTER_ON digitalHi(INVERTER_GPIO, INVERTER_PIN)
void inverterSet(bool on);
#define INVERTER_OFF inverterSet(false)
#define INVERTER_ON inverterSet(true)
#else
#define INVERTER_OFF do {} while(0)
#define INVERTER_ON do {} while(0)
@ -27,3 +28,5 @@
void initInverter(void);

View File

@ -1,23 +1,24 @@
#pragma once
#include <stdbool.h>
#include <stdint.h>
#include "drivers/gpio.h"
#include "drivers/resource.h"
#include "resource.h"
// IO pin identification
// make sure that ioTag_t can't be assigned into IO_t without warning
typedef uint8_t ioTag_t; // packet tag to specify IO pin
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
// NONE initializer for IO_t variable
#define IO_NONE ((IO_t)0)
// preprocessor is used to convert pinid to requested C data value
// compile-time error is generated if requested pin is not available (not set in TARGET_IO_PORTx)
// ioTag_t and IO_t is supported, but ioTag_t is preferred
// expand pinid to ioTag_t, generate compilation error if pin is not supported
// expand pinid to to ioTag_t
#define IO_TAG(pinid) DEFIO_TAG(pinid)
// expand pinid to ioTag_t, expand to NONE if pin is not supported
#define IO_TAG_E(pinid) DEFIO_TAG_E(pinid)
// both ioTag_t and IO_t are guarantied to be zero if pinid is NONE (no pin)
// this simplifies initialization (globals are zeroed on start) and allows
@ -44,7 +45,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration
# define IOCFG_IPD IO_CONFIG(GPIO_Mode_IPD, GPIO_Speed_2MHz)
# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IPU, GPIO_Speed_2MHz)
# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_2MHz)
# define IOCFG_ANALOG IO_CONFIG(GPIO_Mode_AIN, GPIO_Speed_2MHz)
#elif defined(STM32F303xC)
# define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
@ -56,7 +57,18 @@ typedef uint8_t ioConfig_t; // packed IO configuration
# define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
# define IOCFG_ANALOG IO_CONFIG(GPIO_Mode_AN, 0, 0, GPIO_PuPd_NOPULL)
#elif defined(STM32F40_41xxx) || defined(STM32F411xE)
# define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5))
# define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO
# define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
# define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL)
# define IOCFG_AF_OD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)
# define IOCFG_IPD IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_DOWN)
# define IOCFG_IPU IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_UP)
# define IOCFG_IN_FLOATING IO_CONFIG(GPIO_Mode_IN, 0, 0, GPIO_PuPd_NOPULL)
#elif defined(UNIT_TEST)
@ -88,7 +100,7 @@ resourceType_t IOGetResources(IO_t io);
IO_t IOGetByTag(ioTag_t tag);
void IOConfigGPIO(IO_t io, ioConfig_t cfg);
#if defined(STM32F303xC)
#if defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af);
#endif

View File

@ -15,27 +15,105 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
initLeds(void)
{
struct {
GPIO_TypeDef *gpio;
gpio_config_t cfg;
} gpio_setup[] = {
#include "platform.h"
#include "io.h"
#include "io_impl.h"
#include "light_led.h"
static const IO_t leds[] = {
#ifdef LED0
{
.gpio = LED0_GPIO,
.cfg = { LED0_PIN, Mode_Out_PP, Speed_2MHz }
},
#endif
DEFIO_IO(LED0),
#else
DEFIO_IO(NONE),
#endif
#ifdef LED1
{
.gpio = LED1_GPIO,
.cfg = { LED1_PIN, Mode_Out_PP, Speed_2MHz }
},
DEFIO_IO(LED1),
#else
DEFIO_IO(NONE),
#endif
#ifdef LED2
DEFIO_IO(LED2),
#else
DEFIO_IO(NONE),
#endif
}
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
#ifdef LED0_A
DEFIO_IO(LED0_A),
#else
DEFIO_IO(NONE),
#endif
#ifdef LED1_A
DEFIO_IO(LED1_A),
#else
DEFIO_IO(NONE),
#endif
#ifdef LED2_A
DEFIO_IO(LED2_A),
#else
DEFIO_IO(NONE),
#endif
#endif
};
uint8_t gpio_count = sizeof(gpio_setup) / sizeof(gpio_setup[0]);
uint8_t ledPolarity = 0
#ifdef LED0_INVERTED
| BIT(0)
#endif
#ifdef LED1_INVERTED
| BIT(1)
#endif
#ifdef LED2_INVERTED
| BIT(2)
#endif
#ifdef LED0_A_INVERTED
| BIT(3)
#endif
#ifdef LED1_A_INVERTED
| BIT(4)
#endif
#ifdef LED2_A_INVERTED
| BIT(5)
#endif
;
uint8_t ledOffset = 0;
void ledInit(bool alternative_led)
{
uint32_t i;
#if defined(LED0_A) || defined(LED1_A) || defined(LED2_A)
if (alternative_led)
ledOffset = LED_NUMBER;
#else
UNUSED(alternative_led);
#endif
LED0_OFF;
LED1_OFF;
LED2_OFF;
for (i = 0; i < LED_NUMBER; i++) {
if (leds[i + ledOffset]) {
IOInit(leds[i + ledOffset], OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
}
}
LED0_OFF;
LED1_OFF;
LED2_OFF;
}
void ledToggle(int led)
{
IOToggle(leds[led + ledOffset]);
}
void ledSet(int led, bool on)
{
bool inverted = (1 << (led + ledOffset)) & ledPolarity;
IOWrite(leds[led + ledOffset], on ? inverted : !inverted);
}

View File

@ -17,56 +17,39 @@
#pragma once
struct {
GPIO_TypeDef *gpio;
uint16_t pin;
} led_config[3];
#define LED_NUMBER 3
// Helpful macros
#ifdef LED0
#define LED0_TOGGLE digitalToggle(led_config[0].gpio, led_config[0].pin)
#ifndef LED0_INVERTED
#define LED0_OFF digitalHi(led_config[0].gpio, led_config[0].pin)
#define LED0_ON digitalLo(led_config[0].gpio, led_config[0].pin)
# define LED0_TOGGLE ledToggle(0)
# define LED0_OFF ledSet(0, false)
# define LED0_ON ledSet(0, true)
#else
#define LED0_OFF digitalLo(led_config[0].gpio, led_config[0].pin)
#define LED0_ON digitalHi(led_config[0].gpio, led_config[0].pin)
#endif // inverted
#else
#define LED0_TOGGLE do {} while(0)
#define LED0_OFF do {} while(0)
#define LED0_ON do {} while(0)
# define LED0_TOGGLE do {} while(0)
# define LED0_OFF do {} while(0)
# define LED0_ON do {} while(0)
#endif
#ifdef LED1
#define LED1_TOGGLE digitalToggle(led_config[1].gpio, led_config[1].pin)
#ifndef LED1_INVERTED
#define LED1_OFF digitalHi(led_config[1].gpio, led_config[1].pin)
#define LED1_ON digitalLo(led_config[1].gpio, led_config[1].pin)
# define LED1_TOGGLE ledToggle(1)
# define LED1_OFF ledSet(1, false)
# define LED1_ON ledSet(1, true)
#else
#define LED1_OFF digitalLo(led_config[1].gpio, led_config[1].pin)
#define LED1_ON digitalHi(led_config[1].gpio, led_config[1].pin)
#endif // inverted
#else
#define LED1_TOGGLE do {} while(0)
#define LED1_OFF do {} while(0)
#define LED1_ON do {} while(0)
# define LED1_TOGGLE do {} while(0)
# define LED1_OFF do {} while(0)
# define LED1_ON do {} while(0)
#endif
#ifdef LED2
#define LED2_TOGGLE digitalToggle(led_config[2].gpio, led_config[2].pin)
#ifndef LED2_INVERTED
#define LED2_OFF digitalHi(led_config[2].gpio, led_config[2].pin)
#define LED2_ON digitalLo(led_config[2].gpio, led_config[2].pin)
# define LED2_TOGGLE ledToggle(2)
# define LED2_OFF ledSet(2, false)
# define LED2_ON ledSet(2, true)
#else
#define LED2_OFF digitalLo(led_config[2].gpio, led_config[2].pin)
#define LED2_ON digitalHi(led_config[2].gpio, led_config[2].pin)
#endif // inverted
#else
#define LED2_TOGGLE do {} while(0)
#define LED2_OFF do {} while(0)
#define LED2_ON do {} while(0)
# define LED2_TOGGLE do {} while(0)
# define LED2_OFF do {} while(0)
# define LED2_ON do {} while(0)
#endif
void ledInit(bool alternative_led);
void ledToggle(int led);
void ledSet(int led, bool state);

View File

@ -1,64 +0,0 @@
/*
* 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 <stdlib.h>
#include <platform.h>
#include "common/utils.h"
#include "system.h"
#include "gpio.h"
#include "light_led.h"
void ledInit(bool alternative_led)
{
UNUSED(alternative_led);
#if defined(LED0) || defined(LED1) || defined(LED2)
gpio_config_t cfg;
cfg.mode = Mode_Out_PP;
cfg.speed = Speed_2MHz;
#ifdef LED0
RCC_APB2PeriphClockCmd(LED0_PERIPHERAL, ENABLE);
led_config[0].gpio = LED0_GPIO;
led_config[0].pin = LED0_PIN;
cfg.pin = led_config[0].pin;
LED0_OFF;
gpioInit(led_config[0].gpio, &cfg);
#endif
#ifdef LED1
RCC_APB2PeriphClockCmd(LED1_PERIPHERAL, ENABLE);
led_config[1].gpio = LED1_GPIO;
led_config[1].pin = LED1_PIN;
cfg.pin = led_config[1].pin;
LED1_OFF;
gpioInit(led_config[1].gpio, &cfg);
#endif
#ifdef LED2
RCC_APB2PeriphClockCmd(LED2_PERIPHERAL, ENABLE);
led_config[2].gpio = LED2_GPIO;
led_config[2].pin = LED2_PIN;
cfg.pin = led_config[2].pin;
LED2_OFF;
gpioInit(led_config[2].gpio, &cfg);
#endif
#endif
}

View File

@ -1,88 +0,0 @@
/*
* 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 <stdlib.h>
#include <platform.h>
#include "common/utils.h"
#include "gpio.h"
#include "light_led.h"
void ledInit(bool alternative_led)
{
#if defined(LED0) || defined(LED1) || defined(LED2)
gpio_config_t cfg;
cfg.mode = Mode_Out_PP;
cfg.speed = Speed_2MHz;
#ifdef LED0
if (alternative_led) {
#ifdef LED0_PERIPHERAL_2
RCC_AHBPeriphClockCmd(LED0_PERIPHERAL_2, ENABLE);
led_config[0].gpio = LED0_GPIO_2;
led_config[0].pin = LED0_PIN_2;
#endif
} else {
RCC_AHBPeriphClockCmd(LED0_PERIPHERAL, ENABLE);
led_config[0].gpio = LED0_GPIO;
led_config[0].pin = LED0_PIN;
}
cfg.pin = led_config[0].pin;
LED0_OFF;
gpioInit(led_config[0].gpio, &cfg);
#endif
#ifdef LED1
if (alternative_led) {
#ifdef LED1_PERIPHERAL_2
RCC_AHBPeriphClockCmd(LED1_PERIPHERAL_2, ENABLE);
led_config[1].gpio = LED1_GPIO_2;
led_config[1].pin = LED1_PIN_2;
#endif
} else {
RCC_AHBPeriphClockCmd(LED1_PERIPHERAL, ENABLE);
led_config[1].gpio = LED1_GPIO;
led_config[1].pin = LED1_PIN;
}
cfg.pin = led_config[1].pin;
LED1_OFF;
gpioInit(led_config[1].gpio, &cfg);
#endif
#ifdef LED2
if (alternative_led) {
#ifdef LED2_PERIPHERAL_2
RCC_AHBPeriphClockCmd(LED2_PERIPHERAL_2, ENABLE);
led_config[2].gpio = LED2_GPIO_2;
led_config[2].pin = LED2_PIN_2;
#endif
} else {
RCC_AHBPeriphClockCmd(LED2_PERIPHERAL, ENABLE);
led_config[2].gpio = LED2_GPIO;
led_config[2].pin = LED2_PIN;
}
cfg.pin = led_config[2].pin;
LED2_OFF;
gpioInit(led_config[2].gpio, &cfg);
#endif
#else
UNUSED(alternative_led);
#endif
}

View File

@ -23,6 +23,7 @@
*
* Currently the timings are 0 = 350ns high/800ns and 1 = 700ns high/650ns low.
*/
#include <stdbool.h>
#include <stdint.h>
#include <string.h>
@ -36,6 +37,8 @@
#include "drivers/dma.h"
#include "drivers/light_ws2811strip.h"
#ifdef LED_STRIP
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
volatile uint8_t ws2811LedDataTransferInProgress = 0;
@ -170,3 +173,4 @@ void ws2811UpdateStrip(void)
ws2811LedStripDMAEnable();
}
#endif

View File

@ -6,10 +6,12 @@
// can't use 0
#define NVIC_PRIO_MAX NVIC_BUILD_PRIORITY(0, 1)
#define NVIC_PRIO_TIMER NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_BARO_EXT NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
#define NVIC_PRIO_BST_READ_DATA NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_BARO_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_SONAR_EXTI NVIC_BUILD_PRIORITY(2, 0) // maybe increate slightly
#define NVIC_PRIO_TRANSPONDER_DMA NVIC_BUILD_PRIORITY(3, 0)
#define NVIC_PRIO_MPU_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_INT_EXTI NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_WS2811_DMA NVIC_BUILD_PRIORITY(1, 2) // TODO - is there some reason to use high priority? (or to use DMA IRQ at all?)
#define NVIC_PRIO_SERIALUART1_TXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART1 NVIC_BUILD_PRIORITY(1, 1)
@ -19,6 +21,15 @@
#define NVIC_PRIO_SERIALUART3_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART3_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART3 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART4_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART4_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART4 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART5_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART5_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART5 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_SERIALUART6_TXDMA NVIC_BUILD_PRIORITY(1, 0)
#define NVIC_PRIO_SERIALUART6_RXDMA NVIC_BUILD_PRIORITY(1, 1)
#define NVIC_PRIO_SERIALUART6 NVIC_BUILD_PRIORITY(1, 2)
#define NVIC_PRIO_I2C_ER NVIC_BUILD_PRIORITY(0, 0)
#define NVIC_PRIO_I2C_EV NVIC_BUILD_PRIORITY(0, 0)
#define NVIC_PRIO_USB NVIC_BUILD_PRIORITY(2, 0)
@ -27,6 +38,7 @@
#define NVIC_PRIO_MPU_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_MAG_DATA_READY NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_CALLBACK NVIC_BUILD_PRIORITY(0x0f, 0x0f)
#define NVIC_PRIO_BST_READ_DATA NVIC_BUILD_PRIORITY(1, 1)
// utility macros to join/split priority
#define NVIC_BUILD_PRIORITY(base,sub) (((((base)<<(4-(7-(NVIC_PRIORITY_GROUPING>>8))))|((sub)&(0x0f>>(7-(NVIC_PRIORITY_GROUPING>>8)))))<<4)&0xf0)

View File

@ -4,17 +4,48 @@
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
{
int tag = periphTag >> 5;
uint32_t mask = 1 << (periphTag & 0x1f);
switch(tag) {
case RCC_AHB:
RCC_AHBPeriphClockCmd(mask, NewState);
break;
case RCC_APB2:
RCC_APB2PeriphClockCmd(mask, NewState);
break;
case RCC_APB1:
RCC_APB1PeriphClockCmd(mask, NewState);
break;
}
int tag = periphTag >> 5;
uint32_t mask = 1 << (periphTag & 0x1f);
switch (tag) {
#if defined(STM32F303xC)
case RCC_AHB:
RCC_AHBPeriphClockCmd(mask, NewState);
break;
#endif
case RCC_APB2:
RCC_APB2PeriphClockCmd(mask, NewState);
break;
case RCC_APB1:
RCC_APB1PeriphClockCmd(mask, NewState);
break;
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
case RCC_AHB1:
RCC_AHB1PeriphClockCmd(mask, NewState);
break;
#endif
}
}
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState)
{
int tag = periphTag >> 5;
uint32_t mask = 1 << (periphTag & 0x1f);
switch (tag) {
#if defined(STM32F303xC)
case RCC_AHB:
RCC_AHBPeriphResetCmd(mask, NewState);
break;
#endif
case RCC_APB2:
RCC_APB2PeriphResetCmd(mask, NewState);
break;
case RCC_APB1:
RCC_APB1PeriphResetCmd(mask, NewState);
break;
#if defined(STM32F40_41xxx) || defined(STM32F411xE)
case RCC_AHB1:
RCC_AHB1PeriphResetCmd(mask, NewState);
break;
#endif
}
}

View File

@ -17,5 +17,5 @@ enum rcc_reg {
typedef uint8_t rccPeriphTag_t;
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);

View File

@ -21,18 +21,23 @@ typedef enum {
OWNER_TIMER,
OWNER_SONAR,
OWNER_SYSTEM,
OWNER_SDCARD,
OWNER_FLASH,
OWNER_USB
} resourceOwner_t;
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)
// with mode switching (shared serial ports, ...) this will need some improvement
typedef enum {
RESOURCE_INPUT = 1 << 0,
RESOURCE_OUTPUT = 1<< 1,
RESOURCE_NONE = 0,
RESOURCE_INPUT = 1 << 0,
RESOURCE_OUTPUT = 1 << 1,
RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT,
RESOURCE_TIMER = 1 << 2,
RESOURCE_TIMER = 1 << 2,
RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too
RESOURCE_USART = 1 << 4,
RESOURCE_ADC = 1 << 5,
RESOURCE_EXTI = 1 << 6,
RESOURCE_USART = 1 << 4,
RESOURCE_ADC = 1 << 5,
RESOURCE_EXTI = 1 << 6,
RESOURCE_I2C = 1 << 7,
RESOURCE_SPI = 1 << 8,
} resourceType_t;

View File

@ -24,7 +24,7 @@
#include "platform.h"
#include "nvic.h"
#include "gpio.h"
#include "io.h"
#include "drivers/bus_spi.h"
#include "drivers/system.h"
@ -37,8 +37,8 @@
#define SDCARD_PROFILING
#endif
#define SET_CS_HIGH GPIO_SetBits(SDCARD_SPI_CS_GPIO, SDCARD_SPI_CS_PIN)
#define SET_CS_LOW GPIO_ResetBits(SDCARD_SPI_CS_GPIO, SDCARD_SPI_CS_PIN)
#define SET_CS_HIGH IOHi(sdcardDetectPin)
#define SET_CS_LOW IOLo(sdcardDetectPin)
#define SDCARD_INIT_NUM_DUMMY_BYTES 10
#define SDCARD_MAXIMUM_BYTE_DELAY_FOR_CMD_REPLY 8
@ -117,25 +117,23 @@ static sdcard_t sdcard;
STATIC_ASSERT(sizeof(sdcardCSD_t) == 16, sdcard_csd_bitfields_didnt_pack_properly);
static IO_t sdcardDetectPin = IO_NONE;
void sdcardInsertionDetectDeinit(void)
{
#ifdef SDCARD_DETECT_PIN
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = SDCARD_DETECT_PIN;
GPIO_Init(SDCARD_DETECT_GPIO_PORT, &GPIO_InitStructure);
sdcardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdcardDetectPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(sdcardDetectPin, SPI_IO_CS_CFG);
#endif
}
void sdcardInsertionDetectInit(void)
{
#ifdef SDCARD_DETECT_PIN
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = SDCARD_DETECT_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(SDCARD_DETECT_GPIO_PORT, &GPIO_InitStructure);
sdcardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
IOInit(sdcardDetectPin, OWNER_SDCARD, RESOURCE_INPUT);
IOConfigGPIO(sdcardDetectPin, SPI_IO_CS_CFG);
#endif
}
@ -148,7 +146,7 @@ bool sdcard_isInserted(void)
#ifdef SDCARD_DETECT_PIN
result = (GPIO_ReadInputData(SDCARD_DETECT_GPIO_PORT) & SDCARD_DETECT_PIN) != 0;
result = IORead(sdcardDetectPin) != 0;
#ifdef SDCARD_DETECT_INVERTED
result = !result;

View File

@ -24,7 +24,8 @@
#include "system.h"
#include "gpio.h"
#include "nvic.h"
#include "io.h"
#include "exti.h"
#include "sonar_hcsr04.h"
/* HC-SR04 consists of ultrasonic transmitter, receiver, and control circuits.
@ -41,40 +42,27 @@ STATIC_UNIT_TESTED volatile int32_t measurement = -1;
static uint32_t lastMeasurementAt;
static sonarHardware_t const *sonarHardware;
#if !defined(UNIT_TEST)
static void ECHO_EXTI_IRQHandler(void)
extiCallbackRec_t hcsr04_extiCallbackRec;
static IO_t echoIO;
//static IO_t triggerIO;
void hcsr04_extiHandler(extiCallbackRec_t* cb)
{
static uint32_t timing_start;
uint32_t timing_stop;
UNUSED(cb);
if (digitalIn(sonarHardware->echo_gpio, sonarHardware->echo_pin) != 0) {
timing_start = micros();
} else {
}
else {
timing_stop = micros();
if (timing_stop > timing_start) {
measurement = timing_stop - timing_start;
}
}
EXTI_ClearITPendingBit(sonarHardware->exti_line);
}
void EXTI0_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI1_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
void EXTI9_5_IRQHandler(void)
{
ECHO_EXTI_IRQHandler();
}
#endif
void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sonarRange)
{
sonarHardware = initialSonarHardware;
@ -84,7 +72,6 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sona
#if !defined(UNIT_TEST)
gpio_config_t gpio;
EXTI_InitTypeDef EXTIInit;
#ifdef STM32F10X
// enable AFIO for EXTI support
@ -108,35 +95,17 @@ void hcsr04_init(const sonarHardware_t *initialSonarHardware, sonarRange_t *sona
gpio.pin = sonarHardware->echo_pin;
gpio.mode = Mode_IN_FLOATING;
gpioInit(sonarHardware->echo_gpio, &gpio);
#ifdef STM32F10X
// setup external interrupt on echo pin
gpioExtiLineConfig(GPIO_PortSourceGPIOB, sonarHardware->exti_pin_source);
echoIO = IOGetByTag(sonarHardware->echoIO);
#ifdef USE_EXTI
EXTIHandlerInit(&hcsr04_extiCallbackRec, hcsr04_extiHandler);
EXTIConfig(echoIO, &hcsr04_extiCallbackRec, NVIC_PRIO_SONAR_EXTI, EXTI_Trigger_Rising_Falling); // TODO - priority!
EXTIEnable(echoIO, true);
#endif
#ifdef STM32F303xC
gpioExtiLineConfig(EXTI_PortSourceGPIOB, sonarHardware->exti_pin_source);
#endif
EXTI_ClearITPendingBit(sonarHardware->exti_line);
EXTIInit.EXTI_Line = sonarHardware->exti_line;
EXTIInit.EXTI_Mode = EXTI_Mode_Interrupt;
EXTIInit.EXTI_Trigger = EXTI_Trigger_Rising_Falling;
EXTIInit.EXTI_LineCmd = ENABLE;
EXTI_Init(&EXTIInit);
NVIC_InitTypeDef NVIC_InitStructure;
NVIC_InitStructure.NVIC_IRQChannel = sonarHardware->exti_irqn;
NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SONAR_ECHO);
NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_SONAR_ECHO);
NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
NVIC_Init(&NVIC_InitStructure);
lastMeasurementAt = millis() - 60; // force 1st measurement in hcsr04_get_distance()
#else
lastMeasurementAt = 0; // to avoid "unused" compiler warning
UNUSED(lastMeasurementAt); // to avoid "unused" compiler warning
#endif
}

View File

@ -18,15 +18,15 @@
#pragma once
#include "platform.h"
#include "io.h"
typedef struct sonarHardware_s {
uint16_t trigger_pin;
GPIO_TypeDef* trigger_gpio;
uint16_t echo_pin;
GPIO_TypeDef* echo_gpio;
uint32_t exti_line;
uint8_t exti_pin_source;
IRQn_Type exti_irqn;
ioTag_t triggerIO;
ioTag_t echoIO;
} sonarHardware_t;
typedef struct sonarRange_s {

View File

@ -21,7 +21,7 @@
#include "platform.h"
#include "build_config.h"
#include "common/utils.h"
#include "system.h"
#include "gpio.h"
@ -31,49 +31,39 @@
#ifdef BEEPER
void (*systemBeepPtr)(bool onoff) = NULL;
static IO_t beeperIO = DEFIO_IO(NONE);
static bool beeperInverted = false;
static uint16_t beeperPin;
static void beepNormal(bool onoff)
{
if (onoff) {
digitalLo(BEEP_GPIO, beeperPin);
} else {
digitalHi(BEEP_GPIO, beeperPin);
}
}
static void beepInverted(bool onoff)
{
if (onoff) {
digitalHi(BEEP_GPIO, beeperPin);
} else {
digitalLo(BEEP_GPIO, beeperPin);
}
}
#endif
void systemBeep(bool onoff)
{
#ifndef BEEPER
UNUSED(onoff);
UNUSED(onoff);
#else
systemBeepPtr(onoff);
IOWrite(beeperIO, beeperInverted ? onoff : !onoff);
#endif
}
void beeperInit(beeperConfig_t *config)
void systemBeepToggle(void)
{
#ifndef BEEPER
UNUSED(config);
#else
beeperPin = config->gpioPin;
initBeeperHardware(config);
if (config->isInverted)
systemBeepPtr = beepInverted;
else
systemBeepPtr = beepNormal;
BEEP_OFF;
#ifdef BEEPER
IOToggle(beeperIO);
#endif
}
void beeperInit(const beeperConfig_t *config)
{
#ifndef BEEPER
UNUSED(config);
#else
beeperIO = IOGetByTag(config->ioTag);
beeperInverted = config->isInverted;
if (beeperIO) {
IOInit(beeperIO, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP);
}
systemBeep(false);
#endif
}

View File

@ -17,25 +17,25 @@
#pragma once
#include "drivers/io.h"
#ifdef BEEPER
#define BEEP_TOGGLE digitalToggle(BEEP_GPIO, BEEP_PIN)
#define BEEP_TOGGLE systemBeepToggle()
#define BEEP_OFF systemBeep(false)
#define BEEP_ON systemBeep(true)
#else
#define BEEP_TOGGLE
#define BEEP_OFF
#define BEEP_ON
#define BEEP_TOGGLE do {} while(0)
#define BEEP_OFF do {} while(0)
#define BEEP_ON do {} while(0)
#endif
typedef struct beeperConfig_s {
uint32_t gpioPeripheral;
uint16_t gpioPin;
GPIO_TypeDef *gpioPort;
GPIO_Mode gpioMode;
bool isInverted;
ioTag_t ioTag;
unsigned isInverted : 1;
unsigned isOD : 1;
} beeperConfig_t;
void systemBeep(bool onoff);
void beeperInit(beeperConfig_t *beeperConfig);
void systemBeep(bool on);
void systemBeepToggle(void);
void beeperInit(const beeperConfig_t *beeperConfig);
void initBeeperHardware(beeperConfig_t *config);

View File

@ -1,46 +0,0 @@
/*
* 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 <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "system.h"
#include "gpio.h"
#include "sound_beeper.h"
void initBeeperHardware(beeperConfig_t *config)
{
#ifndef BEEPER
UNUSED(config);
#else
gpio_config_t gpioConfig = {
config->gpioPin,
config->gpioMode,
Speed_2MHz
};
RCC_APB2PeriphClockCmd(config->gpioPeripheral, ENABLE);
gpioInit(config->gpioPort, &gpioConfig);
#endif
}

View File

@ -1,45 +0,0 @@
/*
* 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 <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "gpio.h"
#include "sound_beeper.h"
void initBeeperHardware(beeperConfig_t *config)
{
#ifndef BEEPER
UNUSED(config);
#else
gpio_config_t gpioConfig = {
config->gpioPin,
config->gpioMode,
Speed_2MHz
};
RCC_AHBPeriphClockCmd(config->gpioPeripheral, ENABLE);
gpioInit(config->gpioPort, &gpioConfig);
#endif
}

View File

@ -55,48 +55,6 @@ void registerExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
failureMode(FAILURE_DEVELOPER); // EXTI_CALLBACK_HANDLER_COUNT is too low for the amount of handlers required.
}
void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn)
{
for (int index = 0; index < EXTI_CALLBACK_HANDLER_COUNT; index++) {
extiCallbackHandlerConfig_t *candidate = &extiHandlerConfigs[index];
if (candidate->fn == fn && candidate->irqn == irqn) {
candidate->fn = NULL;
candidate->irqn = 0;
return;
}
}
}
static void extiHandler(IRQn_Type irqn)
{
for (int index = 0; index < EXTI_CALLBACK_HANDLER_COUNT; index++) {
extiCallbackHandlerConfig_t *candidate = &extiHandlerConfigs[index];
if (candidate->fn && candidate->irqn == irqn) {
candidate->fn();
}
}
}
void EXTI15_10_IRQHandler(void)
{
extiHandler(EXTI15_10_IRQn);
}
#if defined(CC3D)
void EXTI3_IRQHandler(void)
{
extiHandler(EXTI3_IRQn);
}
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
void EXTI9_5_IRQHandler(void)
{
extiHandler(EXTI9_5_IRQn);
}
#endif
// cycles per microsecond
static uint32_t usTicks = 0;
// current uptime for 1kHz systick timer. will rollover after 49 days. hopefully we won't care.

View File

@ -24,8 +24,18 @@ void delay(uint32_t ms);
uint32_t micros(void);
uint32_t millis(void);
typedef enum {
FAILURE_DEVELOPER = 0,
FAILURE_MISSING_ACC,
FAILURE_ACC_INIT,
FAILURE_ACC_INCOMPATIBLE,
FAILURE_INVALID_EEPROM_CONTENTS,
FAILURE_FLASH_WRITE_FAILED,
FAILURE_GYRO_INIT_FAILED
} failureMode_e;
// failure
void failureMode(uint8_t mode);
void failureMode(failureMode_e mode);
// bootloader/IAP
void systemReset(void);
@ -43,13 +53,5 @@ void unregisterExtiCallbackHandler(IRQn_Type irqn, extiCallbackHandlerFunc *fn);
extern uint32_t cachedRccCsrValue;
typedef enum {
FAILURE_DEVELOPER = 0,
FAILURE_MISSING_ACC,
FAILURE_ACC_INIT,
FAILURE_ACC_INCOMPATIBLE,
FAILURE_INVALID_EEPROM_CONTENTS,
FAILURE_FLASH_WRITE_FAILED,
FAILURE_GYRO_INIT_FAILED
} failureMode_e;

View File

@ -15,39 +15,32 @@
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
*/
#include "sdcard.h"
#include <stdlib.h>
#include <stdbool.h>
#include <stdint.h>
#include "platform.h"
#include "io.h"
#include "system.h"
#include "gpio.h"
#include "drivers/system.h"
static IO_t usbDetectPin = IO_NONE;
void usbCableDetectDeinit(void)
{
#ifdef USB_DETECT_PIN
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE);
IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING);
usbDetectPin = IO_NONE;
#endif
}
void usbCableDetectInit(void)
{
#ifdef USB_DETECT_PIN
RCC_AHBPeriphClockCmd(USB_DETECT_GPIO_CLK, ENABLE);
usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN));
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT);
IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP);
#endif
}
@ -56,7 +49,7 @@ bool usbCableIsInserted(void)
bool result = false;
#ifdef USB_DETECT_PIN
result = (GPIO_ReadInputData(USB_DETECT_GPIO_PORT) & USB_DETECT_PIN) != 0;
result = IORead(usbDetectPin) != 0;
#endif
return result;

View File

@ -23,35 +23,30 @@
#include "platform.h"
#include "gpio.h"
#include "drivers/system.h"
#include "drivers/usb_io.h"
#include "io.h"
#include "system.h"
#include "usb_io.h"
#ifdef USB_IO
static IO_t usbDetectPin = IO_NONE;
void usbCableDetectDeinit(void)
{
#ifdef USB_CABLE_DETECTION
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
#ifdef USB_DETECT_PIN
IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE);
IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING);
usbDetectPin = IO_NONE;
#endif
}
void usbCableDetectInit(void)
{
#ifdef USB_CABLE_DETECTION
RCC_AHBPeriphClockCmd(USB_DETECT_GPIO_CLK, ENABLE);
#ifdef USB_DETECT_PIN
usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN));
GPIO_InitTypeDef GPIO_InitStructure;
GPIO_InitStructure.GPIO_Pin = USB_DETECT_PIN;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_IN;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
GPIO_Init(USB_DETECT_GPIO_PORT, &GPIO_InitStructure);
IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT);
IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP);
#endif
}
@ -59,8 +54,8 @@ bool usbCableIsInserted(void)
{
bool result = false;
#ifdef USB_CABLE_DETECTION
result = (GPIO_ReadInputData(USB_DETECT_GPIO_PORT) & USB_DETECT_PIN) != 0;
#ifdef USB_DETECT_PIN
result = IORead(usbDetectPin) != 0;
#endif
return result;
@ -68,32 +63,15 @@ bool usbCableIsInserted(void)
void usbGenerateDisconnectPulse(void)
{
GPIO_InitTypeDef GPIO_InitStructure;
/* Pull down PA12 to create USB disconnect pulse */
#if defined(STM32F303xC)
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_GPIOA, ENABLE);
IO_t usbPin = IOGetByTag(IO_TAG(PA12));
IOConfigGPIO(usbPin, IOCFG_OUT_OD);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_OUT;
GPIO_InitStructure.GPIO_OType = GPIO_OType_OD;
GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_NOPULL;
#else
RCC_APB2PeriphClockCmd(RCC_APB2Periph_GPIOA, ENABLE);
GPIO_InitStructure.GPIO_Pin = GPIO_Pin_12;
GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz;
GPIO_InitStructure.GPIO_Mode = GPIO_Mode_Out_OD;
#endif
GPIO_Init(GPIOA, &GPIO_InitStructure);
GPIO_ResetBits(GPIOA, GPIO_Pin_12);
IOHi(usbPin);
delay(200);
GPIO_SetBits(GPIOA, GPIO_Pin_12);
IOLo(usbPin);
}
#endif

View File

@ -2692,7 +2692,7 @@ static void cliSet(char *cmdline)
if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
bool changeValue = false;
int_float_value_t tmp;
int_float_value_t tmp = { 0 };
switch (valueTable[i].type & VALUE_MODE_MASK) {
case MODE_DIRECT: {
int32_t value = 0;

View File

@ -353,14 +353,12 @@ void init(void)
#ifdef BEEPER
beeperConfig_t beeperConfig = {
.gpioPeripheral = BEEP_PERIPHERAL,
.gpioPin = BEEP_PIN,
.gpioPort = BEEP_GPIO,
.ioTag = IO_TAG(BEEPER),
#ifdef BEEPER_INVERTED
.gpioMode = Mode_Out_PP,
.isOD = false,
.isInverted = true
#else
.gpioMode = Mode_Out_OD,
.isOD = true,
.isInverted = false
#endif
};
@ -371,13 +369,13 @@ void init(void)
#ifdef NAZE
if (hardwareRevision >= NAZE32_REV5) {
// naze rev4 and below used opendrain to PNP for buzzer. Rev5 and above use PP to NPN.
beeperConfig.gpioMode = Mode_Out_PP;
beeperConfig.isOD = true;
beeperConfig.isInverted = true;
}
#endif
#ifdef CC3D
if (masterConfig.use_buzzer_p6 == 1)
beeperConfig.gpioPin = Pin_2;
beeperConfig.ioTag = IO_TAG(BEEPER_OPT);
#endif
beeperInit(&beeperConfig);
@ -391,18 +389,16 @@ void init(void)
bstInit(BST_DEVICE);
#endif
#ifdef USE_SPI
spiInit(SPI1);
spiInit(SPI2);
spiInit(SPIDEV_1);
spiInit(SPIDEV_2);
#ifdef STM32F303xC
#ifdef ALIENFLIGHTF3
if (hardwareRevision == AFF3_REV_2) {
spiInit(SPI3);
spiInit(SPIDEV_3);
}
#else
spiInit(SPI3);
spiInit(SPIDEV_3);
#endif
#endif
#endif

View File

@ -28,6 +28,7 @@
#define U_ID_1 (*(uint32_t*)0x1FFFF7B0)
#define U_ID_2 (*(uint32_t*)0x1FFFF7B4)
#define STM32F3
#endif
#ifdef STM32F10X
@ -41,6 +42,7 @@
#define U_ID_1 (*(uint32_t*)0x1FFFF7EC)
#define U_ID_2 (*(uint32_t*)0x1FFFF7F0)
#define STM32F1
#endif // STM32F10X
#include "target.h"

View File

@ -22,7 +22,8 @@
#include "platform.h"
#include "debug.h"
#include "drivers/gpio.h"
#include "drivers/io.h"
#include "drivers/io_impl.h"
#include "drivers/system.h"
#include "drivers/light_led.h"
@ -58,6 +59,13 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
#ifdef SPEKTRUM_BIND
static IO_t BindPin = DEFIO_IO(NONE);
#endif
#ifdef HARDWARE_BIND_PLUG
static IO_t BindPlug = DEFIO_IO(NONE);
#endif
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataPtr *callback)
{
rxRuntimeConfigPtr = rxRuntimeConfig;
@ -159,16 +167,13 @@ static uint16_t spektrumReadRawRC(rxRuntimeConfig_t *rxRuntimeConfig, uint8_t ch
bool spekShouldBind(uint8_t spektrum_sat_bind)
{
#ifdef HARDWARE_BIND_PLUG
gpio_config_t cfg = {
BINDPLUG_PIN,
Mode_IPU,
Speed_2MHz
};
gpioInit(BINDPLUG_PORT, &cfg);
BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN));
IOInit(BindPlug, OWNER_SYSTEM, RESOURCE_INPUT);
IOConfigGPIO(BindPlug, IOCFG_IPU);
// Check status of bind plug and exit if not active
delayMicroseconds(10); // allow configuration to settle
if (digitalIn(BINDPLUG_PORT, BINDPLUG_PIN)) {
if (IORead(BindPlug)) {
return false;
}
#endif
@ -194,15 +199,12 @@ void spektrumBind(rxConfig_t *rxConfig)
LED1_ON;
gpio_config_t cfg = {
BIND_PIN,
Mode_Out_OD,
Speed_2MHz
};
gpioInit(BIND_PORT, &cfg);
BindPin = IOGetByTag(IO_TAG(BIND_PIN));
IOInit(BindPin, OWNER_SYSTEM, RESOURCE_OUTPUT);
IOConfigGPIO(BindPin, IOCFG_OUT_PP);
// RX line, set high
digitalHi(BIND_PORT, BIND_PIN);
IOWrite(BindPin, true);
// Bind window is around 20-140ms after powerup
delay(60);
@ -213,13 +215,13 @@ void spektrumBind(rxConfig_t *rxConfig)
LED0_OFF;
LED2_OFF;
// RX line, drive low for 120us
digitalLo(BIND_PORT, BIND_PIN);
IOWrite(BindPin, false);
delayMicroseconds(120);
LED0_ON;
LED2_ON;
// RX line, drive high for 120us
digitalHi(BIND_PORT, BIND_PIN);
IOWrite(BindPin, true);
delayMicroseconds(120);
}

View File

@ -84,26 +84,19 @@ uint8_t detectedSensors[MAX_SENSORS_TO_DETECT] = { GYRO_NONE, ACC_NONE, BARO_NON
const extiConfig_t *selectMPUIntExtiConfig(void)
{
#if defined(MPU_INT_EXTI)
static const extiConfig_t mpuIntExtiConfig = { .io = IO_TAG(MPU_INT_EXTI) };
return &mpuIntExtiConfig;
#endif
#ifdef NAZE
// MPU_INT output on rev4 PB13
static const extiConfig_t nazeRev4MPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOB,
.gpioPin = Pin_13,
.gpioPort = GPIOB,
.exti_port_source = GPIO_PortSourceGPIOB,
.exti_line = EXTI_Line13,
.exti_pin_source = GPIO_PinSource13,
.exti_irqn = EXTI15_10_IRQn
.io = IO_TAG(PB13)
};
// MPU_INT output on rev5 hardware PC13
static const extiConfig_t nazeRev5MPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOC,
.gpioPin = Pin_13,
.gpioPort = GPIOC,
.exti_port_source = GPIO_PortSourceGPIOC,
.exti_line = EXTI_Line13,
.exti_pin_source = GPIO_PinSource13,
.exti_irqn = EXTI15_10_IRQn
.io = IO_TAG(PC13)
};
#ifdef AFROMINI
@ -111,118 +104,29 @@ const extiConfig_t *selectMPUIntExtiConfig(void)
#else
if (hardwareRevision < NAZE32_REV5) {
return &nazeRev4MPUIntExtiConfig;
} else {
}
else {
return &nazeRev5MPUIntExtiConfig;
}
#endif
#endif
#if defined(SPRACINGF3) || defined(SPRACINGF3MINI) || defined(SPRACINGF3EVO)
static const extiConfig_t spRacingF3MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPort = GPIOC,
.gpioPin = Pin_13,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource13,
.exti_line = EXTI_Line13,
.exti_irqn = EXTI15_10_IRQn
};
return &spRacingF3MPUIntExtiConfig;
#endif
#if defined(CC3D)
static const extiConfig_t cc3dMPUIntExtiConfig = {
.gpioAPB2Peripherals = RCC_APB2Periph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_3,
.exti_port_source = GPIO_PortSourceGPIOA,
.exti_pin_source = GPIO_PinSource3,
.exti_line = EXTI_Line3,
.exti_irqn = EXTI3_IRQn
};
return &cc3dMPUIntExtiConfig;
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
static const extiConfig_t RaceMPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_5,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource5,
.exti_line = EXTI_Line5,
.exti_irqn = EXTI9_5_IRQn
};
return &RaceMPUIntExtiConfig;
#endif
#if defined(DOGE)
static const extiConfig_t dogeMPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPort = GPIOC,
.gpioPin = Pin_13,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource13,
.exti_line = EXTI_Line13,
.exti_irqn = EXTI15_10_IRQn
};
return &dogeMPUIntExtiConfig;
#endif
#if defined(MOTOLAB) || defined(SPARKY)
static const extiConfig_t MotolabF3MPU6050Config = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_15,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource15,
.exti_line = EXTI_Line15,
.exti_irqn = EXTI15_10_IRQn
};
return &MotolabF3MPU6050Config;
#endif
#ifdef SINGULARITY
static const extiConfig_t singularityMPU6050Config = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOC,
.gpioPort = GPIOC,
.gpioPin = Pin_13,
.exti_port_source = EXTI_PortSourceGPIOC,
.exti_pin_source = EXTI_PinSource13,
.exti_line = EXTI_Line13,
.exti_irqn = EXTI15_10_IRQn
};
return &singularityMPU6050Config;
#endif
#ifdef ALIENFLIGHTF3
// MPU_INT output on V1 PA15
static const extiConfig_t alienFlightF3V1MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOA,
.gpioPort = GPIOA,
.gpioPin = Pin_15,
.exti_port_source = EXTI_PortSourceGPIOA,
.exti_pin_source = EXTI_PinSource15,
.exti_line = EXTI_Line15,
.exti_irqn = EXTI15_10_IRQn
.io = IO_TAG(PA15)
};
// MPU_INT output on V2 PB13
static const extiConfig_t alienFlightF3V2MPUIntExtiConfig = {
.gpioAHBPeripherals = RCC_AHBPeriph_GPIOB,
.gpioPort = GPIOB,
.gpioPin = Pin_13,
.exti_port_source = EXTI_PortSourceGPIOB,
.exti_pin_source = EXTI_PinSource13,
.exti_line = EXTI_Line13,
.exti_irqn = EXTI15_10_IRQn
.io = IO_TAG(PB13)
};
if (hardwareRevision == AFF3_REV_1) {
return &alienFlightF3V1MPUIntExtiConfig;
} else {
}
else {
return &alienFlightF3V2MPUIntExtiConfig;
}
#endif
return NULL;
}
@ -534,23 +438,20 @@ static void detectBaro(baroSensor_e baroHardwareToUse)
#ifdef USE_BARO_BMP085
const bmp085Config_t *bmp085Config = NULL;
const bmp085Config_t *bmp085Config = NULL;
#if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO)
static const bmp085Config_t defaultBMP085Config = {
.gpioAPB2Peripherals = BARO_APB2_PERIPHERALS,
.xclrGpioPin = BARO_XCLR_PIN,
.xclrGpioPort = BARO_XCLR_GPIO,
.eocGpioPin = BARO_EOC_PIN,
.eocGpioPort = BARO_EOC_GPIO
};
bmp085Config = &defaultBMP085Config;
static const bmp085Config_t defaultBMP085Config = {
.xclrIO = IO_TAG(BARO_XCLR_PIN),
.eocIO = IO_TAG(BARO_EOC_PIN),
};
bmp085Config = &defaultBMP085Config;
#endif
#ifdef NAZE
if (hardwareRevision == NAZE32) {
bmp085Disable(bmp085Config);
}
if (hardwareRevision == NAZE32) {
bmp085Disable(bmp085Config);
}
#endif
#endif

View File

@ -56,18 +56,16 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
.trigger_gpio = GPIOB,
.echo_pin = Pin_9, // PWM6 (PB9) - 5v tolerant
.echo_gpio = GPIOB,
.exti_line = EXTI_Line9,
.exti_pin_source = GPIO_PinSource9,
.exti_irqn = EXTI9_5_IRQn
.triggerIO = IO_TAG(PB8),
.echoIO = IO_TAG(PB9),
};
static const sonarHardware_t sonarRC78 = {
.trigger_pin = Pin_0, // RX7 (PB0) - only 3.3v ( add a 1K Ohms resistor )
.trigger_gpio = GPIOB,
.echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
.echo_gpio = GPIOB,
.exti_line = EXTI_Line1,
.exti_pin_source = GPIO_PinSource1,
.exti_irqn = EXTI1_IRQn
.triggerIO = IO_TAG(PB0),
.echoIO = IO_TAG(PB1),
};
// If we are using softserial, parallel PWM or ADC current sensor, then use motor pins 5 and 6 for sonar, otherwise use rc pins 7 and 8
if (feature(FEATURE_SOFTSERIAL)
@ -84,9 +82,8 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
.trigger_gpio = GPIOB,
.echo_pin = Pin_1, // RX8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
.echo_gpio = GPIOB,
.exti_line = EXTI_Line1,
.exti_pin_source = GPIO_PinSource1,
.exti_irqn = EXTI1_IRQn
.triggerIO = IO_TAG(PB0),
.echoIO = IO_TAG(PB1),
};
return &sonarHardware;
#elif defined(CC3D)
@ -96,9 +93,8 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
.trigger_gpio = GPIOB,
.echo_pin = Pin_0, // (PB0) - only 3.3v ( add a 1K Ohms resistor )
.echo_gpio = GPIOB,
.exti_line = EXTI_Line0,
.exti_pin_source = GPIO_PinSource0,
.exti_irqn = EXTI0_IRQn
.triggerIO = IO_TAG(PB5),
.echoIO = IO_TAG(PB0),
};
return &sonarHardware;
#elif defined(SPRACINGF3) || defined(SPRACINGF3MINI)
@ -108,9 +104,8 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
.trigger_gpio = GPIOB,
.echo_pin = Pin_1, // RC_CH8 (PB1) - only 3.3v ( add a 1K Ohms resistor )
.echo_gpio = GPIOB,
.exti_line = EXTI_Line1,
.exti_pin_source = EXTI_PinSource1,
.exti_irqn = EXTI1_IRQn
.triggerIO = IO_TAG(PB0),
.echoIO = IO_TAG(PB1),
};
return &sonarHardware;
#elif defined(SPARKY)
@ -120,9 +115,8 @@ const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryCon
.trigger_gpio = GPIOA,
.echo_pin = Pin_1, // PWM7 (PB1) - only 3.3v ( add a 1K Ohms resistor )
.echo_gpio = GPIOB,
.exti_line = EXTI_Line1,
.exti_pin_source = EXTI_PinSource1,
.exti_irqn = EXTI1_IRQn
.triggerIO = IO_TAG(PA2),
.echoIO = IO_TAG(PB1),
};
return &sonarHardware;
#elif defined(UNIT_TEST)

View File

@ -20,11 +20,10 @@
#include <stdlib.h>
#include "platform.h"
#include "build_config.h"
#include "drivers/system.h"
#include "drivers/gpio.h"
#include "drivers/io.h"
#include "hardware_revision.h"
@ -36,15 +35,18 @@ static const char * const hardwareRevisionNames[] = {
uint8_t hardwareRevision = UNKNOWN;
static IO_t HWDetectPin = IO_NONE;
void detectHardwareRevision(void)
{
gpio_config_t cfg = {HW_PIN, Mode_IPU, Speed_2MHz};
RCC_AHBPeriphClockCmd(HW_PERIPHERAL, ENABLE);
gpioInit(HW_GPIO, &cfg);
HWDetectPin = IOGetByTag(IO_TAG(HW_PIN));
IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT);
IOConfigGPIO(HWDetectPin, IOCFG_IPU);
// Check hardware revision
delayMicroseconds(10); // allow configuration to settle
if (digitalIn(HW_GPIO, HW_PIN)) {
if (IORead(HWDetectPin)) {
hardwareRevision = AFF3_REV_1;
} else {
hardwareRevision = AFF3_REV_2;

View File

@ -19,35 +19,23 @@
#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
#define USE_HARDWARE_REVISION_DETECTION
#define HW_GPIO GPIOB
#define HW_PIN Pin_2
#define HW_PERIPHERAL RCC_AHBPeriph_GPIOB
#define HW_PIN PB2
// LED's V1
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_4 // Blue LEDs - PB4
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_5 // Green LEDs - PB5
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB4 // LED - PB4
#define LED1 PB5 // LED - PB5
// LED's V2
#define LED0_GPIO_2 GPIOB
#define LED0_PIN_2 Pin_8 // Blue LEDs - PB8
#define LED0_PERIPHERAL_2 RCC_AHBPeriph_GPIOB
#define LED1_GPIO_2 GPIOB
#define LED1_PIN_2 Pin_9 // Green LEDs - PB9
#define LED1_PERIPHERAL_2 RCC_AHBPeriph_GPIOB
#define LED0_A PB8 // LED - PB8
#define LED1_A PB9 // LED - PB9
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_5 // White LEDs - PA5
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
#define BEEPER PA5 // LED - PA5
#define USABLE_TIMER_CHANNEL_COUNT 11
#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_EXTI
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
@ -78,10 +66,6 @@
#define MAG_AK8963_ALIGN CW0_DEG_FLIP
#define BEEPER
#define LED0
#define LED1
#define USE_VCP
#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
#define USE_USART2 // Receiver - RX (PA3)
@ -113,16 +97,8 @@
#define USE_I2C
#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
#define I2C2_SCL_GPIO GPIOA
#define I2C2_SCL_GPIO_AF GPIO_AF_4
#define I2C2_SCL_PIN GPIO_Pin_9
#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9
#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SDA_GPIO GPIOA
#define I2C2_SDA_GPIO_AF GPIO_AF_4
#define I2C2_SDA_PIN GPIO_Pin_10
#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10
#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA
#define I2C2_SCL_PIN PA9
#define I2C2_SDA_PIN PA10
// SPI3
// PA15 38 SPI3_NSS
@ -133,9 +109,7 @@
#define USE_SPI
#define USE_SPI_DEVICE_3
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
#define MPU6500_CS_GPIO GPIOA
#define MPU6500_CS_PIN GPIO_Pin_15
#define MPU6500_CS_PIN PA15
#define MPU6500_SPI_INSTANCE SPI3
#define USE_ADC
@ -160,20 +134,18 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
// alternative defaults for AlienFlight F3 target
#define ALIENFLIGHT
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB12 (Pin 25)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_12
#define BINDPLUG_PIN PB12
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -17,20 +17,17 @@
#define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED0
#define LED0 PB3 // PB3 (LED)
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_GPIO GPIOB
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO
#define INVERTER_USART USART1
#define BEEPER PB15 // PB15 (Beeper)
#define BEEPER_OPT PB2 // PB15 (Beeper)
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_15 // PA15 (Beeper)
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
#define USE_EXTI
#define USE_MPU_DATA_READY_SIGNAL
#define MPU_INT_EXTI PA3
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN GPIO_Pin_4
@ -115,13 +112,10 @@
#define SPEKTRUM_BIND
// USART3, PB11 (Flexport)
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define INVERTER
#define BEEPER
#define DISPLAY
#define BLACKBOX
#define TELEMETRY
@ -144,4 +138,4 @@
// IO - from schematics
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(14))
#define TARGET_IO_PORTC (BIT(14))

View File

@ -19,18 +19,12 @@
#define TARGET_BOARD_IDENTIFIER "CHF3" // Chebuzz F3
#define LED0_GPIO GPIOE
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED0 PE8 // Blue LEDs - PE8/PE12
#define LED0_INVERTED
#define LED1_GPIO GPIOE
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED1 PE10 // Orange LEDs - PE10/PE14
#define LED1_INVERTED
#define BEEP_GPIO GPIOE
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
#define BEEPER PE9 // Red LEDs - PE9/PE13
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 18
@ -39,30 +33,16 @@
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN Pin_14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
#define SPI2_MOSI_PIN Pin_15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_PIN GPIO_Pin_14
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SDCARD_DETECT_GPIO_PORT GPIOC
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
@ -107,10 +87,6 @@
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define BEEPER
#define LED0
#define LED1
#define USE_VCP
#define USE_USART1
#define USE_USART2
@ -142,36 +118,18 @@
#define EXTERNAL1_ADC_CHANNEL ADC_Channel_9
#define GPS
#define LED_STRIP
#if 1
#define LED_STRIP_TIMER TIM16
#else
// alternative LED strip configuration, tested working.
#define LED_STRIP_TIMER TIM1
#define USE_LED_STRIP_ON_DMA1_CHANNEL2
#define WS2811_GPIO GPIOA
#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
#define WS2811_GPIO_AF GPIO_AF_6
#define WS2811_PIN GPIO_Pin_8
#define WS2811_PIN_SOURCE GPIO_PinSource8
#define WS2811_TIMER TIM1
#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1
#define WS2811_DMA_CHANNEL DMA1_Channel2
#define WS2811_IRQ DMA1_Channel2_IRQn
#endif
#define BLACKBOX
#define GTUNE
//#define GTUNE
#define TELEMETRY
#define SERIAL_RX
#define USE_SERVOS
#define USE_CLI
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -20,19 +20,9 @@
#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
#define USE_HARDWARE_REVISION_DETECTION
#define LED0_GPIO GPIOC
#define LED0_PIN Pin_14 // PC14 (LED)
#define LED0
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_13 // PC13 (LED)
#define LED1
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED2_GPIO GPIOC
#define LED2_PIN Pin_15 // PC15 (LED)
#define LED2
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOC
#define LED0 PC14 // PC14 (LED)
#define LED1 PC13 // PC13 (LED)
#define LED2 PC15 // PC15 (LED)
#define ACC
#define USE_ACC_MPU6050
@ -63,8 +53,7 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
#define USE_QUAD_MIXER_ONLY
@ -84,4 +73,4 @@
// IO - assuming all IOs on 48pin package TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))

View File

@ -21,44 +21,26 @@
#define BST_DEVICE_NAME "COLIBRI RACE"
#define BST_DEVICE_NAME_LENGTH 12
#define LED0_GPIO GPIOC
#define LED0_PIN Pin_15
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOC
#define LED2_GPIO GPIOC
#define LED2_PIN Pin_13
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEP_GPIO GPIOB
#define BEEP_PIN Pin_13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEPER PB13
#define BEEPER_INVERTED
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
#define MPU6500_CS_GPIO GPIOA
#define MPU6500_CS_PIN GPIO_Pin_4
#define USE_EXTI
#define MPU6500_CS_PIN PA4
#define MPU6500_SPI_INSTANCE SPI1
#define MPU6000_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
#define MPU6000_CS_GPIO GPIOA
#define MPU6000_CS_PIN GPIO_Pin_4
#define MPU6000_CS_PIN PA4
#define MPU6000_SPI_INSTANCE SPI1
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_GPIO GPIOB
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI1_SCK_PIN GPIO_Pin_3
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI1_MISO_PIN GPIO_Pin_4
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI1_MOSI_PIN GPIO_Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -87,11 +69,6 @@
#define USE_MAG_AK8963
#define USE_MAG_AK8975
#define BEEPER
#define LED0
#define LED1
#define LED2
#define USB_IO
#define USE_VCP
@ -184,6 +161,8 @@
// MPU6500 interrupt
#define USE_EXTI
#define MPU_INT_EXTI PA5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -200,4 +179,4 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -20,23 +20,15 @@
#define TARGET_BOARD_IDENTIFIER "DOGE"
// tqfp48 pin 34
#define LED0_GPIO GPIOA
#define LED0_PIN Pin_13
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOA
#define LED0 PA13
// tqfp48 pin 37
#define LED1_GPIO GPIOA
#define LED1_PIN Pin_14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOA
#define LED1 PA14
// tqfp48 pin 38
#define LED2_GPIO GPIOA
#define LED2_PIN Pin_15
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOA
#define LED2 Pa15
#define BEEP_GPIO GPIOB
#define BEEP_PIN Pin_2
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEPER PB2
#define BEEPER_INVERTED
// tqfp48 pin 3
@ -103,11 +95,6 @@
#define USE_BARO_BMP280
#define USE_BARO_SPI_BMP280
#define BEEPER
#define LED0
#define LED1
#define LED2
#define USB_IO
#define USE_VCP
#define USE_USART1
@ -160,6 +147,8 @@
#define CURRENT_METER_ADC_CHANNEL ADC_Channel_2
// mpu_int definition in sensors/initialisation.c
#define USE_EXTI
#define MPU_INT_EXTI PC13
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -193,7 +182,6 @@
#define SPEKTRUM_BIND
// Use UART3 for speksat
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -19,18 +19,13 @@
#define TARGET_BOARD_IDENTIFIER "EUF1"
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_4 // PB4 (LED)
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_GPIO GPIOB
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_EXTI
#define MPU6000_CS_GPIO GPIOB
#define MPU6000_CS_PIN GPIO_Pin_12
#define MPU6000_SPI_INSTANCE SPI2
@ -73,12 +68,8 @@
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define SONAR
#define LED0
#define LED1
#define DISPLAY
#define INVERTER
#define USE_USART1
#define USE_USART2
@ -131,11 +122,10 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
// IO - stm32f103RCT6 in 64pin package (TODO)
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))

View File

@ -19,10 +19,7 @@
#define TARGET_BOARD_IDENTIFIER "IFF3"
#define LED0
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB3
#define USABLE_TIMER_CHANNEL_COUNT 17
@ -115,8 +112,7 @@
#define SPEKTRUM_BIND
// USART3,
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_BOOTLOADER
#define USE_SERIAL_4WAY_SK_BOOTLOADER
@ -140,4 +136,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))

View File

@ -20,21 +20,11 @@
#define TARGET_BOARD_IDENTIFIER "LUX"
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0_GPIO GPIOC
#define LED0_PIN Pin_15
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOC
#define LED0 PC15
#define LED1 PC14
#define LED2 PC13
#define LED1_GPIO GPIOC
#define LED1_PIN Pin_14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOC
#define LED2_GPIO GPIOC
#define LED2_PIN Pin_13
#define LED2_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEP_GPIO GPIOB
#define BEEP_PIN Pin_13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEPER PB13
#define BEEPER_INVERTED
#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA
@ -45,14 +35,9 @@
#define USE_SPI
#define USE_SPI_DEVICE_1
#define SPI1_GPIO GPIOB
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI1_SCK_PIN GPIO_Pin_3
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI1_MISO_PIN GPIO_Pin_4
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI1_MOSI_PIN GPIO_Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define USABLE_TIMER_CHANNEL_COUNT 11
@ -68,11 +53,6 @@
#define USE_ACC_SPI_MPU6500
#define ACC_MPU6500_ALIGN CW270_DEG
#define BEEPER
#define LED0
#define LED1
#define LED2
#define USB_IO
#define USE_VCP
@ -148,6 +128,8 @@
// MPU6500 interrupt
#define USE_EXTI
#define MPU_INT_EXTI PA5
//#define DEBUG_MPU_DATA_READY_INTERRUPT
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -159,8 +141,7 @@
#define SPEKTRUM_BIND
// USART1, PC5
#define BIND_PORT GPIOC
#define BIND_PIN Pin_5
#define BIND_PIN PC5
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
@ -169,4 +150,4 @@
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -20,22 +20,17 @@
#define TARGET_BOARD_IDENTIFIER "MOTO" // MotoLab
#define USE_CLI
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_5 // Blue LEDs - PB5
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_9 // Green LEDs - PB9
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB5 // Blue LEDs - PB5
//#define LED1 PB9 // Green LEDs - PB9
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_0
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
#define BEEPER PA0
#define BEEPER_INVERTED
#define BEEPER
#define USABLE_TIMER_CHANNEL_COUNT 9
// MPU6050 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
//#define ENSURE_MPU_DATA_READY_IS_LOW
@ -65,8 +60,6 @@
//#define MAG
//#define USE_MAG_HMC5883
#define LED0
#define USE_VCP
#define USE_USART1
#define USE_USART2
@ -185,8 +178,7 @@
#define SPEKTRUM_BIND
// USART2, PB4
#define BIND_PORT GPIOB
#define BIND_PIN Pin_4
#define BIND_PIN PB4
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
@ -194,4 +186,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))

View File

@ -52,8 +52,8 @@ void detectHardwareRevision(void)
#ifdef USE_SPI
#define DISABLE_SPI_CS GPIO_SetBits(NAZE_SPI_CS_GPIO, NAZE_SPI_CS_PIN)
#define ENABLE_SPI_CS GPIO_ResetBits(NAZE_SPI_CS_GPIO, NAZE_SPI_CS_PIN)
#define DISABLE_SPI_CS IOLo(nazeSpiCsPin)
#define ENABLE_SPI_CS IOHi(nazeSpiCsPin)
#define SPI_DEVICE_NONE (0)
#define SPI_DEVICE_FLASH (1)
@ -62,8 +62,14 @@ void detectHardwareRevision(void)
#define M25P16_INSTRUCTION_RDID 0x9F
#define FLASH_M25P16_ID (0x202015)
static IO_t nazeSpiCsPin = IO_NONE;
uint8_t detectSpiDevice(void)
{
#ifdef NAZE_SPI_CS_PIN
nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN));
#endif
uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 };
uint8_t in[4];
uint32_t flash_id;

View File

@ -22,28 +22,19 @@
#define BOARD_HAS_VOLTAGE_DIVIDER
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_4 // PB4 (LED)
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_12 // PA12 (Beeper)
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
#define BEEPER PA12 // PA12 (Beeper)
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN Pin_13
#define BARO_EOC_GPIO GPIOC
#define BARO_EOC_PIN Pin_14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define BARO_XCLR_PIN PC13
#define BARO_EOC_PIN PC14
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_GPIO GPIOB
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_EXTI
// SPI2
// PB15 28 SPI2_MOSI
// PB14 27 SPI2_MISO
@ -55,7 +46,7 @@
#define NAZE_SPI_INSTANCE SPI2
#define NAZE_SPI_CS_GPIO GPIOB
#define NAZE_SPI_CS_PIN GPIO_Pin_12
#define NAZE_SPI_CS_PIN PB12
#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision:
@ -117,10 +108,6 @@
#define MAG_HMC5883_ALIGN CW180_DEG
#define SONAR
#define BEEPER
#define LED0
#define LED1
#define INVERTER
#define DISPLAY
#define USE_USART1
@ -185,24 +172,22 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
// alternative defaults for AlienWii32 F1 target
#ifdef ALIENWII32
#ifdef ALIENFLIGHT
#undef TARGET_BOARD_IDENTIFIER
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienWii32 F1.
#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienFlight F1.
#undef BOARD_HAS_VOLTAGE_DIVIDER
#define HARDWARE_BIND_PLUG
// Hardware bind plug at PB5 (Pin 41)
#define BINDPLUG_PORT GPIOB
#define BINDPLUG_PIN Pin_5
#define BINDPLUG_PIN PB5
#endif
// IO - assuming all IOs on 48pin package
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))

View File

@ -19,15 +19,8 @@
#pragma once
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEP_GPIO GPIOB
#define BEEP_PIN Pin_10
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOB
#define BEEPER
#define LED0
#define LED0 PB12
#define BEEPER PB10
#define GYRO
#define ACC
@ -50,12 +43,11 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
// IO - assuming 303 in 64pin package, TODO
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -23,18 +23,12 @@
//#define OLIMEXINO_UNCUT_LED2_E_JUMPER
#ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER
#define LED0_GPIO GPIOA
#define LED0_PIN Pin_5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOA
#define LED0
#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green
#endif
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit()
#define LED1_GPIO GPIOA
#define LED1_PIN Pin_1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOA
#define LED1
#define LED1 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow
#endif
#define GYRO
@ -118,4 +112,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(2))
#define TARGET_IO_PORTD (BIT(2))

View File

@ -19,21 +19,11 @@
#define TARGET_BOARD_IDENTIFIER "103R"
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3 // PB3 (LED)
#define LED0_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED0 PB3 // PB3 (LED)
#define LED1 PB4 // PB4 (LED)
#define LED2 PD2 // PD2 (LED) - Labelled LED4
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_4 // PB4 (LED)
#define LED1_PERIPHERAL RCC_APB2Periph_GPIOB
#define LED2_GPIO GPIOD
#define LED2_PIN Pin_2 // PD2 (LED) - Labelled LED4
#define LED2_PERIPHERAL RCC_APB2Periph_GPIOD
#define BEEP_GPIO GPIOA
#define BEEP_PIN Pin_12 // PA12 (Beeper)
#define BEEP_PERIPHERAL RCC_APB2Periph_GPIOA
#define BEEPER PA12 // PA12 (Beeper)
#define BARO_XCLR_GPIO GPIOC
#define BARO_XCLR_PIN Pin_13
@ -41,9 +31,7 @@
#define BARO_EOC_PIN Pin_14
#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC
#define INVERTER_PIN Pin_2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_GPIO GPIOB
#define INVERTER_PERIPHERAL RCC_APB2Periph_GPIOB
#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO
#define INVERTER_USART USART2
#define USE_SPI
@ -99,11 +87,6 @@
#define USE_FLASH_M25P16
#define SONAR
#define BEEPER
#define LED0
#define LED1
#define LED2
#define INVERTER
#define DISPLAY
#define USE_USART1
@ -163,4 +146,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))
#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2))

View File

@ -19,13 +19,9 @@
#define TARGET_BOARD_IDENTIFIER "RMDO" // Ready Made RC DoDo
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB3
#define BEEP_GPIO GPIOC
#define BEEP_PIN Pin_15
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
@ -54,8 +50,6 @@
#define USE_FLASH_M25P16
#define SONAR
#define BEEPER
#define LED0
#define USE_USART1
#define USE_USART2
@ -151,8 +145,7 @@
#define SPEKTRUM_BIND
// USART3,
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -19,16 +19,14 @@
#define TARGET_BOARD_IDENTIFIER "SING"
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB3
#define BEEP_GPIO GPIOC
#define BEEP_PIN Pin_15
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEPER PC15
#define USABLE_TIMER_CHANNEL_COUNT 10
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define GYRO
@ -42,9 +40,6 @@
#define USE_FLASHFS
#define USE_FLASH_M25P16
#define BEEPER
#define LED0
#define USE_VCP
#define USE_USART1 // JST-SH Serial - TX (PA9) RX (PA10)
#define USE_USART2 // Input - TX (NC) RX (PA15)
@ -130,8 +125,7 @@
#define SPEKTRUM_BIND
// USART2, PA15
#define BIND_PORT GPIOA
#define BIND_PIN Pin_15
#define BIND_PIN PA15
#define USE_SERIAL_4WAY_BLHELI_INTERFACE

View File

@ -19,22 +19,17 @@
#define TARGET_BOARD_IDENTIFIER "SPKY" // SParKY
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_4 // Blue (Rev 1 & 2) - PB4
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED1_GPIO GPIOB
#define LED1_PIN Pin_5 // Green (Rev 1) / Red (Rev 2) - PB5
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB4 // Blue (Rev 1 & 2) - PB4
#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5
#define BEEP_GPIO GPIOA //USE PWM10 as beeper signal
#define BEEP_PIN Pin_1
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOA
#define BEEPER PA1
#define BEEPER_INVERTED
#define BEEPER
#define USABLE_TIMER_CHANNEL_COUNT 11
// MPU6050 interrupts
#define USE_EXTI
#define MPU_INT_EXTI PA15
#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
#define USE_MPU_DATA_READY_SIGNAL
@ -58,9 +53,6 @@
#define MAG_AK8975_ALIGN CW180_DEG_FLIP
#define LED0
#define LED1
#define USE_VCP
#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7)
#define USE_USART2 // Input - RX (PA3)
@ -167,8 +159,7 @@
#define SPEKTRUM_BIND
// USART2, PA3
#define BIND_PORT GPIOA
#define BIND_PIN Pin_3
#define BIND_PIN PA3
// available IO pins (from schematics)

View File

@ -19,19 +19,17 @@
#define TARGET_BOARD_IDENTIFIER "SRF3"
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB3
#define BEEP_GPIO GPIOC
#define BEEP_PIN Pin_15
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 17
#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready and MAG data ready
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -61,8 +59,6 @@
#define USE_FLASH_M25P16
#define SONAR
#define BEEPER
#define LED0
#define USE_USART1
#define USE_USART2
@ -160,8 +156,7 @@
#define SPEKTRUM_BIND
// USART3,
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
@ -169,4 +164,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4))

View File

@ -19,19 +19,17 @@
#define TARGET_BOARD_IDENTIFIER "SPEV"
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_8
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB8
#define BEEP_GPIO GPIOC
#define BEEP_PIN Pin_15
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -61,8 +59,6 @@
//#define MAG_AK8963_ALIGN CW90_DEG_FLIP
//#define SONAR
#define BEEPER
#define LED0
#define USB_IO
@ -104,43 +100,23 @@
#define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU)
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 SPI2 (SDCard)
#define SPI1_GPIO GPIOB
#define SPI1_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI1_NSS_PIN Pin_9
#define SPI1_NSS_PIN_SOURCE GPIO_PinSource9
#define SPI1_SCK_PIN Pin_3
#define SPI1_SCK_PIN_SOURCE GPIO_PinSource3
#define SPI1_MISO_PIN Pin_4
#define SPI1_MISO_PIN_SOURCE GPIO_PinSource4
#define SPI1_MOSI_PIN Pin_5
#define SPI1_MOSI_PIN_SOURCE GPIO_PinSource5
#define SPI1_NSS_PIN PB9
#define SPI1_SCK_PIN PB3
#define SPI1_MISO_PIN PB4
#define SPI1_MOSI_PIN PB5
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN Pin_14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
#define SPI2_MOSI_PIN Pin_15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN GPIO_Pin_14
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SDCARD_DETECT_GPIO_PORT GPIOC
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
@ -152,9 +128,7 @@
#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5
#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5
#define MPU6500_CS_GPIO_CLK_PERIPHERAL SPI1_GPIO_PERIPHERAL
#define MPU6500_CS_GPIO SPI1_GPIO
#define MPU6500_CS_PIN GPIO_Pin_9
#define MPU6500_CS_PIN PB9
#define MPU6500_SPI_INSTANCE SPI1
#define USE_ADC
@ -219,8 +193,7 @@
#define SPEKTRUM_BIND
// USART3,
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
@ -228,4 +201,4 @@
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -22,19 +22,17 @@
// early prototype had slightly different pin mappings.
//#define SPRACINGF3MINI_MKII_REVA
#define LED0_GPIO GPIOB
#define LED0_PIN Pin_3
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOB
#define LED0 PB3
#define BEEP_GPIO GPIOC
#define BEEP_PIN Pin_15
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOC
#define BEEPER PC15
#define BEEPER_INVERTED
#define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins.
#define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect
#define USE_EXTI
#define MPU_INT_EXTI PC13
#define USE_MPU_DATA_READY_SIGNAL
#define ENSURE_MPU_DATA_READY_IS_LOW
@ -64,15 +62,11 @@
#define MAG_AK8975_ALIGN CW90_DEG_FLIP
#define SONAR
#define BEEPER
#define LED0
#define USB_IO
#define USB_CABLE_DETECTION
#define USB_DETECT_PIN GPIO_Pin_5
#define USB_DETECT_GPIO_PORT GPIOB
#define USB_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define USB_DETECT_PIN PB5
#define USE_VCP
#define USE_USART1
@ -116,32 +110,18 @@
#define USE_SPI
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
#define SPI2_GPIO GPIOB
#define SPI2_GPIO_PERIPHERAL RCC_AHBPeriph_GPIOB
#define SPI2_NSS_PIN Pin_12
#define SPI2_NSS_PIN_SOURCE GPIO_PinSource12
#define SPI2_SCK_PIN Pin_13
#define SPI2_SCK_PIN_SOURCE GPIO_PinSource13
#define SPI2_MISO_PIN Pin_14
#define SPI2_MISO_PIN_SOURCE GPIO_PinSource14
#define SPI2_MOSI_PIN Pin_15
#define SPI2_MOSI_PIN_SOURCE GPIO_PinSource15
#define SPI2_NSS_PIN PB12
#define SPI2_SCK_PIN PB13
#define SPI2_MISO_PIN PB14
#define SPI2_MOSI_PIN PB15
#define USE_SDCARD
#define USE_SDCARD_SPI2
#define SDCARD_DETECT_INVERTED
#define SDCARD_DETECT_PIN GPIO_Pin_14
#define SDCARD_DETECT_EXTI_LINE EXTI_Line14
#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SDCARD_DETECT_GPIO_PORT GPIOC
#define SDCARD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SDCARD_DETECT_PIN PC14
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO SPI2_GPIO
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
@ -225,16 +205,14 @@
#define SPEKTRUM_BIND
// USART3,
#define BIND_PORT GPIOB
#define BIND_PIN Pin_11
#define BIND_PIN PB11
#define HARDWARE_BIND_PLUG
#define BINDPLUG_PORT BUTTON_B_PORT
#define BINDPLUG_PIN BUTTON_B_PIN
#define BINDPLUG_PIN PB0
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
#define TARGET_IO_PORTA 0xffff
#define TARGET_IO_PORTB 0xffff
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))

View File

@ -19,21 +19,12 @@
#define TARGET_BOARD_IDENTIFIER "SDF3" // STM Discovery F3
#define LED0_GPIO GPIOE
#define LED0_PIN Pin_8|Pin_12 // Blue LEDs - PE8/PE12
#define LED0_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED0 PE8 // Blue LEDs - PE8/PE12
#define LED0_INVERTED
#define LED1_GPIO GPIOE
#define LED1_PIN Pin_10|Pin_14 // Orange LEDs - PE10/PE14
#define LED1_PERIPHERAL RCC_AHBPeriph_GPIOE
#define LED1 PE10 // Orange LEDs - PE10/PE14
#define LED1_INVERTED
#define BEEP_GPIO GPIOE
#define BEEP_PIN Pin_9|Pin_13 // Red LEDs - PE9/PE13
#define BEEP_PERIPHERAL RCC_AHBPeriph_GPIOE
#define BEEPER_INVERTED
#define BEEPER PE9 // Red LEDs - PE9/PE13
#define BEEPER_INVERTED
#define USE_SPI
@ -53,16 +44,8 @@
#define USE_SD_CARD
#define SD_DETECT_PIN GPIO_Pin_14
#define SD_DETECT_EXTI_LINE EXTI_Line14
#define SD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource14
#define SD_DETECT_GPIO_PORT GPIOC
#define SD_DETECT_GPIO_CLK RCC_AHBPeriph_GPIOC
#define SD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
#define SD_DETECT_EXTI_IRQn EXTI15_10_IRQn
#define SD_CS_GPIO GPIOB
#define SD_CS_PIN GPIO_Pin_12
#define SD_DETECT_PIN PC14
#define SD_CS_PIN PB12
#define SD_SPI_INSTANCE SPI2
//#define USE_FLASHFS
@ -87,9 +70,7 @@
#define USE_GYRO_L3GD20
#define L3GD20_SPI SPI1
#define L3GD20_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOE
#define L3GD20_CS_GPIO GPIOE
#define L3GD20_CS_PIN GPIO_Pin_3
#define L3GD20_CS_PIN PE3
#define GYRO_L3GD20_ALIGN CW270_DEG
@ -97,9 +78,7 @@
#define USE_SDCARD_SPI2
#define SDCARD_SPI_INSTANCE SPI2
#define SDCARD_SPI_CS_GPIO GPIOB
#define SDCARD_SPI_CS_PIN GPIO_Pin_12
#define SDCARD_SPI_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB
#define SDCARD_SPI_CS_PIN PB12
// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init:
#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128
// Divide to under 25MHz for normal operation:
@ -118,10 +97,6 @@
#define MAG
#define USE_MAG_HMC5883
#define BEEPER
#define LED0
#define LED1
#define USE_VCP
#define USE_USART1
#define USE_USART2
@ -184,4 +159,4 @@
#define TARGET_IO_PORTC 0xffff
#define TARGET_IO_PORTD 0xffff
#define TARGET_IO_PORTE 0xffff
#define TARGET_IO_PORTF 0x00ff
#define TARGET_IO_PORTF 0x00ff