diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c
index cea7f46120..bfe63dbddc 100644
--- a/src/main/drivers/accgyro_mpu.c
+++ b/src/main/drivers/accgyro_mpu.c
@@ -41,6 +41,7 @@
#include "accgyro_mpu6500.h"
#include "accgyro_spi_mpu6000.h"
#include "accgyro_spi_mpu6500.h"
+#include "accgyro_spi_mpu9250.h"
#include "accgyro_mpu.h"
//#define DEBUG_MPU_DATA_READY_INTERRUPT
@@ -89,6 +90,7 @@ mpuDetectionResult_t *detectMpu(const extiConfig_t *configToUse)
#ifndef USE_I2C
ack = false;
+ sig = 0;
#else
ack = mpuReadRegisterI2C(MPU_RA_WHO_AM_I, 1, &sig);
#endif
@@ -152,6 +154,19 @@ static bool detectSPISensorsAndUpdateDetectionResult(void)
}
#endif
+#ifdef USE_GYRO_SPI_MPU9250
+ if (mpu9250SpiDetect()) {
+ mpuDetectionResult.sensor = MPU_9250_SPI;
+ mpuConfiguration.gyroReadXRegister = MPU_RA_GYRO_XOUT_H;
+ mpuConfiguration.read = mpu9250ReadRegister;
+ mpuConfiguration.slowread = mpu9250SlowReadRegister;
+ mpuConfiguration.verifywrite = verifympu9250WriteRegister;
+ mpuConfiguration.write = mpu9250WriteRegister;
+ mpuConfiguration.reset = mpu9250ResetGyro;
+ return true;
+ }
+#endif
+
return false;
}
#endif
diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h
index 516d620f42..6dbfcebf6c 100644
--- a/src/main/drivers/accgyro_mpu.h
+++ b/src/main/drivers/accgyro_mpu.h
@@ -137,11 +137,19 @@ enum gyro_fsr_e {
INV_FSR_2000DPS,
NUM_GYRO_FSR
};
+
+enum fchoice_b {
+ FCB_DISABLED = 0,
+ FCB_8800_32,
+ FCB_3600_32
+};
+
enum clock_sel_e {
INV_CLK_INTERNAL = 0,
INV_CLK_PLL,
NUM_CLK
};
+
enum accel_fsr_e {
INV_FSR_2G = 0,
INV_FSR_4G,
@@ -156,7 +164,8 @@ typedef enum {
MPU_60x0,
MPU_60x0_SPI,
MPU_65xx_I2C,
- MPU_65xx_SPI
+ MPU_65xx_SPI,
+ MPU_9250_SPI
} detectedMPUSensor_e;
typedef enum {
diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c
new file mode 100644
index 0000000000..72248c30a9
--- /dev/null
+++ b/src/main/drivers/accgyro_spi_mpu9250.c
@@ -0,0 +1,239 @@
+/*
+ * 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 .
+ */
+
+
+/*
+ * Authors:
+ * Dominic Clifton - Cleanflight implementation
+ * John Ihlein - Initial FF32 code
+ * Kalyn Doerr (RS2K) - Robust rewrite
+*/
+
+#include
+#include
+#include
+
+#include "platform.h"
+#include "light_led.h"
+
+#include "common/axis.h"
+#include "common/maths.h"
+
+#include "io.h"
+
+#include "system.h"
+#include "exti.h"
+#include "bus_spi.h"
+#include "gyro_sync.h"
+#include "debug.h"
+
+#include "sensor.h"
+#include "accgyro.h"
+#include "accgyro_mpu.h"
+#include "accgyro_spi_mpu9250.h"
+
+static void mpu9250AccAndGyroInit(uint8_t lpf);
+
+static bool mpuSpi9250InitDone = false;
+
+static IO_t mpuSpi9250CsPin = IO_NONE;
+
+#define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin)
+#define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin)
+
+void mpu9250ResetGyro(void) {
+ // Device Reset
+ mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
+ delay(150);
+}
+
+bool mpu9250WriteRegister(uint8_t reg, uint8_t data)
+{
+ ENABLE_MPU9250;
+ delayMicroseconds(1);
+ spiTransferByte(MPU9250_SPI_INSTANCE, reg);
+ spiTransferByte(MPU9250_SPI_INSTANCE, data);
+ DISABLE_MPU9250;
+ delayMicroseconds(1);
+
+ return true;
+}
+
+bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
+{
+ ENABLE_MPU9250;
+ spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
+ spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
+ DISABLE_MPU9250;
+
+ return true;
+}
+
+bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data)
+{
+ ENABLE_MPU9250;
+ delayMicroseconds(1);
+ spiTransferByte(MPU9250_SPI_INSTANCE, reg | 0x80); // read transaction
+ spiTransfer(MPU9250_SPI_INSTANCE, data, NULL, length);
+ DISABLE_MPU9250;
+ delayMicroseconds(1);
+
+ return true;
+}
+
+void mpu9250SpiGyroInit(uint8_t lpf)
+{
+ (void)(lpf);
+
+ mpuIntExtiInit();
+
+ mpu9250AccAndGyroInit(lpf);
+
+ spiResetErrorCounter(MPU9250_SPI_INSTANCE);
+
+ spiSetDivisor(MPU9250_SPI_INSTANCE, 5); //high speed now that we don't need to write to the slow registers
+
+ int16_t data[3];
+ mpuGyroRead(data);
+
+ if ((((int8_t)data[1]) == -1 && ((int8_t)data[0]) == -1) || spiGetErrorCounter(MPU9250_SPI_INSTANCE) != 0) {
+ spiResetErrorCounter(MPU9250_SPI_INSTANCE);
+ failureMode(FAILURE_GYRO_INIT_FAILED);
+ }
+}
+
+void mpu9250SpiAccInit(void)
+{
+ mpuIntExtiInit();
+
+ acc_1G = 512 * 8;
+}
+
+
+bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) {
+
+ uint8_t in;
+ uint8_t attemptsRemaining = 20;
+
+ mpu9250WriteRegister(reg, data);
+ delayMicroseconds(100);
+
+ do {
+ mpu9250SlowReadRegister(reg, 1, &in);
+ if (in == data) {
+ return true;
+ } else {
+ debug[3]++;
+ mpu9250WriteRegister(reg, data);
+ delayMicroseconds(100);
+ }
+ } while (attemptsRemaining--);
+ return false;
+}
+
+static void mpu9250AccAndGyroInit(uint8_t lpf) {
+
+ if (mpuSpi9250InitDone) {
+ return;
+ }
+
+ spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed for writing to slow registers
+
+ mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
+ delay(50);
+
+ verifympu9250WriteRegister(MPU_RA_PWR_MGMT_1, INV_CLK_PLL);
+
+ verifympu9250WriteRegister(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3 | FCB_DISABLED); //Fchoice_b defaults to 00 which makes fchoice 11
+
+ if (lpf == 4) {
+ verifympu9250WriteRegister(MPU_RA_CONFIG, 1); //1KHz, 184DLPF
+ } else if (lpf < 4) {
+ verifympu9250WriteRegister(MPU_RA_CONFIG, 7); //8KHz, 3600DLPF
+ } else if (lpf > 4) {
+ verifympu9250WriteRegister(MPU_RA_CONFIG, 0); //8KHz, 250DLPF
+ }
+
+ verifympu9250WriteRegister(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); // Get Divider Drops
+
+ verifympu9250WriteRegister(MPU_RA_ACCEL_CONFIG, INV_FSR_8G << 3);
+ verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0 << 7 | 0 << 6 | 0 << 5 | 1 << 4 | 0 << 3 | 0 << 2 | 1 << 1 | 0 << 0); // INT_ANYRD_2CLEAR, BYPASS_EN
+
+#if defined(USE_MPU_DATA_READY_SIGNAL)
+ verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly.
+#endif
+
+ mpuSpi9250InitDone = true; //init done
+}
+
+bool mpu9250SpiDetect(void)
+{
+ uint8_t in;
+ uint8_t attemptsRemaining = 20;
+
+ /* not the best place for this - should really have an init method */
+#ifdef MPU9250_CS_PIN
+ mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
+#endif
+ IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI);
+ IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
+
+ spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_SLOW_CLOCK); //low speed
+ mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET);
+
+ do {
+ delay(150);
+
+ mpu9250ReadRegister(MPU_RA_WHO_AM_I, 1, &in);
+ if (in == MPU9250_WHO_AM_I_CONST) {
+ break;
+ }
+ if (!attemptsRemaining) {
+ return false;
+ }
+ } while (attemptsRemaining--);
+
+ return true;
+}
+
+bool mpu9250SpiAccDetect(acc_t *acc)
+{
+ if (mpuDetectionResult.sensor != MPU_9250_SPI) {
+ return false;
+ }
+
+ acc->init = mpu9250SpiAccInit;
+ acc->read = mpuAccRead;
+
+ return true;
+}
+
+bool mpu9250SpiGyroDetect(gyro_t *gyro)
+{
+ if (mpuDetectionResult.sensor != MPU_9250_SPI) {
+ return false;
+ }
+
+ gyro->init = mpu9250SpiGyroInit;
+ gyro->read = mpuGyroRead;
+ gyro->intStatus = checkMPUDataReady;
+
+ // 16.4 dps/lsb scalefactor
+ gyro->scale = 1.0f / 16.4f;
+
+ return true;
+}
diff --git a/src/main/drivers/accgyro_spi_mpu9250.h b/src/main/drivers/accgyro_spi_mpu9250.h
new file mode 100644
index 0000000000..521cefdf28
--- /dev/null
+++ b/src/main/drivers/accgyro_spi_mpu9250.h
@@ -0,0 +1,36 @@
+
+#pragma once
+
+#define mpu9250_CONFIG 0x1A
+
+/* We should probably use these. :)
+#define BITS_DLPF_CFG_256HZ 0x00
+#define BITS_DLPF_CFG_188HZ 0x01
+#define BITS_DLPF_CFG_98HZ 0x02
+#define BITS_DLPF_CFG_42HZ 0x03
+#define BITS_DLPF_CFG_20HZ 0x04
+#define BITS_DLPF_CFG_10HZ 0x05
+#define BITS_DLPF_CFG_5HZ 0x06
+#define BITS_DLPF_CFG_2100HZ_NOLPF 0x07
+*/
+
+#define GYRO_SCALE_FACTOR 0.00053292f // (4/131) * pi/180 (32.75 LSB = 1 DPS)
+
+#define MPU9250_WHO_AM_I_CONST (0x71)
+
+#define MPU9250_BIT_RESET (0x80)
+
+// RF = Register Flag
+#define MPU_RF_DATA_RDY_EN (1 << 0)
+
+void mpu9250ResetGyro(void);
+
+bool mpu9250SpiDetect(void);
+
+bool mpu9250SpiAccDetect(acc_t *acc);
+bool mpu9250SpiGyroDetect(gyro_t *gyro);
+
+bool mpu9250WriteRegister(uint8_t reg, uint8_t data);
+bool verifympu9250WriteRegister(uint8_t reg, uint8_t data);
+bool mpu9250ReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
+bool mpu9250SlowReadRegister(uint8_t reg, uint8_t length, uint8_t *data);
diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c
new file mode 100644
index 0000000000..0d051fc118
--- /dev/null
+++ b/src/main/drivers/adc_stm32f4xx.c
@@ -0,0 +1,162 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+#include "system.h"
+
+#include "io.h"
+
+#include "sensors/sensors.h" // FIXME dependency into the main code
+
+#include "sensor.h"
+#include "accgyro.h"
+
+#include "adc.h"
+#include "adc_impl.h"
+
+void adcInit(drv_adc_config_t *init)
+{
+ ADC_InitTypeDef ADC_InitStructure;
+ DMA_InitTypeDef DMA_InitStructure;
+
+ uint8_t i;
+ uint8_t configuredAdcChannels = 0;
+
+ memset(&adcConfig, 0, sizeof(adcConfig));
+
+#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
+ UNUSED(init);
+#endif
+
+#ifdef VBAT_ADC_PIN
+ if (init->enableVBat) {
+ IOInit(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
+ IOConfigGPIO(IOGetByTag(IO_TAG(VBAT_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
+ adcConfig[ADC_BATTERY].adcChannel = VBAT_ADC_CHANNEL;
+ adcConfig[ADC_BATTERY].dmaIndex = configuredAdcChannels++;
+ adcConfig[ADC_BATTERY].enabled = true;
+ adcConfig[ADC_BATTERY].sampleTime = ADC_SampleTime_480Cycles;
+ }
+#endif
+
+#ifdef EXTERNAL1_ADC_PIN
+ if (init->enableExternal1) {
+ IOInit(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
+ IOConfigGPIO(IOGetByTag(IO_TAG(EXTERNAL1_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
+ adcConfig[ADC_EXTERNAL1].adcChannel = EXTERNAL1_ADC_CHANNEL;
+ adcConfig[ADC_EXTERNAL1].dmaIndex = configuredAdcChannels++;
+ adcConfig[ADC_EXTERNAL1].enabled = true;
+ adcConfig[ADC_EXTERNAL1].sampleTime = ADC_SampleTime_480Cycles;
+ }
+#endif
+
+#ifdef RSSI_ADC_PIN
+ if (init->enableRSSI) {
+ IOInit(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
+ IOConfigGPIO(IOGetByTag(IO_TAG(RSSI_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
+ adcConfig[ADC_RSSI].adcChannel = RSSI_ADC_CHANNEL;
+ adcConfig[ADC_RSSI].dmaIndex = configuredAdcChannels++;
+ adcConfig[ADC_RSSI].enabled = true;
+ adcConfig[ADC_RSSI].sampleTime = ADC_SampleTime_480Cycles;
+ }
+#endif
+
+#ifdef CURRENT_METER_ADC_PIN
+ if (init->enableCurrentMeter) {
+ IOInit(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), OWNER_SYSTEM, RESOURCE_ADC);
+ IOConfigGPIO(IOGetByTag(IO_TAG(CURRENT_METER_ADC_PIN)), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
+ adcConfig[ADC_CURRENT].adcChannel = CURRENT_METER_ADC_CHANNEL;
+ adcConfig[ADC_CURRENT].dmaIndex = configuredAdcChannels++;
+ adcConfig[ADC_CURRENT].enabled = true;
+ adcConfig[ADC_CURRENT].sampleTime = ADC_SampleTime_480Cycles;
+ }
+#endif
+
+ //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
+
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA2, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOC, ENABLE);
+ RCC_APB2PeriphClockCmd(RCC_APB2Periph_ADC1, ENABLE);
+
+ DMA_DeInit(DMA2_Stream4);
+
+ DMA_StructInit(&DMA_InitStructure);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&ADC1->DR;
+ DMA_InitStructure.DMA_Channel = DMA_Channel_0;
+ DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)adcValues;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
+ DMA_InitStructure.DMA_BufferSize = configuredAdcChannels;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = configuredAdcChannels > 1 ? DMA_MemoryInc_Enable : DMA_MemoryInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_HalfWord;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_High;
+ DMA_Init(DMA2_Stream4, &DMA_InitStructure);
+
+ DMA_Cmd(DMA2_Stream4, ENABLE);
+
+ // calibrate
+
+ /*
+ ADC_VoltageRegulatorCmd(ADC1, ENABLE);
+ delay(10);
+ ADC_SelectCalibrationMode(ADC1, ADC_CalibrationMode_Single);
+ ADC_StartCalibration(ADC1);
+ while(ADC_GetCalibrationStatus(ADC1) != RESET);
+ ADC_VoltageRegulatorCmd(ADC1, DISABLE);
+ */
+
+ ADC_CommonInitTypeDef ADC_CommonInitStructure;
+
+ ADC_CommonStructInit(&ADC_CommonInitStructure);
+ ADC_CommonInitStructure.ADC_Mode = ADC_Mode_Independent;
+ ADC_CommonInitStructure.ADC_Prescaler = ADC_Prescaler_Div8;
+ ADC_CommonInitStructure.ADC_DMAAccessMode = ADC_DMAAccessMode_Disabled;
+ ADC_CommonInitStructure.ADC_TwoSamplingDelay = ADC_TwoSamplingDelay_5Cycles;
+ ADC_CommonInit(&ADC_CommonInitStructure);
+
+ ADC_StructInit(&ADC_InitStructure);
+
+ ADC_InitStructure.ADC_ContinuousConvMode = ENABLE;
+ ADC_InitStructure.ADC_Resolution = ADC_Resolution_12b;
+ ADC_InitStructure.ADC_ExternalTrigConv = ADC_ExternalTrigConv_T1_CC1;
+ ADC_InitStructure.ADC_ExternalTrigConvEdge = ADC_ExternalTrigConvEdge_None;
+ ADC_InitStructure.ADC_DataAlign = ADC_DataAlign_Right;
+ ADC_InitStructure.ADC_NbrOfConversion = configuredAdcChannels;
+ ADC_InitStructure.ADC_ScanConvMode = configuredAdcChannels > 1 ? ENABLE : DISABLE; // 1=scan more that one channel in group
+
+ ADC_Init(ADC1, &ADC_InitStructure);
+
+ uint8_t rank = 1;
+ for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
+ if (!adcConfig[i].enabled) {
+ continue;
+ }
+ ADC_RegularChannelConfig(ADC1, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
+ }
+ ADC_DMARequestAfterLastTransferCmd(ADC1, ENABLE);
+
+ ADC_DMACmd(ADC1, ENABLE);
+ ADC_Cmd(ADC1, ENABLE);
+
+ ADC_SoftwareStartConv(ADC1);
+}
diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c
index d0dbcd8ae7..a444332aba 100644
--- a/src/main/drivers/bus_i2c_stm32f10x.c
+++ b/src/main/drivers/bus_i2c_stm32f10x.c
@@ -39,13 +39,23 @@ 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
-// I2C1
-// SCL PB6
-// SDA PB7
+#define GPIO_AF_I2C GPIO_AF_I2C1
+#ifdef STM32F4
+
+#if defined(USE_I2C_PULLUP)
+#define IOCFG_I2C IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_OD, GPIO_PuPd_UP)
+#else
+#define IOCFG_I2C IOCFG_AF_OD
+#endif
+
+#ifndef I2C1_SCL
+#define I2C1_SCL PB8
+#endif
+#ifndef I2C1_SDA
+#define I2C1_SDA PB9
+#endif
+#else
#ifndef I2C1_SCL
#define I2C1_SCL PB6
#endif
@@ -53,6 +63,8 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#define I2C1_SDA PB7
#endif
+#endif
+
#ifndef I2C2_SCL
#define I2C2_SCL PB10
#endif
@@ -60,6 +72,15 @@ static void i2cUnstick(IO_t scl, IO_t sda);
#define I2C2_SDA PB11
#endif
+#ifdef STM32F4
+#ifndef I2C3_SCL
+#define I2C3_SCL PA8
+#endif
+#ifndef I2C3_SDA
+#define I2C3_SDA PB4
+#endif
+#endif
+
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 },
diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c
index 9dc5c4dff9..5af40d0750 100644
--- a/src/main/drivers/bus_spi.c
+++ b/src/main/drivers/bus_spi.c
@@ -117,7 +117,7 @@ void spiInitDevice(SPIDevice device)
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 defined(STM32F303xC) || defined(STM32F4)
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);
@@ -161,7 +161,7 @@ void spiInitDevice(SPIDevice device)
}
#ifdef STM32F303xC
- // Configure for 8-bit reads.
+ // Configure for 8-bit reads.
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
#endif
@@ -193,7 +193,7 @@ bool spiInit(SPIDevice device)
break;
#endif
case SPIDEV_3:
-#if defined(USE_SPI_DEVICE_3) && (defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE))
+#if defined(USE_SPI_DEVICE_3) && (defined(STM32F303xC) || defined(STM32F4))
spiInitDevice(device);
return true;
#else
diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c
index a07858194d..726f4f85a1 100644
--- a/src/main/drivers/compass_ak8963.c
+++ b/src/main/drivers/compass_ak8963.c
@@ -95,7 +95,7 @@ ak8963Configuration_t ak8963config;
static float magGain[3] = { 1.0f, 1.0f, 1.0f };
// FIXME pretend we have real MPU9250 support
-#ifdef MPU6500_SPI_INSTANCE
+#if defined(MPU6500_SPI_INSTANCE) && !defined(MPU9250_SPI_INSTANCE)
#define MPU9250_SPI_INSTANCE
#define verifympu9250WriteRegister mpu6500WriteRegister
#define mpu9250WriteRegister mpu6500WriteRegister
diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h
index a4f324d5d3..9cb34c7665 100644
--- a/src/main/drivers/dma.h
+++ b/src/main/drivers/dma.h
@@ -15,6 +15,21 @@
* along with Cleanflight. If not, see .
*/
+#ifdef STM32F4
+typedef void(*dmaCallbackHandlerFuncPtr)(DMA_Stream_TypeDef *stream);
+
+typedef enum {
+ DMA1_ST2_HANDLER = 0,
+ DMA1_ST7_HANDLER,
+} dmaHandlerIdentifier_e;
+
+typedef struct dmaHandlers_s {
+ dmaCallbackHandlerFuncPtr dma1Stream2IRQHandler;
+ dmaCallbackHandlerFuncPtr dma1Stream7IRQHandler;
+} dmaHandlers_t;
+
+#else
+
typedef void (*dmaCallbackHandlerFuncPtr)(DMA_Channel_TypeDef *channel);
typedef enum {
@@ -30,6 +45,7 @@ typedef struct dmaHandlers_s {
dmaCallbackHandlerFuncPtr dma1Channel6IRQHandler;
dmaCallbackHandlerFuncPtr dma1Channel7IRQHandler;
} dmaHandlers_t;
+#endif
void dmaInit(void);
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback);
diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c
new file mode 100644
index 0000000000..6b49fe6299
--- /dev/null
+++ b/src/main/drivers/dma_stm32f4xx.c
@@ -0,0 +1,65 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include
+
+#include "build_config.h"
+
+#include "drivers/dma.h"
+
+/*
+ * DMA handlers for DMA resources that are shared between different features depending on run-time configuration.
+ */
+static dmaHandlers_t dmaHandlers;
+
+void dmaNoOpHandler(DMA_Stream_TypeDef *stream)
+{
+ UNUSED(stream);
+}
+
+void DMA1_Stream2_IRQHandler(void)
+{
+ dmaHandlers.dma1Stream2IRQHandler(DMA1_Stream2);
+}
+
+void DMA1_Stream7_IRQHandler(void)
+{
+ dmaHandlers.dma1Stream7IRQHandler(DMA1_Stream7);
+}
+
+void dmaInit(void)
+{
+ memset(&dmaHandlers, 0, sizeof(dmaHandlers));
+ dmaHandlers.dma1Stream2IRQHandler = dmaNoOpHandler;
+ dmaHandlers.dma1Stream7IRQHandler = dmaNoOpHandler;
+}
+
+void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback)
+{
+ switch (identifier) {
+ case DMA1_ST2_HANDLER:
+ dmaHandlers.dma1Stream2IRQHandler = callback;
+ break;
+ case DMA1_ST7_HANDLER:
+ dmaHandlers.dma1Stream7IRQHandler = callback;
+ break;
+ }
+}
diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c
index 400cdf4896..9940e0d2c6 100644
--- a/src/main/drivers/exti.c
+++ b/src/main/drivers/exti.c
@@ -4,9 +4,8 @@
#include "platform.h"
-#include "drivers/nvic.h"
-#include "drivers/io_impl.h"
-
+#include "nvic.h"
+#include "io_impl.h"
#include "exti.h"
#ifdef USE_EXTI
@@ -23,32 +22,38 @@ extiChannelRec_t extiChannelRecs[16];
static const uint8_t extiGroups[16] = { 0, 1, 2, 3, 4, 5, 5, 5, 5, 5, 6, 6, 6, 6, 6, 6 };
static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS];
-#if defined(STM32F10X)
+#if defined(STM32F1) || defined(STM32F4)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
- EXTI0_IRQn, EXTI1_IRQn, EXTI2_IRQn, EXTI3_IRQn, EXTI4_IRQn,
- EXTI9_5_IRQn, EXTI15_10_IRQn
+ EXTI0_IRQn,
+ EXTI1_IRQn,
+ EXTI2_IRQn,
+ EXTI3_IRQn,
+ EXTI4_IRQn,
+ EXTI9_5_IRQn,
+ EXTI15_10_IRQn
};
-#elif defined(STM32F303xC)
+#elif defined(STM32F3)
static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = {
- EXTI0_IRQn, EXTI1_IRQn, EXTI2_TS_IRQn, EXTI3_IRQn, EXTI4_IRQn,
- EXTI9_5_IRQn, EXTI15_10_IRQn
+ EXTI0_IRQn,
+ EXTI1_IRQn,
+ EXTI2_TS_IRQn,
+ EXTI3_IRQn,
+ EXTI4_IRQn,
+ EXTI9_5_IRQn,
+ EXTI15_10_IRQn
};
#else
# warning "Unknown CPU"
#endif
-
-
void EXTIInit(void)
{
- // TODO - stm32F303
-
-#ifdef STM32F10X
+#if defined(STM32F1)
// enable AFIO for EXTI support
RCC_APB2PeriphClockCmd(RCC_APB2Periph_AFIO, ENABLE);
#endif
-#ifdef STM32F303xC
+#if defined(STM32F3) || defined(STM32F4)
/* Enable SYSCFG clock otherwise the EXTI irq handlers are not called */
RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE);
#endif
@@ -75,6 +80,8 @@ void EXTIConfig(IO_t io, extiCallbackRec_t *cb, int irqPriority, EXTITrigger_Typ
GPIO_EXTILineConfig(IO_GPIO_PortSource(io), IO_GPIO_PinSource(io));
#elif defined(STM32F303xC)
SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
+#elif defined(STM32F4)
+ SYSCFG_EXTILineConfig(IO_EXTI_PortSourceGPIO(io), IO_EXTI_PinSource(io));
#else
# warning "Unknown CPU"
#endif
@@ -116,7 +123,7 @@ void EXTIRelease(IO_t io)
void EXTIEnable(IO_t io, bool enable)
{
-#if defined(STM32F10X)
+#if defined(STM32F1) || defined(STM32F4)
uint32_t extiLine = IO_EXTI_Line(io);
if(!extiLine)
return;
@@ -161,9 +168,9 @@ void EXTI_IRQHandler(void)
_EXTI_IRQ_HANDLER(EXTI0_IRQHandler);
_EXTI_IRQ_HANDLER(EXTI1_IRQHandler);
-#if defined(STM32F10X)
+#if defined(STM32F1)
_EXTI_IRQ_HANDLER(EXTI2_IRQHandler);
-#elif defined(STM32F303xC)
+#elif defined(STM32F3) || defined(STM32F4)
_EXTI_IRQ_HANDLER(EXTI2_TS_IRQHandler);
#else
# warning "Unknown CPU"
diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h
index b734de6477..8f3a32a59a 100644
--- a/src/main/drivers/gpio.h
+++ b/src/main/drivers/gpio.h
@@ -19,7 +19,7 @@
#include "platform.h"
-#if defined(STM32F10X)
+#ifdef STM32F1
typedef enum
{
Mode_AIN = 0x0,
@@ -33,31 +33,7 @@ typedef enum
} GPIO_Mode;
#endif
-#ifdef STM32F303xC
-
-/*
-typedef enum
-{
- GPIO_Mode_IN = 0x00, // GPIO Input Mode
- GPIO_Mode_OUT = 0x01, // GPIO Output Mode
- GPIO_Mode_AF = 0x02, // GPIO Alternate function Mode
- GPIO_Mode_AN = 0x03 // GPIO Analog In/Out Mode
-} GPIOMode_TypeDef;
-
-typedef enum
-{
- GPIO_OType_PP = 0x00,
- GPIO_OType_OD = 0x01
-} GPIOOType_TypeDef;
-
-typedef enum
-{
- GPIO_PuPd_NOPULL = 0x00,
- GPIO_PuPd_UP = 0x01,
- GPIO_PuPd_DOWN = 0x02
-} GPIOPuPd_TypeDef;
-*/
-
+#ifdef STM32F3
typedef enum
{
Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
@@ -73,6 +49,22 @@ typedef enum
} GPIO_Mode;
#endif
+#ifdef STM32F4
+typedef enum
+{
+ Mode_AIN = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_AN,
+ Mode_IN_FLOATING = (GPIO_PuPd_NOPULL << 2) | GPIO_Mode_IN,
+ Mode_IPD = (GPIO_PuPd_DOWN << 2) | GPIO_Mode_IN,
+ Mode_IPU = (GPIO_PuPd_UP << 2) | GPIO_Mode_IN,
+ Mode_Out_OD = (GPIO_OType_OD << 4) | GPIO_Mode_OUT,
+ Mode_Out_PP = (GPIO_OType_PP << 4) | GPIO_Mode_OUT,
+ Mode_AF_OD = (GPIO_OType_OD << 4) | GPIO_Mode_AF,
+ Mode_AF_PP = (GPIO_OType_PP << 4) | GPIO_Mode_AF,
+ Mode_AF_PP_PD = (GPIO_OType_PP << 4) | (GPIO_PuPd_DOWN << 2) | GPIO_Mode_AF,
+ Mode_AF_PP_PU = (GPIO_OType_PP << 4) | (GPIO_PuPd_UP << 2) | GPIO_Mode_AF
+} GPIO_Mode;
+#endif
+
typedef enum
{
Speed_10MHz = 1,
@@ -109,11 +101,17 @@ typedef struct
} gpio_config_t;
#ifndef UNIT_TEST
+#ifdef STM32F4
+static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; }
+static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; }
+#else
static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; }
-static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; }
-static inline void digitalToggle(GPIO_TypeDef *p, uint16_t i) { p->ODR ^= i; }
-static inline uint16_t digitalIn(GPIO_TypeDef *p, uint16_t i) {return p->IDR & i; }
+static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; }
#endif
+static inline void digitalToggle(GPIO_TypeDef *p, uint16_t i) { p->ODR ^= i; }
+static inline uint16_t digitalIn(GPIO_TypeDef *p, uint16_t i) { return p->IDR & i; }
+#endif
+
void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config);
void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc);
diff --git a/src/main/drivers/gpio_stm32f4xx.c b/src/main/drivers/gpio_stm32f4xx.c
new file mode 100644
index 0000000000..0129bf68f4
--- /dev/null
+++ b/src/main/drivers/gpio_stm32f4xx.c
@@ -0,0 +1,76 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+
+#include "platform.h"
+
+#include "build_config.h"
+
+#include "gpio.h"
+
+#define MODE_OFFSET 0
+#define PUPD_OFFSET 2
+#define OUTPUT_OFFSET 4
+
+#define MODE_MASK ((1|2))
+#define PUPD_MASK ((1|2))
+#define OUTPUT_MASK ((1|2))
+
+//#define GPIO_Speed_10MHz GPIO_Speed_Level_1 Fast Speed:10MHz
+//#define GPIO_Speed_2MHz GPIO_Speed_Level_2 Medium Speed:2MHz
+//#define GPIO_Speed_50MHz GPIO_Speed_Level_3 High Speed:50MHz
+
+void gpioInit(GPIO_TypeDef *gpio, gpio_config_t *config)
+{
+ GPIO_InitTypeDef GPIO_InitStructure;
+
+ uint32_t pinIndex;
+ for (pinIndex = 0; pinIndex < 16; pinIndex++) {
+ // are we doing this pin?
+ uint32_t pinMask = (0x1 << pinIndex);
+ if (config->pin & pinMask) {
+
+ GPIO_InitStructure.GPIO_Pin = pinMask;
+ GPIO_InitStructure.GPIO_Mode = (config->mode >> MODE_OFFSET) & MODE_MASK;
+
+ GPIOSpeed_TypeDef speed = GPIO_Medium_Speed;
+ switch (config->speed) {
+ case Speed_10MHz:
+ speed = GPIO_Medium_Speed;
+ break;
+ case Speed_2MHz:
+ speed = GPIO_Low_Speed;
+ break;
+ case Speed_50MHz:
+ speed = GPIO_Fast_Speed;
+ break;
+ }
+
+ GPIO_InitStructure.GPIO_Speed = speed;
+ GPIO_InitStructure.GPIO_OType = (config->mode >> OUTPUT_OFFSET) & OUTPUT_MASK;
+ GPIO_InitStructure.GPIO_PuPd = (config->mode >> PUPD_OFFSET) & PUPD_MASK;
+ GPIO_Init(gpio, &GPIO_InitStructure);
+ }
+ }
+}
+
+void gpioExtiLineConfig(uint8_t portsrc, uint8_t pinsrc)
+{
+ SYSCFG_EXTILineConfig(portsrc, pinsrc);
+}
diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c
index 31cf8ada76..09de097716 100644
--- a/src/main/drivers/io.c
+++ b/src/main/drivers/io.c
@@ -1,112 +1,122 @@
-
#include "common/utils.h"
-#include "drivers/io.h"
-#include "drivers/io_impl.h"
-#include "drivers/rcc.h"
+#include "io.h"
+#include "io_impl.h"
+#include "rcc.h"
#include "target.h"
// io ports defs are stored in array by index now
struct ioPortDef_s {
- rccPeriphTag_t rcc;
+ rccPeriphTag_t rcc;
};
#if defined(STM32F10X)
const struct ioPortDef_s ioPortDefs[] = {
- {RCC_APB2(IOPA)},
- {RCC_APB2(IOPB)},
- {RCC_APB2(IOPC)},
- {RCC_APB2(IOPD)},
- {RCC_APB2(IOPE)},
- {
+ { RCC_APB2(IOPA) },
+ { RCC_APB2(IOPB) },
+ { RCC_APB2(IOPC) },
+ { RCC_APB2(IOPD) },
+ { RCC_APB2(IOPE) },
+{
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
- RCC_APB2(IOPF),
+ RCC_APB2(IOPF),
#else
- 0,
+ 0,
#endif
- },
- {
+},
+{
#if defined (STM32F10X_HD) || defined (STM32F10X_XL) || defined (STM32F10X_HD_VL)
- RCC_APB2(IOPG),
+ RCC_APB2(IOPG),
#else
- 0,
+ 0,
#endif
- },
+},
};
#elif defined(STM32F303xC)
const struct ioPortDef_s ioPortDefs[] = {
- {RCC_AHB(GPIOA)},
- {RCC_AHB(GPIOB)},
- {RCC_AHB(GPIOC)},
- {RCC_AHB(GPIOD)},
- {RCC_AHB(GPIOE)},
- {RCC_AHB(GPIOF)},
+ { RCC_AHB(GPIOA) },
+ { RCC_AHB(GPIOB) },
+ { RCC_AHB(GPIOC) },
+ { RCC_AHB(GPIOD) },
+ { RCC_AHB(GPIOE) },
+ { RCC_AHB(GPIOF) },
};
-#endif
+#elif defined(STM32F4)
+const struct ioPortDef_s ioPortDefs[] = {
+ { RCC_AHB1(GPIOA) },
+ { RCC_AHB1(GPIOB) },
+ { RCC_AHB1(GPIOC) },
+ { RCC_AHB1(GPIOD) },
+ { RCC_AHB1(GPIOE) },
+ { RCC_AHB1(GPIOF) },
+};
+# endif
ioRec_t* IO_Rec(IO_t io)
{
- return io;
+ return io;
}
GPIO_TypeDef* IO_GPIO(IO_t io)
{
- ioRec_t *ioRec = IO_Rec(io);
- return ioRec->gpio;
+ ioRec_t *ioRec = IO_Rec(io);
+ return ioRec->gpio;
}
uint16_t IO_Pin(IO_t io)
{
- ioRec_t *ioRec = IO_Rec(io);
- return ioRec->pin;
+ ioRec_t *ioRec = IO_Rec(io);
+ return ioRec->pin;
}
// port index, GPIOA == 0
int IO_GPIOPortIdx(IO_t io)
{
- if(!io)
- return -1;
- return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
+ if (!io)
+ return -1;
+ return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); // ports are 0x400 apart
}
int IO_EXTI_PortSourceGPIO(IO_t io)
{
- return IO_GPIOPortIdx(io);
+ return IO_GPIOPortIdx(io);
}
int IO_GPIO_PortSource(IO_t io)
{
- return IO_GPIOPortIdx(io);
+ return IO_GPIOPortIdx(io);
}
// zero based pin index
int IO_GPIOPinIdx(IO_t io)
{
- if(!io)
- return -1;
- return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
+ if (!io)
+ return -1;
+ return 31 - __builtin_clz(IO_Pin(io)); // CLZ is a bit faster than FFS
}
int IO_EXTI_PinSource(IO_t io)
{
- return IO_GPIOPinIdx(io);
+ return IO_GPIOPinIdx(io);
}
int IO_GPIO_PinSource(IO_t io)
{
- return IO_GPIOPinIdx(io);
+ return IO_GPIOPinIdx(io);
}
// mask on stm32f103, bit index on stm32f303
uint32_t IO_EXTI_Line(IO_t io)
{
- if(!io)
- return 0;
+ if (!io)
+ return 0;
#if defined(STM32F10X)
- return 1 << IO_GPIOPinIdx(io);
+ return 1 << IO_GPIOPinIdx(io);
#elif defined(STM32F303xC)
- return IO_GPIOPinIdx(io);
+ return IO_GPIOPinIdx(io);
+#elif defined(STM32F40_41xxx) || defined(STM32F411xE)
+ return 1 << IO_GPIOPinIdx(io);
#else
# error "Unknown target type"
#endif
@@ -114,158 +124,179 @@ uint32_t IO_EXTI_Line(IO_t io)
bool IORead(IO_t io)
{
- if(!io)
- return false;
- return !!(IO_GPIO(io)->IDR & IO_Pin(io));
+ if (!io)
+ return false;
+ return !! (IO_GPIO(io)->IDR & IO_Pin(io));
}
void IOWrite(IO_t io, bool hi)
{
- if(!io)
- return;
- IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
+ if (!io)
+ return;
+#if defined(STM32F40_41xxx) || defined(STM32F411xE)
+ if (hi) {
+ IO_GPIO(io)->BSRRL = IO_Pin(io);
+ }
+ else {
+ IO_GPIO(io)->BSRRH = IO_Pin(io);
+ }
+#else
+ IO_GPIO(io)->BSRR = IO_Pin(io) << (hi ? 0 : 16);
+#endif
}
void IOHi(IO_t io)
{
- if(!io)
- return;
- IO_GPIO(io)->BSRR = IO_Pin(io);
+ if (!io)
+ return;
+#if defined(STM32F40_41xxx) || defined(STM32F411xE)
+ IO_GPIO(io)->BSRRL = IO_Pin(io);
+#else
+ IO_GPIO(io)->BSRR = IO_Pin(io);
+#endif
}
void IOLo(IO_t io)
{
- if(!io)
- return;
- IO_GPIO(io)->BRR = IO_Pin(io);
+ if (!io)
+ return;
+#if defined(STM32F40_41xxx) || defined(STM32F411xE)
+ IO_GPIO(io)->BSRRH = IO_Pin(io);
+#else
+ IO_GPIO(io)->BRR = IO_Pin(io);
+#endif
}
void IOToggle(IO_t io)
{
- if(!io)
- return;
- // check pin state and use BSRR accordinly to avoid race condition
- uint16_t mask = IO_Pin(io);
- if(IO_GPIO(io)->ODR & mask)
- mask <<= 16; // bit is set, shift mask to reset half
- IO_GPIO(io)->BSRR = mask;
+ if (!io)
+ return;
+ // check pin state and use BSRR accordinly to avoid race condition
+ uint16_t mask = IO_Pin(io);
+#if defined(STM32F40_41xxx) || defined(STM32F411xE)
+ IO_GPIO(io)->ODR ^= mask;
+#else
+ if (IO_GPIO(io)->ODR & mask)
+ mask <<= 16; // bit is set, shift mask to reset half
+
+ IO_GPIO(io)->BSRR = mask;
+#endif
}
// claim IO pin, set owner and resources
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources)
{
- ioRec_t *ioRec = IO_Rec(io);
- if(owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
- ioRec->owner = owner;
- ioRec->resourcesUsed |= resources;
+ ioRec_t *ioRec = IO_Rec(io);
+ if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner
+ ioRec->owner = owner;
+ ioRec->resourcesUsed |= resources;
}
void IORelease(IO_t io)
{
- ioRec_t *ioRec = IO_Rec(io);
- ioRec->owner = OWNER_FREE;
+ ioRec_t *ioRec = IO_Rec(io);
+ ioRec->owner = OWNER_FREE;
}
resourceOwner_t IOGetOwner(IO_t io)
{
- ioRec_t *ioRec = IO_Rec(io);
- return ioRec->owner;
+ ioRec_t *ioRec = IO_Rec(io);
+ return ioRec->owner;
}
resourceType_t IOGetResources(IO_t io)
{
- ioRec_t *ioRec = IO_Rec(io);
- return ioRec->resourcesUsed;
+ ioRec_t *ioRec = IO_Rec(io);
+ return ioRec->resourcesUsed;
}
-#if defined(STM32F10X)
+#if defined(STM32F10X)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
- if(!io)
- return;
- rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
- RCC_ClockCmd(rcc, ENABLE);
+ if (!io)
+ return;
+ rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
+ RCC_ClockCmd(rcc, ENABLE);
- GPIO_InitTypeDef init = {
- .GPIO_Pin = IO_Pin(io),
- .GPIO_Speed = cfg & 0x03,
- .GPIO_Mode = cfg & 0x7c,
- };
- GPIO_Init(IO_GPIO(io), &init);
+ GPIO_InitTypeDef init = {
+ .GPIO_Pin = IO_Pin(io),
+ .GPIO_Speed = cfg & 0x03,
+ .GPIO_Mode = cfg & 0x7c,
+ };
+ GPIO_Init(IO_GPIO(io), &init);
}
-
-#elif defined(STM32F303xC)
+#elif defined(STM32F303xC) || defined(STM32F40_41xxx) || defined(STM32F411xE)
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
{
- if(!io)
- return;
- rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
- RCC_ClockCmd(rcc, ENABLE);
+ if (!io)
+ return;
+ rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
+ RCC_ClockCmd(rcc, ENABLE);
- GPIO_InitTypeDef init = {
- .GPIO_Pin = IO_Pin(io),
- .GPIO_Mode = (cfg >> 0) & 0x03,
- .GPIO_Speed = (cfg >> 2) & 0x03,
- .GPIO_OType = (cfg >> 4) & 0x01,
- .GPIO_PuPd = (cfg >> 5) & 0x03,
- };
- GPIO_Init(IO_GPIO(io), &init);
+ GPIO_InitTypeDef init = {
+ .GPIO_Pin = IO_Pin(io),
+ .GPIO_Mode = (cfg >> 0) & 0x03,
+ .GPIO_Speed = (cfg >> 2) & 0x03,
+ .GPIO_OType = (cfg >> 4) & 0x01,
+ .GPIO_PuPd = (cfg >> 5) & 0x03,
+ };
+ GPIO_Init(IO_GPIO(io), &init);
}
void IOConfigGPIOAF(IO_t io, ioConfig_t cfg, uint8_t af)
{
- if(!io)
- return;
+ if (!io)
+ return;
- rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
- RCC_ClockCmd(rcc, ENABLE);
- GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
+ rccPeriphTag_t rcc = ioPortDefs[IO_GPIOPortIdx(io)].rcc;
+ RCC_ClockCmd(rcc, ENABLE);
+ GPIO_PinAFConfig(IO_GPIO(io), IO_GPIO_PinSource(io), af);
- GPIO_InitTypeDef init = {
- .GPIO_Pin = IO_Pin(io),
- .GPIO_Mode = (cfg >> 0) & 0x03,
- .GPIO_Speed = (cfg >> 2) & 0x03,
- .GPIO_OType = (cfg >> 4) & 0x01,
- .GPIO_PuPd = (cfg >> 5) & 0x03,
- };
- GPIO_Init(IO_GPIO(io), &init);
+ GPIO_InitTypeDef init = {
+ .GPIO_Pin = IO_Pin(io),
+ .GPIO_Mode = (cfg >> 0) & 0x03,
+ .GPIO_Speed = (cfg >> 2) & 0x03,
+ .GPIO_OType = (cfg >> 4) & 0x01,
+ .GPIO_PuPd = (cfg >> 5) & 0x03,
+ };
+ GPIO_Init(IO_GPIO(io), &init);
}
#endif
-static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = {DEFIO_PORT_USED_LIST};
-static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = {DEFIO_PORT_OFFSET_LIST};
+static const uint16_t ioDefUsedMask[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_USED_LIST };
+static const uint8_t ioDefUsedOffset[DEFIO_PORT_USED_COUNT] = { DEFIO_PORT_OFFSET_LIST };
ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
// initialize all ioRec_t structures from ROM
// currently only bitmask is used, this may change in future
void IOInitGlobal(void) {
- ioRec_t *ioRec = ioRecs;
+ ioRec_t *ioRec = ioRecs;
- for(unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++)
- for(unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++)
- if(ioDefUsedMask[port] & (1 << pin)) {
- ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
- ioRec->pin = 1 << pin;
- ioRec++;
- }
+ for (unsigned port = 0; port < ARRAYLEN(ioDefUsedMask); port++)
+ for (unsigned pin = 0; pin < sizeof(ioDefUsedMask[0]) * 8; pin++)
+ if (ioDefUsedMask[port] & (1 << pin)) {
+ ioRec->gpio = (GPIO_TypeDef *)(GPIOA_BASE + (port << 10)); // ports are 0x400 apart
+ ioRec->pin = 1 << pin;
+ ioRec++;
+ }
}
IO_t IOGetByTag(ioTag_t tag)
{
- int portIdx = DEFIO_TAG_GPIOID(tag);
- int pinIdx = DEFIO_TAG_PIN(tag);
+ int portIdx = DEFIO_TAG_GPIOID(tag);
+ int pinIdx = DEFIO_TAG_PIN(tag);
- if(portIdx >= DEFIO_PORT_USED_COUNT)
- return NULL;
- // check if pin exists
- if(!(ioDefUsedMask[portIdx] & (1 << pinIdx)))
- return NULL;
- // count bits before this pin on single port
- int offset = __builtin_popcount(((1 << pinIdx)-1) & ioDefUsedMask[portIdx]);
- // and add port offset
- offset += ioDefUsedOffset[portIdx];
- return ioRecs + offset;
+ if (portIdx >= DEFIO_PORT_USED_COUNT)
+ return NULL;
+ // check if pin exists
+ if (!(ioDefUsedMask[portIdx] & (1 << pinIdx)))
+ return NULL;
+ // count bits before this pin on single port
+ int offset = __builtin_popcount(((1 << pinIdx) - 1) & ioDefUsedMask[portIdx]);
+ // and add port offset
+ offset += ioDefUsedOffset[portIdx];
+ return ioRecs + offset;
}
diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h
index 5808296554..1b5cb15e09 100644
--- a/src/main/drivers/io_impl.h
+++ b/src/main/drivers/io_impl.h
@@ -5,26 +5,33 @@
#include "platform.h"
typedef struct ioDef_s {
- ioTag_t tag;
+ ioTag_t tag;
} ioDef_t;
typedef struct ioRec_s {
- GPIO_TypeDef *gpio;
- uint16_t pin;
- resourceOwner_t owner;
- resourceType_t resourcesUsed; // TODO!
+ GPIO_TypeDef *gpio;
+ uint16_t pin;
+ resourceOwner_t owner;
+ resourceType_t resourcesUsed; // TODO!
} ioRec_t;
extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT];
int IO_GPIOPortIdx(IO_t io);
int IO_GPIOPinIdx(IO_t io);
-#if defined(STM32F10X)
+#if defined(STM32F1)
+int IO_GPIO_PinSource(IO_t io);
+int IO_GPIO_PortSource(IO_t io);
+#elif defined(STM32F3)
int IO_GPIO_PinSource(IO_t io);
int IO_GPIO_PortSource(IO_t io);
-#elif defined(STM32F303xC)
int IO_EXTI_PortSourceGPIO(IO_t io);
int IO_EXTI_PinSource(IO_t io);
-#endif
+#elif defined(STM32F4)
+int IO_GPIO_PinSource(IO_t io);
+int IO_GPIO_PortSource(IO_t io);
+int IO_EXTI_PortSourceGPIO(IO_t io);
+int IO_EXTI_PinSource(IO_t io);
+# endif
uint32_t IO_EXTI_Line(IO_t io);
ioRec_t *IO_Rec(IO_t io);
diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c
new file mode 100644
index 0000000000..d85f1c5757
--- /dev/null
+++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c
@@ -0,0 +1,130 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+
+#include "platform.h"
+
+#include "common/color.h"
+#include "light_ws2811strip.h"
+#include "nvic.h"
+
+#ifdef LED_STRIP
+void ws2811LedStripHardwareInit(void)
+{
+ TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
+ TIM_OCInitTypeDef TIM_OCInitStructure;
+ GPIO_InitTypeDef GPIO_InitStructure;
+ DMA_InitTypeDef DMA_InitStructure;
+
+ uint16_t prescalerValue;
+
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_GPIOA, ENABLE);
+ RCC_APB1PeriphClockCmd(RCC_APB1Periph_TIM5, ENABLE);
+ RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE);
+
+
+ /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_0;
+ GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF;
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP;
+ GPIO_InitStructure.GPIO_OType = GPIO_OType_PP;
+ GPIO_InitStructure.GPIO_Speed = GPIO_Speed_100MHz;
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ GPIO_PinAFConfig(GPIOA, GPIO_PinSource0, GPIO_AF_TIM5);
+
+
+ // Stop timer
+ TIM_Cmd(TIM5, DISABLE);
+
+ /* Compute the prescaler value */
+ prescalerValue = (uint16_t) (SystemCoreClock / 2 / 84000000) - 1;
+ /* Time base configuration */
+ TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz
+ TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
+ TIM_TimeBaseStructure.TIM_ClockDivision = 0;
+ TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
+ TIM_TimeBaseInit(TIM5, &TIM_TimeBaseStructure);
+
+ /* PWM1 Mode configuration: Channel1 */
+ TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
+ TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
+ TIM_OCInitStructure.TIM_Pulse = 0;
+ TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
+ TIM_OC1Init(TIM5, &TIM_OCInitStructure);
+ TIM_OC1PreloadConfig(TIM5, TIM_OCPreload_Enable);
+
+ TIM_Cmd(TIM5, ENABLE);
+
+
+ /* configure DMA */
+ /* DMA1 Channel Config */
+ DMA_Cmd(DMA1_Stream2, DISABLE); // disable DMA channel 6
+ DMA_DeInit(DMA1_Stream2);
+ DMA_StructInit(&DMA_InitStructure);
+ DMA_InitStructure.DMA_Channel = DMA_Channel_6;
+ DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&(TIM5->CCR1);
+ DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+ DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
+ DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
+ DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
+ DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
+ DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+ DMA_Init(DMA1_Stream2, &DMA_InitStructure);
+
+ DMA_ITConfig(DMA1_Stream2, DMA_IT_TC, ENABLE);
+ DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2); // clear DMA1 Channel 6 transfer complete flag
+
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ NVIC_InitStructure.NVIC_IRQChannel = DMA1_Stream2_IRQn;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_WS2811_DMA);
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(NVIC_PRIO_WS2811_DMA);
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ setStripColor(&hsv_white);
+ ws2811UpdateStrip();
+}
+
+void DMA1_Stream2_IRQHandler(void)
+{
+ if (DMA_GetFlagStatus(DMA1_Stream2, DMA_FLAG_TCIF2)) {
+ ws2811LedDataTransferInProgress = 0;
+ DMA_Cmd(DMA1_Stream2, DISABLE);
+ TIM_DMACmd(TIM5, TIM_DMA_CC1, DISABLE);
+ DMA_ClearITPendingBit(DMA1_Stream2, DMA_IT_TCIF2);
+ }
+}
+
+void ws2811LedStripDMAEnable(void)
+{
+ DMA_SetCurrDataCounter(DMA1_Stream2, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
+ TIM_SetCounter(TIM5, 0);
+ DMA_Cmd(DMA1_Stream2, ENABLE);
+ TIM_DMACmd(TIM5, TIM_DMA_CC1, ENABLE);
+}
+#endif
diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c
index b786ba0cee..763c10e11d 100755
--- a/src/main/drivers/pwm_mapping.c
+++ b/src/main/drivers/pwm_mapping.c
@@ -68,15 +68,8 @@ void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui
PWM11.14 used for servos
*/
-enum {
- MAP_TO_PPM_INPUT = 1,
- MAP_TO_PWM_INPUT,
- MAP_TO_MOTOR_OUTPUT,
- MAP_TO_SERVO_OUTPUT,
-};
-
#if defined(NAZE) || defined(OLIMEXINO) || defined(NAZE32PRO) || defined(STM32F3DISCOVERY) || defined(EUSTM32F103RC) || defined(PORT103R)
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
@@ -91,7 +84,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -109,7 +102,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -124,7 +117,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -144,7 +137,7 @@ static const uint16_t airPWM[] = {
#endif
#ifdef CC3D
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -159,7 +152,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -175,7 +168,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -190,7 +183,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -205,7 +198,7 @@ static const uint16_t airPWM[] = {
PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
0xFFFF
};
-static const uint16_t multiPPM_BP6[] = {
+const uint16_t multiPPM_BP6[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -219,7 +212,7 @@ static const uint16_t multiPPM_BP6[] = {
0xFFFF
};
-static const uint16_t multiPWM_BP6[] = {
+const uint16_t multiPWM_BP6[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -234,7 +227,7 @@ static const uint16_t multiPWM_BP6[] = {
0xFFFF
};
-static const uint16_t airPPM_BP6[] = {
+const uint16_t airPPM_BP6[] = {
PWM6 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -248,7 +241,7 @@ static const uint16_t airPPM_BP6[] = {
0xFFFF
};
-static const uint16_t airPWM_BP6[] = {
+const uint16_t airPWM_BP6[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -265,7 +258,7 @@ static const uint16_t airPWM_BP6[] = {
#endif
#ifdef CJMCU
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -274,7 +267,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -288,17 +281,17 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
0xFFFF
};
#endif
#if defined(COLIBRI_RACE) || defined(LUX_RACE)
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -313,7 +306,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
// prevent crashing, but do nothing
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -328,7 +321,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -343,7 +336,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
// prevent crashing, but do nothing
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -360,7 +353,7 @@ static const uint16_t airPWM[] = {
#endif
#if defined(SPARKY) || defined(ALIENFLIGHTF3)
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), // TIM15
@@ -376,7 +369,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -390,19 +383,19 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
// TODO
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
// TODO
0xFFFF
};
#endif
#ifdef SPRACINGF3
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -420,7 +413,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8),
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -440,7 +433,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -457,7 +450,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
PWM2 | (MAP_TO_PWM_INPUT << 8),
PWM3 | (MAP_TO_PWM_INPUT << 8),
@@ -479,7 +472,7 @@ static const uint16_t airPWM[] = {
#endif
#ifdef SPRACINGF3EVO
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -495,7 +488,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -509,7 +502,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -524,7 +517,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
@@ -540,7 +533,7 @@ static const uint16_t airPWM[] = {
#endif
#if defined(MOTOLAB)
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM9 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -554,7 +547,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM1 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -566,19 +559,19 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
// TODO
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
// TODO
0xFFFF
};
#endif
#if defined(SINGULARITY)
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -592,7 +585,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -605,7 +598,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8),
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -619,7 +612,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
@@ -634,7 +627,7 @@ static const uint16_t airPWM[] = {
#endif
#ifdef SPRACINGF3MINI
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -650,7 +643,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM4 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -664,7 +657,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
@@ -679,7 +672,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
PWM4 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
@@ -695,7 +688,7 @@ static const uint16_t airPWM[] = {
#endif
#ifdef DOGE
-static const uint16_t multiPPM[] = {
+const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -708,7 +701,7 @@ static const uint16_t multiPPM[] = {
0xFFFF
};
-static const uint16_t multiPWM[] = {
+const uint16_t multiPWM[] = {
// prevent crashing, but do nothing
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -721,7 +714,7 @@ static const uint16_t multiPWM[] = {
0xFFFF
};
-static const uint16_t airPPM[] = {
+const uint16_t airPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -734,7 +727,7 @@ static const uint16_t airPPM[] = {
0xFFFF
};
-static const uint16_t airPWM[] = {
+const uint16_t airPWM[] = {
// prevent crashing, but do nothing
PWM2 | (MAP_TO_MOTOR_OUTPUT << 8),
PWM3 | (MAP_TO_MOTOR_OUTPUT << 8),
@@ -748,7 +741,7 @@ static const uint16_t airPWM[] = {
};
#endif
-static const uint16_t * const hardwareMaps[] = {
+const uint16_t * const hardwareMaps[] = {
multiPWM,
multiPPM,
airPWM,
@@ -756,7 +749,7 @@ static const uint16_t * const hardwareMaps[] = {
};
#ifdef CC3D
-static const uint16_t * const hardwareMapsBP6[] = {
+const uint16_t * const hardwareMapsBP6[] = {
multiPWM_BP6,
multiPPM_BP6,
airPWM_BP6,
@@ -766,9 +759,11 @@ static const uint16_t * const hardwareMapsBP6[] = {
static pwmOutputConfiguration_t pwmOutputConfiguration;
-pwmOutputConfiguration_t *pwmGetOutputConfiguration(void){
+pwmOutputConfiguration_t *pwmGetOutputConfiguration(void)
+{
return &pwmOutputConfiguration;
}
+
pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
{
int i = 0;
@@ -776,7 +771,6 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init)
int channelIndex = 0;
-
memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration));
// this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ]
diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h
index aaaf4ac6b2..da5762ec61 100644
--- a/src/main/drivers/pwm_mapping.h
+++ b/src/main/drivers/pwm_mapping.h
@@ -59,6 +59,10 @@ typedef struct drv_pwm_config_s {
#endif
#ifdef STM32F303xC
bool useUART3;
+#endif
+#ifdef STM32F4
+ bool useUART2;
+ bool useUART6;
#endif
bool useVbat;
bool useFastPwm;
@@ -71,7 +75,6 @@ typedef struct drv_pwm_config_s {
#ifdef USE_SERVOS
bool useServos;
bool useChannelForwarding; // configure additional channels as servos
- uint8_t pwmProtocolType;
uint16_t servoPwmRate;
uint16_t servoCenterPulse;
#endif
@@ -79,12 +82,19 @@ typedef struct drv_pwm_config_s {
bool useBuzzerP6;
#endif
bool airplane; // fixed wing hardware config, lots of servos etc
+ uint8_t pwmProtocolType;
uint16_t motorPwmRate;
uint16_t idlePulse; // PWM value to use when initializing the driver. set this to either PULSE_1MS (regular pwm),
// some higher value (used by 3d mode), or 0, for brushed pwm drivers.
sonarGPIOConfig_t *sonarGPIOConfig;
} drv_pwm_config_t;
+enum {
+ MAP_TO_PPM_INPUT = 1,
+ MAP_TO_PWM_INPUT,
+ MAP_TO_MOTOR_OUTPUT,
+ MAP_TO_SERVO_OUTPUT,
+};
typedef enum {
PWM_PF_NONE = 0,
@@ -129,4 +139,9 @@ enum {
PWM16
};
+extern const uint16_t multiPPM[];
+extern const uint16_t multiPWM[];
+extern const uint16_t airPPM[];
+extern const uint16_t airPWM[];
+
pwmOutputConfiguration_t *pwmGetOutputConfiguration(void);
diff --git a/src/main/drivers/rcc.h b/src/main/drivers/rcc.h
index a00b5b8450..4c927c1dd9 100644
--- a/src/main/drivers/rcc.h
+++ b/src/main/drivers/rcc.h
@@ -1,21 +1,25 @@
#pragma once
+#include "platform.h"
#include "common/utils.h"
enum rcc_reg {
- RCC_EMPTY = 0, // make sure that default value (0) does not enable anything
- RCC_AHB,
- RCC_APB2,
- RCC_APB1,
+ RCC_EMPTY = 0, // make sure that default value (0) does not enable anything
+ RCC_AHB,
+ RCC_APB2,
+ RCC_APB1,
+ RCC_AHB1,
};
#define RCC_ENCODE(reg, mask) (((reg) << 5) | LOG2_32BIT(mask))
#define RCC_AHB(periph) RCC_ENCODE(RCC_AHB, RCC_AHBENR_ ## periph ## EN)
#define RCC_APB2(periph) RCC_ENCODE(RCC_APB2, RCC_APB2ENR_ ## periph ## EN)
#define RCC_APB1(periph) RCC_ENCODE(RCC_APB1, RCC_APB1ENR_ ## periph ## EN)
+#define RCC_AHB1(periph) RCC_ENCODE(RCC_AHB1, RCC_AHB1ENR_ ## periph ## EN)
typedef uint8_t rccPeriphTag_t;
void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
void RCC_ResetCmd(rccPeriphTag_t periphTag, FunctionalState NewState);
+
diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c
index d6f2b9e6a3..45919cbc58 100644
--- a/src/main/drivers/sdcard.c
+++ b/src/main/drivers/sdcard.c
@@ -405,22 +405,32 @@ static void sdcard_sendDataBlockBegin(uint8_t *buffer, bool multiBlockWrite)
spiTransferByte(SDCARD_SPI_INSTANCE, multiBlockWrite ? SDCARD_MULTIPLE_BLOCK_WRITE_START_TOKEN : SDCARD_SINGLE_BLOCK_WRITE_START_TOKEN);
if (useDMAForTx) {
+#ifdef SDCARD_DMA_CHANNEL_TX
// Queue the transmission of the sector payload
+#ifdef SDCARD_DMA_CLK
+ RCC_AHB1PeriphClockCmd(SDCARD_DMA_CLK, ENABLE);
+#endif
DMA_InitTypeDef DMA_InitStructure;
DMA_StructInit(&DMA_InitStructure);
+#ifdef SDCARD_DMA_CHANNEL
+ DMA_InitStructure.DMA_Channel = SDCARD_DMA_CHANNEL;
+ DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t) buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+#else
+ DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
+ DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) buffer;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
+#endif
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t) &SDCARD_SPI_INSTANCE->DR;
DMA_InitStructure.DMA_Priority = DMA_Priority_Low;
- DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
- DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t) buffer;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
DMA_InitStructure.DMA_BufferSize = SDCARD_BLOCK_SIZE;
- DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(SDCARD_DMA_CHANNEL_TX);
@@ -429,7 +439,9 @@ static void sdcard_sendDataBlockBegin(uint8_t *buffer, bool multiBlockWrite)
DMA_Cmd(SDCARD_DMA_CHANNEL_TX, ENABLE);
SPI_I2S_DMACmd(SDCARD_SPI_INSTANCE, SPI_I2S_DMAReq_Tx, ENABLE);
- } else {
+#endif
+ }
+ else {
// Send the first chunk now
spiTransfer(SDCARD_SPI_INSTANCE, NULL, buffer, SDCARD_NON_DMA_CHUNK_SIZE);
}
@@ -542,7 +554,15 @@ void sdcard_init(bool useDMA)
spiTransfer(SDCARD_SPI_INSTANCE, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES);
// Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles:
+ int time = 0;
while (spiIsBusBusy(SDCARD_SPI_INSTANCE)) {
+ if (time > 10) {
+ sdcard.state = SDCARD_STATE_NOT_PRESENT;
+ sdcard.failureCount++;
+ return;
+ }
+ delay(1000);
+ time++;
}
sdcard.operationStartTime = millis();
@@ -697,8 +717,14 @@ bool sdcard_poll(void)
// Have we finished sending the write yet?
sendComplete = false;
+#ifdef SDCARD_DMA_CHANNEL_TX
+#ifdef SDCARD_DMA_CHANNEL
+ if (useDMAForTx && DMA_GetFlagStatus(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG) == SET) {
+ DMA_ClearFlag(SDCARD_DMA_CHANNEL_TX, SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG);
+#else
if (useDMAForTx && DMA_GetFlagStatus(SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG) == SET) {
DMA_ClearFlag(SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG);
+#endif
DMA_Cmd(SDCARD_DMA_CHANNEL_TX, DISABLE);
@@ -715,7 +741,7 @@ bool sdcard_poll(void)
sendComplete = true;
}
-
+#endif
if (!useDMAForTx) {
// Send another chunk
spiTransfer(SDCARD_SPI_INSTANCE, NULL, sdcard.pendingOperation.buffer + SDCARD_NON_DMA_CHUNK_SIZE * sdcard.pendingOperation.chunkIndex, SDCARD_NON_DMA_CHUNK_SIZE);
diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c
index b524f70f76..95e2b8c9a2 100644
--- a/src/main/drivers/serial_uart.c
+++ b/src/main/drivers/serial_uart.c
@@ -127,6 +127,20 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
// Receive DMA or IRQ
DMA_InitTypeDef DMA_InitStructure;
if (mode & MODE_RX) {
+#ifdef STM32F4
+ if (s->rxDMAStream) {
+ DMA_StructInit(&DMA_InitStructure);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
+ DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
+ DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
+ DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+#else
if (s->rxDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->rxDMAPeripheralBaseAddr;
@@ -136,8 +150,20 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
-
+#endif
DMA_InitStructure.DMA_BufferSize = s->port.rxBufferSize;
+
+#ifdef STM32F4
+ DMA_InitStructure.DMA_Channel = s->rxDMAChannel;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralToMemory;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
+ DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)s->port.rxBuffer;
+ DMA_DeInit(s->rxDMAStream);
+ DMA_Init(s->rxDMAStream, &DMA_InitStructure);
+ DMA_Cmd(s->rxDMAStream, ENABLE);
+ USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
+ s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAStream);
+#else
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralSRC;
DMA_InitStructure.DMA_Mode = DMA_Mode_Circular;
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)s->port.rxBuffer;
@@ -146,6 +172,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
DMA_Cmd(s->rxDMAChannel, ENABLE);
USART_DMACmd(s->USARTx, USART_DMAReq_Rx, ENABLE);
s->rxDMAPos = DMA_GetCurrDataCounter(s->rxDMAChannel);
+#endif
} else {
USART_ClearITPendingBit(s->USARTx, USART_IT_RXNE);
USART_ITConfig(s->USARTx, USART_IT_RXNE, ENABLE);
@@ -154,6 +181,20 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
// Transmit DMA or IRQ
if (mode & MODE_TX) {
+#ifdef STM32F4
+ if (s->txDMAStream) {
+ DMA_StructInit(&DMA_InitStructure);
+ DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
+ DMA_InitStructure.DMA_Priority = DMA_Priority_Medium;
+ DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
+ DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
+ DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
+ DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
+ DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Disable ;
+ DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull ;
+ DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single ;
+ DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
+#else
if (s->txDMAChannel) {
DMA_StructInit(&DMA_InitStructure);
DMA_InitStructure.DMA_PeripheralBaseAddr = s->txDMAPeripheralBaseAddr;
@@ -163,8 +204,18 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Byte;
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
-
+#endif
DMA_InitStructure.DMA_BufferSize = s->port.txBufferSize;
+
+#ifdef STM32F4
+ DMA_InitStructure.DMA_Channel = s->txDMAChannel;
+ DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
+ DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
+ DMA_DeInit(s->txDMAStream);
+ DMA_Init(s->txDMAStream, &DMA_InitStructure);
+ DMA_ITConfig(s->txDMAStream, DMA_IT_TC | DMA_IT_FE | DMA_IT_TE | DMA_IT_DME, ENABLE);
+ DMA_SetCurrDataCounter(s->txDMAStream, 0);
+#else
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
DMA_DeInit(s->txDMAChannel);
@@ -172,6 +223,7 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback,
DMA_ITConfig(s->txDMAChannel, DMA_IT_TC, ENABLE);
DMA_SetCurrDataCounter(s->txDMAChannel, 0);
s->txDMAChannel->CNDTR = 0;
+#endif
USART_DMACmd(s->USARTx, USART_DMAReq_Tx, ENABLE);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
@@ -199,6 +251,21 @@ void uartSetMode(serialPort_t *instance, portMode_t mode)
void uartStartTxDMA(uartPort_t *s)
{
+#ifdef STM32F4
+ DMA_Cmd(s->txDMAStream, DISABLE);
+ DMA_MemoryTargetConfig(s->txDMAStream, (uint32_t)&s->port.txBuffer[s->port.txBufferTail], DMA_Memory_0);
+ //s->txDMAStream->M0AR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
+ if (s->port.txBufferHead > s->port.txBufferTail) {
+ s->txDMAStream->NDTR = s->port.txBufferHead - s->port.txBufferTail;
+ s->port.txBufferTail = s->port.txBufferHead;
+ }
+ else {
+ s->txDMAStream->NDTR = s->port.txBufferSize - s->port.txBufferTail;
+ s->port.txBufferTail = 0;
+ }
+ s->txDMAEmpty = false;
+ DMA_Cmd(s->txDMAStream, ENABLE);
+#else
s->txDMAChannel->CMAR = (uint32_t)&s->port.txBuffer[s->port.txBufferTail];
if (s->port.txBufferHead > s->port.txBufferTail) {
s->txDMAChannel->CNDTR = s->port.txBufferHead - s->port.txBufferTail;
@@ -209,13 +276,19 @@ void uartStartTxDMA(uartPort_t *s)
}
s->txDMAEmpty = false;
DMA_Cmd(s->txDMAChannel, ENABLE);
+#endif
}
uint8_t uartTotalRxBytesWaiting(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t*)instance;
- if (s->rxDMAChannel) {
+#ifdef STM32F4
+ if (s->rxDMAStream) {
+ uint32_t rxDMAHead = s->rxDMAStream->NDTR;
+#else
+ if (s->rxDMAChannel) {
uint32_t rxDMAHead = s->rxDMAChannel->CNDTR;
+#endif
if (rxDMAHead >= s->rxDMAPos) {
return rxDMAHead - s->rxDMAPos;
} else {
@@ -242,13 +315,21 @@ uint8_t uartTotalTxBytesFree(serialPort_t *instance)
bytesUsed = s->port.txBufferSize + s->port.txBufferHead - s->port.txBufferTail;
}
+#ifdef STM32F4
+ if (s->txDMAStream) {
+ /*
+ * When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
+ * the remaining size of that in-progress transfer here instead:
+ */
+ bytesUsed += s->txDMAStream->NDTR;
+#else
if (s->txDMAChannel) {
/*
* When we queue up a DMA request, we advance the Tx buffer tail before the transfer finishes, so we must add
* the remaining size of that in-progress transfer here instead:
*/
bytesUsed += s->txDMAChannel->CNDTR;
-
+#endif
/*
* If the Tx buffer is being written to very quickly, we might have advanced the head into the buffer
* space occupied by the current DMA transfer. In that case the "bytesUsed" total will actually end up larger
@@ -268,7 +349,11 @@ uint8_t uartTotalTxBytesFree(serialPort_t *instance)
bool isUartTransmitBufferEmpty(serialPort_t *instance)
{
uartPort_t *s = (uartPort_t *)instance;
+#ifdef STM32F4
+ if (s->txDMAStream)
+#else
if (s->txDMAChannel)
+#endif
return s->txDMAEmpty;
else
return s->port.txBufferTail == s->port.txBufferHead;
@@ -279,7 +364,11 @@ uint8_t uartRead(serialPort_t *instance)
uint8_t ch;
uartPort_t *s = (uartPort_t *)instance;
+#ifdef STM32F4
+ if (s->rxDMAStream) {
+#else
if (s->rxDMAChannel) {
+#endif
ch = s->port.rxBuffer[s->port.rxBufferSize - s->rxDMAPos];
if (--s->rxDMAPos == 0)
s->rxDMAPos = s->port.rxBufferSize;
@@ -305,8 +394,13 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
s->port.txBufferHead++;
}
+#ifdef STM32F4
+ if (s->txDMAStream) {
+ if (!(s->txDMAStream->CR & 1))
+#else
if (s->txDMAChannel) {
if (!(s->txDMAChannel->CCR & 1))
+#endif
uartStartTxDMA(s);
} else {
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
diff --git a/src/main/drivers/serial_uart.h b/src/main/drivers/serial_uart.h
index ab7a8dbfcc..1458c3aca3 100644
--- a/src/main/drivers/serial_uart.h
+++ b/src/main/drivers/serial_uart.h
@@ -32,9 +32,16 @@
typedef struct {
serialPort_t port;
-
- DMA_Channel_TypeDef *rxDMAChannel;
- DMA_Channel_TypeDef *txDMAChannel;
+
+#ifdef STM32F4
+ DMA_Stream_TypeDef *rxDMAStream;
+ DMA_Stream_TypeDef *txDMAStream;
+ uint32_t rxDMAChannel;
+ uint32_t txDMAChannel;
+#else
+ DMA_Channel_TypeDef *rxDMAChannel;
+ DMA_Channel_TypeDef *txDMAChannel;
+#endif
uint32_t rxDMAIrq;
uint32_t txDMAIrq;
diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c
new file mode 100644
index 0000000000..71b112e368
--- /dev/null
+++ b/src/main/drivers/serial_uart_stm32f4xx.c
@@ -0,0 +1,582 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "system.h"
+#include "io.h"
+#include "rcc.h"
+#include "nvic.h"
+
+#include "serial.h"
+#include "serial_uart.h"
+#include "serial_uart_impl.h"
+
+// Using RX DMA disables the use of receive callbacks
+//#define USE_USART1_RX_DMA
+//#define USE_USART2_RX_DMA
+//#define USE_USART3_RX_DMA
+//#define USE_USART4_RX_DMA
+//#define USE_USART5_RX_DMA
+//#define USE_USART6_RX_DMA
+
+#define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE
+#define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE
+
+typedef enum UARTDevice {
+ UARTDEV_1 = 0,
+ UARTDEV_2 = 1,
+ UARTDEV_3 = 2,
+ UARTDEV_4 = 3,
+ UARTDEV_5 = 4,
+ UARTDEV_6 = 5
+} UARTDevice;
+
+typedef struct uartDevice_s {
+ USART_TypeDef* dev;
+ uartPort_t port;
+ uint32_t DMAChannel;
+ DMA_Stream_TypeDef *txDMAStream;
+ DMA_Stream_TypeDef *rxDMAStream;
+ ioTag_t rx;
+ ioTag_t tx;
+ volatile uint8_t rxBuffer[UART_RX_BUFFER_SIZE];
+ volatile uint8_t txBuffer[UART_TX_BUFFER_SIZE];
+ uint32_t rcc_ahb1;
+ rccPeriphTag_t rcc_apb2;
+ rccPeriphTag_t rcc_apb1;
+ uint8_t af;
+ uint8_t txIrq;
+ uint8_t rxIrq;
+ uint32_t txPriority;
+ uint32_t rxPriority;
+} uartDevice_t;
+
+//static uartPort_t uartPort[MAX_UARTS];
+#ifdef USE_USART1
+static uartDevice_t uart1 =
+{
+ .DMAChannel = DMA_Channel_4,
+ .txDMAStream = DMA2_Stream7,
+#ifdef USE_USART1_RX_DMA
+ .rxDMAStream = DMA2_Stream5,
+#endif
+ .dev = USART1,
+ .rx = IO_TAG(USART1_RX_PIN),
+ .tx = IO_TAG(USART1_TX_PIN),
+ .af = GPIO_AF_USART1,
+#ifdef USART1_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART1_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb2 = RCC_APB2(USART1),
+ .txIrq = DMA2_Stream7_IRQn,
+ .rxIrq = USART1_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART1_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART1
+};
+#endif
+
+#ifdef USE_USART2
+static uartDevice_t uart2 =
+{
+ .DMAChannel = DMA_Channel_4,
+#ifdef USE_USART2_RX_DMA
+ .rxDMAStream = DMA1_Stream5,
+#endif
+ .txDMAStream = DMA1_Stream6,
+ .dev = USART2,
+ .rx = IO_TAG(USART2_RX_PIN),
+ .tx = IO_TAG(USART2_TX_PIN),
+ .af = GPIO_AF_USART2,
+#ifdef USART2_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART2_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb1 = RCC_APB1(USART2),
+ .txIrq = DMA1_Stream6_IRQn,
+ .rxIrq = USART2_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART2_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART2
+};
+#endif
+
+#ifdef USE_USART3
+static uartDevice_t uart3 =
+{
+ .DMAChannel = DMA_Channel_4,
+#ifdef USE_USART3_RX_DMA
+ .rxDMAStream = DMA1_Stream1,
+#endif
+ .txDMAStream = DMA1_Stream3,
+ .dev = USART3,
+ .rx = IO_TAG(USART3_RX_PIN),
+ .tx = IO_TAG(USART3_TX_PIN),
+ .af = GPIO_AF_USART3,
+#ifdef USART3_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART3_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb1 = RCC_APB1(USART3),
+ .txIrq = DMA1_Stream3_IRQn,
+ .rxIrq = USART3_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART3_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART3
+};
+#endif
+
+#ifdef USE_USART4
+static uartDevice_t uart4 =
+{
+ .DMAChannel = DMA_Channel_4,
+#ifdef USE_USART1_RX_DMA
+ .rxDMAStream = DMA1_Stream2,
+#endif
+ .txDMAStream = DMA1_Stream4,
+ .dev = UART4,
+ .rx = IO_TAG(USART4_RX_PIN),
+ .tx = IO_TAG(USART4_TX_PIN),
+ .af = GPIO_AF_UART4,
+#ifdef USART4_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART4_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb1 = RCC_APB1(UART4),
+ .txIrq = DMA1_Stream4_IRQn,
+ .rxIrq = UART4_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART4_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART4
+};
+#endif
+
+#ifdef USE_USART5
+static uartDevice_t uart5 =
+{
+ .DMAChannel = DMA_Channel_4,
+#ifdef USE_USART1_RX_DMA
+ .rxDMAStream = DMA1_Stream0,
+#endif
+ .txDMAStream = DMA2_Stream7,
+ .dev = UART5,
+ .rx = IO_TAG(USART5_RX_PIN),
+ .tx = IO_TAG(USART5_TX_PIN),
+ .af = GPIO_AF_UART5,
+#ifdef USART5_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART5_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb1 = RCC_APB1(UART5),
+ .txIrq = DMA2_Stream7_IRQn,
+ .rxIrq = UART5_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART5_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART5
+};
+#endif
+
+#ifdef USE_USART6
+static uartDevice_t uart6 =
+{
+ .DMAChannel = DMA_Channel_5,
+#ifdef USE_USART6_RX_DMA
+ .rxDMAStream = DMA2_Stream1,
+#endif
+ .txDMAStream = DMA2_Stream6,
+ .dev = USART6,
+ .rx = IO_TAG(USART6_RX_PIN),
+ .tx = IO_TAG(USART6_TX_PIN),
+ .af = GPIO_AF_USART6,
+#ifdef USART6_AHB1_PERIPHERALS
+ .rcc_ahb1 = USART6_AHB1_PERIPHERALS,
+#endif
+ .rcc_apb2 = RCC_APB2(USART6),
+ .txIrq = DMA2_Stream6_IRQn,
+ .rxIrq = USART6_IRQn,
+ .txPriority = NVIC_PRIO_SERIALUART6_TXDMA,
+ .rxPriority = NVIC_PRIO_SERIALUART6
+};
+#endif
+
+static uartDevice_t* uartHardwareMap[] = {
+#ifdef USE_USART1
+ &uart1,
+#else
+ NULL,
+#endif
+#ifdef USE_USART2
+ &uart2,
+#else
+ NULL,
+#endif
+#ifdef USE_USART3
+ &uart3,
+#else
+ NULL,
+#endif
+#ifdef USE_USART4
+ &uart4,
+#else
+ NULL,
+#endif
+#ifdef USE_USART5
+ &uart5,
+#else
+ NULL,
+#endif
+#ifdef USE_USART6
+ &uart6,
+#else
+ NULL,
+#endif
+ };
+
+void usartIrqHandler(uartPort_t *s)
+{
+ if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) {
+ if (s->port.callback) {
+ s->port.callback(s->USARTx->DR);
+ } else {
+ s->port.rxBuffer[s->port.rxBufferHead] = s->USARTx->DR;
+ s->port.rxBufferHead = (s->port.rxBufferHead + 1) % s->port.rxBufferSize;
+ }
+ }
+
+ if (!s->txDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_TXE) == SET)) {
+ if (s->port.txBufferTail != s->port.txBufferHead) {
+ USART_SendData(s->USARTx, s->port.txBuffer[s->port.txBufferTail]);
+ s->port.txBufferTail = (s->port.txBufferTail + 1) % s->port.txBufferSize;
+ } else {
+ USART_ITConfig(s->USARTx, USART_IT_TXE, DISABLE);
+ }
+ }
+
+ if (USART_GetITStatus(s->USARTx, USART_FLAG_ORE) == SET)
+ {
+ USART_ClearITPendingBit (s->USARTx, USART_IT_ORE);
+ }
+}
+
+static void handleUsartTxDma(uartPort_t *s)
+{
+ DMA_Cmd(s->txDMAStream, DISABLE);
+
+ if (s->port.txBufferHead != s->port.txBufferTail)
+ uartStartTxDMA(s);
+ else
+ s->txDMAEmpty = true;
+}
+
+uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ uartPort_t *s;
+ NVIC_InitTypeDef NVIC_InitStructure;
+
+ uartDevice_t *uart = uartHardwareMap[device];
+ if (!uart) return NULL;
+
+ s = &(uart->port);
+ s->port.vTable = uartVTable;
+
+ s->port.baudRate = baudRate;
+
+ s->port.rxBuffer = uart->rxBuffer;
+ s->port.txBuffer = uart->txBuffer;
+ s->port.rxBufferSize = sizeof(uart->rxBuffer);
+ s->port.txBufferSize = sizeof(uart->txBuffer);
+
+ s->USARTx = uart->dev;
+ if (uart->rxDMAStream) {
+ s->rxDMAChannel = uart->DMAChannel;
+ s->rxDMAStream = uart->rxDMAStream;
+ }
+ s->txDMAChannel = uart->DMAChannel;
+ s->txDMAStream = uart->txDMAStream;
+
+ s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
+ s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
+
+ IO_t tx = IOGetByTag(uart->tx);
+ IO_t rx = IOGetByTag(uart->rx);
+
+ if (uart->rcc_apb2)
+ RCC_ClockCmd(uart->rcc_apb2, ENABLE);
+
+ if (uart->rcc_apb1)
+ RCC_ClockCmd(uart->rcc_apb1, ENABLE);
+
+ if (uart->rcc_ahb1)
+ RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE);
+
+ if (options & SERIAL_BIDIR) {
+ IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
+ IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af);
+ }
+ else {
+ if (mode & MODE_TX) {
+ IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART);
+ IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
+ }
+
+ if (mode & MODE_RX) {
+ IOInit(rx, OWNER_SERIAL_RX, RESOURCE_USART);
+ IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
+ }
+ }
+
+ // DMA TX Interrupt
+ NVIC_InitStructure.NVIC_IRQChannel = uart->txIrq;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(uart->txPriority);
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(uart->txPriority);
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+
+ if (!(s->rxDMAChannel)) {
+ NVIC_InitStructure.NVIC_IRQChannel = uart->rxIrq;
+ NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(uart->rxPriority);
+ NVIC_InitStructure.NVIC_IRQChannelSubPriority = NVIC_PRIORITY_SUB(uart->rxPriority);
+ NVIC_InitStructure.NVIC_IRQChannelCmd = ENABLE;
+ NVIC_Init(&NVIC_InitStructure);
+ }
+
+ return s;
+}
+
+#ifdef USE_USART1
+uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_1, baudRate, mode, options);
+}
+
+// USART1 Tx DMA Handler
+void DMA2_Stream7_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
+ }
+}
+
+// USART1 Rx/Tx IRQ Handler
+void USART1_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port);
+ usartIrqHandler(s);
+}
+#endif
+
+#ifdef USE_USART2
+// USART2 - GPS or Spektrum or ?? (RX + TX by IRQ)
+uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_2, baudRate, mode, options);
+}
+
+// USART2 Tx DMA Handler
+void DMA1_Stream6_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
+ }
+}
+
+void USART2_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port);
+ usartIrqHandler(s);
+}
+#endif
+
+#ifdef USE_USART3
+// USART3
+uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_3, baudRate, mode, options);
+}
+
+// USART3 Tx DMA Handler
+void DMA1_Stream3_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF3))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF3);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF3);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF3)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF3);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF3)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF3);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF3)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF3);
+ }
+}
+
+void USART3_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port);
+ usartIrqHandler(s);
+}
+#endif
+
+#ifdef USE_USART4
+// USART4
+uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_4, baudRate, mode, options);
+}
+
+// USART4 Tx DMA Handler
+void DMA1_Stream4_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF4))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF4);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF4);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF4)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF4);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF4)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF4);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF4)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF4);
+ }
+}
+
+void UART4_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port);
+ usartIrqHandler(s);
+}
+#endif
+
+#ifdef USE_USART5
+// USART5
+uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_5, baudRate, mode, options);
+}
+
+// USART5 Tx DMA Handler
+void DMA1_Stream7_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF7))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF7);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF7);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF7);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF7);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF7)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF7);
+ }
+}
+
+void UART5_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port);
+ usartIrqHandler(s);
+}
+#endif
+
+#ifdef USE_USART6
+// USART6
+uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options)
+{
+ return serialUSART(UARTDEV_6, baudRate, mode, options);
+}
+
+// USART6 Tx DMA Handler
+void DMA2_Stream6_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
+ if(DMA_GetITStatus(s->txDMAStream,DMA_IT_TCIF6))
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TCIF6);
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_HTIF6);
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_FEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_FEIF6);
+ }
+ handleUsartTxDma(s);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_TEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_TEIF6);
+ }
+ if(DMA_GetFlagStatus(s->txDMAStream,DMA_IT_DMEIF6)==SET)
+ {
+ DMA_ClearITPendingBit(s->txDMAStream,DMA_IT_DMEIF6);
+ }
+}
+
+void USART6_IRQHandler(void)
+{
+ uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port);
+ usartIrqHandler(s);
+}
+#endif
diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c
index c3f632b1c8..0954027753 100644
--- a/src/main/drivers/serial_usb_vcp.c
+++ b/src/main/drivers/serial_usb_vcp.c
@@ -26,8 +26,12 @@
#include "common/utils.h"
#include "usb_core.h"
+#ifdef STM32F4
+#include "usbd_cdc_vcp.h"
+#else
#include "usb_init.h"
#include "hw_config.h"
+#endif
#include "drivers/system.h"
@@ -173,10 +177,18 @@ serialPort_t *usbVcpOpen(void)
{
vcpPort_t *s;
- Set_System();
- Set_USBClock();
- USB_Interrupts_Config();
- USB_Init();
+#ifdef STM32F4
+ USBD_Init(&USB_OTG_dev,
+ USB_OTG_FS_CORE_ID,
+ &USR_desc,
+ &USBD_CDC_cb,
+ &USR_cb);
+#else
+ Set_System();
+ Set_USBClock();
+ USB_Interrupts_Config();
+ USB_Init();
+#endif
s = &vcpPort;
s->port.vTable = usbVTable;
diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c
index e854c5e217..b1ae263888 100644
--- a/src/main/drivers/system.c
+++ b/src/main/drivers/system.c
@@ -115,6 +115,12 @@ void systemInit(void)
// cache RCC->CSR value to use it in isMPUSoftreset() and others
cachedRccCsrValue = RCC->CSR;
+#ifdef STM32F4
+ /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
+ extern void *isr_vector_table_base;
+ NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
+ RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
+#endif
RCC_ClearFlag();
enableGPIOPowerUsageAndNoiseReductions();
diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c
new file mode 100644
index 0000000000..7880200618
--- /dev/null
+++ b/src/main/drivers/system_stm32f4xx.c
@@ -0,0 +1,166 @@
+/*
+ * 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 .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "gpio.h"
+
+
+#include "exti.h"
+#include "debug.h"
+#include "sensor.h"
+#include "accgyro.h"
+#include "accgyro_mpu.h"
+#include "accgyro_spi_mpu6000.h"
+#include "accgyro_mpu6500.h"
+#include "accgyro_spi_mpu9250.h"
+
+
+#define AIRCR_VECTKEY_MASK ((uint32_t)0x05FA0000)
+
+void systemReset(void)
+{
+ if (mpuConfiguration.reset)
+ mpuConfiguration.reset();
+
+ __disable_irq();
+ NVIC_SystemReset();
+}
+
+void systemResetToBootloader(void)
+{
+ if (mpuConfiguration.reset)
+ mpuConfiguration.reset();
+
+ *((uint32_t *)0x2001FFFC) = 0xDEADBEEF; // 128KB SRAM STM32F4XX
+
+ __disable_irq();
+ NVIC_SystemReset();
+}
+
+void enableGPIOPowerUsageAndNoiseReductions(void)
+{
+
+ RCC_AHB1PeriphClockCmd(
+ RCC_AHB1Periph_GPIOA |
+ RCC_AHB1Periph_GPIOB |
+ RCC_AHB1Periph_GPIOC |
+ RCC_AHB1Periph_GPIOD |
+ RCC_AHB1Periph_GPIOE |
+#ifdef STM32F40_41xxx
+ RCC_AHB1Periph_GPIOF |
+ RCC_AHB1Periph_GPIOG |
+ RCC_AHB1Periph_GPIOH |
+ RCC_AHB1Periph_GPIOI |
+#endif
+ RCC_AHB1Periph_CRC |
+ RCC_AHB1Periph_FLITF |
+ RCC_AHB1Periph_SRAM1 |
+ RCC_AHB1Periph_SRAM2 |
+ RCC_AHB1Periph_BKPSRAM |
+ RCC_AHB1Periph_DMA1 |
+ RCC_AHB1Periph_DMA2 |
+ 0, ENABLE
+ );
+
+ RCC_AHB2PeriphClockCmd(
+ 0, ENABLE);
+#ifdef STM32F40_41xxx
+ RCC_AHB3PeriphClockCmd(
+ 0, ENABLE);
+#endif
+ RCC_APB1PeriphClockCmd(
+ RCC_APB1Periph_TIM2 |
+ RCC_APB1Periph_TIM3 |
+ RCC_APB1Periph_TIM4 |
+ RCC_APB1Periph_TIM5 |
+ RCC_APB1Periph_TIM6 |
+ RCC_APB1Periph_TIM7 |
+ RCC_APB1Periph_TIM12 |
+ RCC_APB1Periph_TIM13 |
+ RCC_APB1Periph_TIM14 |
+ RCC_APB1Periph_WWDG |
+ RCC_APB1Periph_SPI2 |
+ RCC_APB1Periph_SPI3 |
+ RCC_APB1Periph_USART2 |
+ RCC_APB1Periph_USART3 |
+ RCC_APB1Periph_UART4 |
+ RCC_APB1Periph_UART5 |
+ RCC_APB1Periph_I2C1 |
+ RCC_APB1Periph_I2C2 |
+ RCC_APB1Periph_I2C3 |
+ RCC_APB1Periph_CAN1 |
+ RCC_APB1Periph_CAN2 |
+ RCC_APB1Periph_PWR |
+ RCC_APB1Periph_DAC |
+ 0, ENABLE);
+
+ RCC_APB2PeriphClockCmd(
+ RCC_APB2Periph_TIM1 |
+ RCC_APB2Periph_TIM8 |
+ RCC_APB2Periph_USART1 |
+ RCC_APB2Periph_USART6 |
+ RCC_APB2Periph_ADC |
+ RCC_APB2Periph_ADC1 |
+ RCC_APB2Periph_ADC2 |
+ RCC_APB2Periph_ADC3 |
+ RCC_APB2Periph_SDIO |
+ RCC_APB2Periph_SPI1 |
+ RCC_APB2Periph_SYSCFG |
+ RCC_APB2Periph_TIM9 |
+ RCC_APB2Periph_TIM10 |
+ RCC_APB2Periph_TIM11 |
+ 0, ENABLE);
+
+ GPIO_InitTypeDef GPIO_InitStructure;
+ GPIO_StructInit(&GPIO_InitStructure);
+ GPIO_InitStructure.GPIO_PuPd = GPIO_PuPd_UP; // default is un-pulled input
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
+ GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_11 | GPIO_Pin_12); // leave USB D+/D- alone
+
+ GPIO_InitStructure.GPIO_Pin &= ~(GPIO_Pin_13 | GPIO_Pin_14); // leave JTAG pins alone
+ GPIO_Init(GPIOA, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
+ GPIO_Init(GPIOB, &GPIO_InitStructure);
+
+ GPIO_InitStructure.GPIO_Pin = GPIO_Pin_All;
+ GPIO_Init(GPIOC, &GPIO_InitStructure);
+ GPIO_Init(GPIOD, &GPIO_InitStructure);
+ GPIO_Init(GPIOE, &GPIO_InitStructure);
+
+#ifdef STM32F40_41xxx
+ GPIO_Init(GPIOF, &GPIO_InitStructure);
+ GPIO_Init(GPIOG, &GPIO_InitStructure);
+ GPIO_Init(GPIOH, &GPIO_InitStructure);
+ GPIO_Init(GPIOI, &GPIO_InitStructure);
+#endif
+
+}
+
+bool isMPUSoftReset(void)
+{
+ if (RCC->CSR & RCC_CSR_SFTRSTF)
+ return true;
+ else
+ return false;
+}
diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h
index 89317c507d..882b0d6105 100644
--- a/src/main/drivers/timer.h
+++ b/src/main/drivers/timer.h
@@ -23,12 +23,17 @@
typedef uint16_t captureCompare_t; // 16 bit on both 103 and 303, just register access must be 32bit sometimes (use timCCR_t)
-#if defined(STM32F303)
+#if defined(STM32F4)
typedef uint32_t timCCR_t;
typedef uint32_t timCCER_t;
typedef uint32_t timSR_t;
typedef uint32_t timCNT_t;
-#elif defined(STM32F10X)
+#elif defined(STM32F3)
+typedef uint32_t timCCR_t;
+typedef uint32_t timCCER_t;
+typedef uint32_t timSR_t;
+typedef uint32_t timCNT_t;
+#elif defined(STM32F1)
typedef uint16_t timCCR_t;
typedef uint16_t timCCER_t;
typedef uint16_t timSR_t;
@@ -65,7 +70,11 @@ typedef struct {
uint8_t irq;
uint8_t outputEnable;
GPIO_Mode gpioInputMode;
-#ifdef STM32F303
+#ifdef STM32F3
+ uint8_t gpioPinSource; // TODO - this can be removed and pinSource calculated from pin
+ uint8_t alternateFunction;
+#endif
+#ifdef STM32F4
uint8_t gpioPinSource; // TODO - this can be removed and pinSource calculated from pin
uint8_t alternateFunction;
#endif
diff --git a/src/main/drivers/timer_stm32f4xx.c b/src/main/drivers/timer_stm32f4xx.c
new file mode 100644
index 0000000000..beb5701760
--- /dev/null
+++ b/src/main/drivers/timer_stm32f4xx.c
@@ -0,0 +1,67 @@
+/*
+ modified version of StdPeriph function is located here.
+ TODO - what license does apply here?
+ original file was lincesed under MCD-ST Liberty SW License Agreement V2
+ http://www.st.com/software_license_agreement_liberty_v2
+*/
+
+#include "stm32f4xx.h"
+
+/**
+ * @brief Selects the TIM Output Compare Mode.
+ * @note This function does NOT disable the selected channel before changing the Output
+ * Compare Mode.
+ * @param TIMx: where x can be 1 to 17 except 6 and 7 to select the TIM peripheral.
+ * @param TIM_Channel: specifies the TIM Channel
+ * This parameter can be one of the following values:
+ * @arg TIM_Channel_1: TIM Channel 1
+ * @arg TIM_Channel_2: TIM Channel 2
+ * @arg TIM_Channel_3: TIM Channel 3
+ * @arg TIM_Channel_4: TIM Channel 4
+ * @param TIM_OCMode: specifies the TIM Output Compare Mode.
+ * This parameter can be one of the following values:
+ * @arg TIM_OCMode_Timing
+ * @arg TIM_OCMode_Active
+ * @arg TIM_OCMode_Toggle
+ * @arg TIM_OCMode_PWM1
+ * @arg TIM_OCMode_PWM2
+ * @arg TIM_ForcedAction_Active
+ * @arg TIM_ForcedAction_InActive
+ * @retval None
+ */
+
+#define CCMR_Offset ((uint16_t)0x0018)
+
+void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode)
+{
+ uint32_t tmp = 0;
+
+ /* Check the parameters */
+ assert_param(IS_TIM_LIST8_PERIPH(TIMx));
+ assert_param(IS_TIM_CHANNEL(TIM_Channel));
+ assert_param(IS_TIM_OCM(TIM_OCMode));
+
+ tmp = (uint32_t) TIMx;
+ tmp += CCMR_Offset;
+
+ if((TIM_Channel == TIM_Channel_1) ||(TIM_Channel == TIM_Channel_3))
+ {
+ tmp += (TIM_Channel>>1);
+
+ /* Reset the OCxM bits in the CCMRx register */
+ *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC1M);
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *(__IO uint32_t *) tmp |= TIM_OCMode;
+ }
+ else
+ {
+ tmp += (uint16_t)(TIM_Channel - (uint16_t)4)>> (uint16_t)1;
+
+ /* Reset the OCxM bits in the CCMRx register */
+ *(__IO uint32_t *) tmp &= (uint32_t)~((uint32_t)TIM_CCMR1_OC2M);
+
+ /* Configure the OCxM bits in the CCMRx register */
+ *(__IO uint32_t *) tmp |= (uint16_t)(TIM_OCMode << 8);
+ }
+}
diff --git a/src/main/drivers/timer_stm32f4xx.h b/src/main/drivers/timer_stm32f4xx.h
new file mode 100644
index 0000000000..52094cbc03
--- /dev/null
+++ b/src/main/drivers/timer_stm32f4xx.h
@@ -0,0 +1,6 @@
+
+#pragma once
+
+#include "stm32f4xx.h"
+
+void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint16_t TIM_OCMode);