diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 4081d7592..d97cb39a7 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -632,7 +632,7 @@ static void writeInterframe(void) arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT); blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT); - /* + /* * The PID I field changes very slowly, most of the time +-2, so use an encoding * that can pack all three fields into one byte in that situation. */ @@ -1315,7 +1315,7 @@ static void blackboxCheckAndLogFlightMode() } } -/* +/* * Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control * the portion of logged loop iterations. */ diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 7f9b1ec5b..cd4f05d98 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -507,7 +507,7 @@ void blackboxWriteFloat(float value) /** * If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now. - * + * * Intended to be called regularly for the blackbox device to perform housekeeping. */ void blackboxDeviceFlush(void) diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 888847e07..52990c6ac 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -231,7 +231,7 @@ int32_t quickMedianFilter5(int32_t * v) QMF_SORT(p[0], p[1]); QMF_SORT(p[3], p[4]); QMF_SORT(p[0], p[3]); QMF_SORT(p[1], p[4]); QMF_SORT(p[1], p[2]); QMF_SORT(p[2], p[3]); - QMF_SORT(p[1], p[2]); + QMF_SORT(p[1], p[2]); return p[2]; } @@ -279,7 +279,7 @@ float quickMedianFilter5f(float * v) QMF_SORTF(p[0], p[1]); QMF_SORTF(p[3], p[4]); QMF_SORTF(p[0], p[3]); QMF_SORTF(p[1], p[4]); QMF_SORTF(p[1], p[2]); QMF_SORTF(p[2], p[3]); - QMF_SORTF(p[1], p[2]); + QMF_SORTF(p[1], p[2]); return p[2]; } diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 7847fb303..e11d49d15 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -56,7 +56,7 @@ typedef void (*putcf) (void *, char); static putcf stdout_putf; static void *stdout_putp; -// print bf, padded from left to at least n characters. +// print bf, padded from left to at least n characters. // padding is zero ('0') if z!=0, space (' ') otherwise static int putchw(void *putp, putcf putf, int n, char z, char *bf) { diff --git a/src/main/config/config.c b/src/main/config/config.c index 7841ef932..3cdc4f82a 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -159,7 +159,7 @@ size_t custom_flash_memory_address = 0; #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) #else // use the last flash pages for storage -#ifndef CONFIG_START_FLASH_ADDRESS +#ifndef CONFIG_START_FLASH_ADDRESS #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) #endif #endif @@ -349,7 +349,7 @@ void resetSerialConfig(serialConfig_t *serialConfig) serialConfig->reboot_character = 'R'; } -static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) +static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; controlRateConfig->rcYawRate8 = 100; @@ -366,7 +366,7 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) } -void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) +void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) { rcControlsConfig->deadband = 0; rcControlsConfig->yaw_deadband = 0; @@ -374,7 +374,7 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) rcControlsConfig->alt_hold_fast_change = 1; } -void resetMixerConfig(mixerConfig_t *mixerConfig) +void resetMixerConfig(mixerConfig_t *mixerConfig) { mixerConfig->yaw_motor_direction = 1; #ifdef USE_SERVOS @@ -658,7 +658,7 @@ static void resetConf(void) targetConfiguration(); #endif - + // copy first profile into remaining profile for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 4f8f4903f..6632ca3af 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -137,7 +137,7 @@ typedef struct master_t { profile_t profile[MAX_PROFILE_COUNT]; uint8_t current_profile_index; - + modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT]; @@ -161,9 +161,9 @@ typedef struct master_t { uint8_t magic_ef; // magic number, should be 0xEF uint8_t chk; // XOR checksum - + char name[MAX_NAME_LENGTH+1]; - + } master_t; extern master_t masterConfig; diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 9a3cd5725..1c705ef13 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -252,7 +252,7 @@ void mpuIntExtiInit(void) EXTIEnable(mpuIntIO, true); #endif - mpuExtiInitDone = true; + mpuExtiInitDone = true; } static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data) diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 917c06f1a..132c9e13a 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -18,7 +18,7 @@ #pragma once #include "exti.h" - + // MPU6050 #define MPU_RA_WHO_AM_I 0x75 #define MPU_RA_WHO_AM_I_LEGACY 0x00 @@ -119,7 +119,7 @@ typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data); typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data); -typedef void(*mpuResetFuncPtr)(void); +typedef void(*mpuResetFuncPtr)(void); typedef struct mpuConfiguration_s { uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each diff --git a/src/main/drivers/accgyro_mpu6050.c b/src/main/drivers/accgyro_mpu6050.c index 3cc3ac8f6..78e8b8e80 100644 --- a/src/main/drivers/accgyro_mpu6050.c +++ b/src/main/drivers/accgyro_mpu6050.c @@ -104,7 +104,7 @@ static void mpu6050GyroInit(uint8_t lpf) delay(100); ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference) ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) - delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure + delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz) ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index b48338091..dc21901e7 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -158,7 +158,7 @@ bool mpu6000SpiDetect(void) uint8_t in; uint8_t attemptsRemaining = 5; -#ifdef MPU6000_CS_PIN +#ifdef MPU6000_CS_PIN mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN)); #endif IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); @@ -253,7 +253,7 @@ static void mpu6000AccAndGyroInit(void) { delayMicroseconds(15); #endif - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); delayMicroseconds(1); mpuSpi6000InitDone = true; diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index b5beca294..0406e6023 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -54,7 +54,7 @@ static IO_t mpuSpi9250CsPin = IO_NONE; #define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin) #define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin) -void mpu9250ResetGyro(void) +void mpu9250ResetGyro(void) { // Device Reset mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); @@ -123,7 +123,7 @@ void mpu9250SpiAccInit(acc_t *acc) acc->acc_1G = 512 * 8; } -bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) +bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) { uint8_t in; uint8_t attemptsRemaining = 20; @@ -176,7 +176,7 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) { verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. #endif - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); mpuSpi9250InitDone = true; //init done } @@ -208,7 +208,7 @@ bool mpu9250SpiDetect(void) } } while (attemptsRemaining--); - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); return true; } diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 258c8acc8..146ada62b 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -24,14 +24,14 @@ #define ADC_TAG_MAP_COUNT 16 #elif defined(STM32F3) #define ADC_TAG_MAP_COUNT 39 -#else +#else #define ADC_TAG_MAP_COUNT 10 -#endif +#endif typedef enum ADCDevice { ADCINVALID = -1, ADCDEV_1 = 0, -#if defined(STM32F3) +#if defined(STM32F3) ADCDEV_2, ADCDEV_MAX = ADCDEV_2, #elif defined(STM32F4) diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index bc23c2b96..3104bcd5e 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -35,13 +35,13 @@ #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } }; ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; /* TODO -- ADC2 available on large 10x devices. @@ -51,7 +51,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) return ADCINVALID; } -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12 { DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12 { DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12 @@ -61,7 +61,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12 { DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12 { DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12 - { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 + { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 }; // Driver for STM32F103CB onboard ADC diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 5cbe50607..f58a8086d 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -37,12 +37,12 @@ #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, - { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, + { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } }; -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1 { DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1 { DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1 @@ -86,7 +86,7 @@ const adcTagMap_t adcTagMap[] = { ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; if (instance == ADC2) @@ -133,7 +133,7 @@ void adcInit(drv_adc_config_t *init) if (device == ADCINVALID) return; - adcDevice_t adc = adcHardware[device]; + adcDevice_t adc = adcHardware[device]; for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index 197ff1299..968f05a67 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -36,13 +36,13 @@ #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, - //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, + //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } }; /* note these could be packed up for saving space */ -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { /* { DEFIO_TAG_E__PF3, ADC_Channel_9 }, { DEFIO_TAG_E__PF4, ADC_Channel_14 }, @@ -73,7 +73,7 @@ const adcTagMap_t adcTagMap[] = { ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; /* if (instance == ADC2) // TODO add ADC2 and 3 @@ -126,7 +126,7 @@ void adcInit(drv_adc_config_t *init) if (device == ADCINVALID) return; - adcDevice_t adc = adcHardware[device]; + adcDevice_t adc = adcHardware[device]; for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 4c3e77985..9b35646b6 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -35,7 +35,7 @@ #ifdef BARO -#if defined(BARO_EOC_GPIO) +#if defined(BARO_EOC_GPIO) static IO_t eocIO; @@ -49,7 +49,7 @@ void bmp085_extiHandler(extiCallbackRec_t* cb) isConversionComplete = true; } -bool bmp085TestEOCConnected(const bmp085Config_t *config); +bool bmp085TestEOCConnected(const bmp085Config_t *config); # endif typedef struct { @@ -139,7 +139,7 @@ static IO_t xclrIO; #endif -void bmp085InitXclrIO(const bmp085Config_t *config) +void bmp085InitXclrIO(const bmp085Config_t *config) { if (!xclrIO && config && config->xclrIO) { xclrIO = IOGetByTag(config->xclrIO); @@ -184,7 +184,7 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro) delay(20); // datasheet says 10ms, we'll be careful and do 20. - ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ + ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ if (ack) { bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.oversampling_setting = 3; diff --git a/src/main/drivers/barometer_bmp085.h b/src/main/drivers/barometer_bmp085.h index 328bffb13..ffe863d1b 100644 --- a/src/main/drivers/barometer_bmp085.h +++ b/src/main/drivers/barometer_bmp085.h @@ -19,7 +19,7 @@ typedef struct bmp085Config_s { ioTag_t xclrIO; - ioTag_t eocIO; + ioTag_t eocIO; } bmp085Config_t; bool bmp085Detect(const bmp085Config_t *config, baro_t *baro); diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index bdfc75dfa..86f7a6618 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -26,7 +26,7 @@ #ifndef I2C_DEVICE #define I2C_DEVICE I2CINVALID -#endif +#endif typedef enum I2CDevice { I2CINVALID = -1, diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 74a9f3655..7daea6fa9 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -47,35 +47,35 @@ static void i2cUnstick(IO_t scl, IO_t sda); #define IOCFG_I2C IOCFG_AF_OD #endif -#ifndef I2C1_SCL -#define I2C1_SCL PB8 +#ifndef I2C1_SCL +#define I2C1_SCL PB8 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB9 +#ifndef I2C1_SDA +#define I2C1_SDA PB9 #endif #else -#ifndef I2C1_SCL -#define I2C1_SCL PB6 +#ifndef I2C1_SCL +#define I2C1_SCL PB6 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB7 +#ifndef I2C1_SDA +#define I2C1_SDA PB7 #endif #endif -#ifndef I2C2_SCL -#define I2C2_SCL PB10 +#ifndef I2C2_SCL +#define I2C2_SCL PB10 #endif -#ifndef I2C2_SDA +#ifndef I2C2_SDA #define I2C2_SDA PB11 #endif #ifdef STM32F4 -#ifndef I2C3_SCL +#ifndef I2C3_SCL #define I2C3_SCL PA8 #endif -#ifndef I2C3_SDA -#define I2C3_SDA PB4 +#ifndef I2C3_SDA +#define I2C3_SDA PB4 #endif #endif @@ -93,7 +93,7 @@ static i2cState_t i2cState[] = { { false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 } -}; +}; void I2C1_ER_IRQHandler(void) { i2c_er_handler(I2CDEV_1); @@ -121,7 +121,7 @@ void I2C3_EV_IRQHandler(void) { } #endif -static bool i2cHandleHardwareFailure(I2CDevice device) +static bool i2cHandleHardwareFailure(I2CDevice device) { i2cErrorCount++; // reinit peripheral + clock out garbage @@ -129,7 +129,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device) return false; } -bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) +bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) { if (device == I2CINVALID) @@ -138,7 +138,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint32_t timeout = I2C_DEFAULT_TIMEOUT; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; i2cState_t *state; state = &(i2cState[device]); @@ -171,12 +171,12 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, return !(state->error); } -bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) +bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) { return i2cWriteBuffer(device, addr_, reg_, 1, &data); } -bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) +bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) { if (device == I2CINVALID) return false; @@ -369,7 +369,7 @@ void i2c_ev_handler(I2CDevice device) { } } -void i2cInit(I2CDevice device) +void i2cInit(I2CDevice device) { if (device == I2CINVALID) return; @@ -392,7 +392,7 @@ void i2cInit(I2CDevice device) I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); i2cUnstick(scl, sda); - + // Init pins #ifdef STM32F4 IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index d645a7050..524df1bc8 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -39,18 +39,18 @@ #define I2C_SHORT_TIMEOUT ((uint32_t)0x1000) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) -#define I2C_GPIO_AF GPIO_AF_4 +#define I2C_GPIO_AF GPIO_AF_4 -#ifndef I2C1_SCL -#define I2C1_SCL PB6 +#ifndef I2C1_SCL +#define I2C1_SCL PB6 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB7 +#ifndef I2C1_SDA +#define I2C1_SDA PB7 #endif -#ifndef I2C2_SCL -#define I2C2_SCL PF4 +#ifndef I2C2_SCL +#define I2C2_SCL PF4 #endif -#ifndef I2C2_SDA +#ifndef I2C2_SDA #define I2C2_SDA PA10 #endif @@ -82,7 +82,7 @@ void i2cInit(I2CDevice device) I2C_TypeDef *I2Cx; I2Cx = i2c->dev; - + IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); @@ -108,7 +108,7 @@ void i2cInit(I2CDevice device) I2C_Init(I2Cx, &i2cInit); I2C_StretchClockCmd(I2Cx, ENABLE); - + I2C_Cmd(I2Cx, ENABLE); } @@ -122,7 +122,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) addr_ <<= 1; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; @@ -188,7 +188,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* addr_ <<= 1; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 005f7936b..690f25b52 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -36,7 +36,7 @@ #ifndef GPIO_AF_SPI3 #define GPIO_AF_SPI3 GPIO_AF_6 #endif -#endif +#endif #ifndef SPI1_SCK_PIN #define SPI1_NSS_PIN PA4 @@ -84,7 +84,7 @@ static spiDevice_t spiHardwareMap[] = { SPIDevice spiDeviceByInstance(SPI_TypeDef *instance) { - if (instance == SPI1) + if (instance == SPI1) return SPIDEV_1; if (instance == SPI2) diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 422b4c45a..726a5a180 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -65,7 +65,7 @@ typedef struct dmaChannelDescriptor_s { #define DMA_IT_TEIF ((uint32_t)0x00000008) #define DMA_IT_DMEIF ((uint32_t)0x00000004) #define DMA_IT_FEIF ((uint32_t)0x00000001) - + #else typedef enum { diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index cd97ba9b7..ce665bb07 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -24,22 +24,22 @@ static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS]; #if defined(STM32F1) || defined(STM32F4) static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { - EXTI0_IRQn, - EXTI1_IRQn, - EXTI2_IRQn, - EXTI3_IRQn, + EXTI0_IRQn, + EXTI1_IRQn, + EXTI2_IRQn, + EXTI3_IRQn, EXTI4_IRQn, - EXTI9_5_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn }; #elif defined(STM32F3) static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { - EXTI0_IRQn, - EXTI1_IRQn, - EXTI2_TS_IRQn, - EXTI3_IRQn, + EXTI0_IRQn, + EXTI1_IRQn, + EXTI2_TS_IRQn, + EXTI3_IRQn, EXTI4_IRQn, - EXTI9_5_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn }; #else diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 806c777da..29620fbe1 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -199,7 +199,7 @@ static bool m25p16_readIdentification() bool m25p16_init() { -#ifdef M25P16_CS_PIN +#ifdef M25P16_CS_PIN m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN)); #endif IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0); diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index fbbff6ffd..967c87680 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -20,7 +20,7 @@ #include "platform.h" -#ifdef INVERTER +#ifdef INVERTER #include "io.h" #include "io_impl.h" diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 07c53a203..af9deca81 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -52,7 +52,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO -#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 1b3cca2bc..0c880fd78 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -12,7 +12,7 @@ typedef struct ioRec_s { GPIO_TypeDef *gpio; uint16_t pin; resourceOwner_t owner; - resourceType_t resource; + resourceType_t resource; uint8_t index; } ioRec_t; @@ -26,7 +26,7 @@ int IO_GPIO_PortSource(IO_t io); #if defined(STM32F3) || defined(STM32F4) int IO_EXTI_PortSourceGPIO(IO_t io); -int IO_EXTI_PinSource(IO_t io); +int IO_EXTI_PinSource(IO_t io); #endif GPIO_TypeDef* IO_GPIO(IO_t io); diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 8b1bdc5ab..a6b2a6892 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -27,12 +27,12 @@ static const IO_t leds[] = { DEFIO_IO(LED0), #else DEFIO_IO(NONE), -#endif +#endif #ifdef LED1 DEFIO_IO(LED1), #else DEFIO_IO(NONE), -#endif +#endif #ifdef LED2 DEFIO_IO(LED2), #else diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index 3a888bd21..377954ce9 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -31,8 +31,8 @@ #ifdef LED_STRIP -#if !defined(WS2811_PIN) -#define WS2811_PIN PA0 +#if !defined(WS2811_PIN) +#define WS2811_PIN PA0 #define WS2811_TIMER TIM5 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER #define WS2811_DMA_STREAM DMA1_Stream2 diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index b9f521273..cfa2e95e2 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -147,7 +147,7 @@ void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor) { } #endif -void max7456_init(uint8_t video_system) +void max7456_init(uint8_t video_system) { uint8_t max_screen_rows; uint8_t srdata = 0; diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 59e1167a2..d6f41808c 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -95,7 +95,7 @@ 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 ] if (init->airplane) i = 2; // switch to air hardware config @@ -260,7 +260,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (init->useChannelForwarding && !init->airplane) { #if defined(NAZE) && defined(WS2811_TIMER) // if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14 - if (init->useLEDStrip) { + if (init->useLEDStrip) { if (timerIndex >= PWM13 && timerIndex <= PWM14) { type = MAP_TO_SERVO_OUTPUT; } diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index ffd16e74d..5a3f402e9 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -117,7 +117,7 @@ enum { PWM13, PWM14, PWM15, - PWM16, + PWM16, PWM17, PWM18, PWM19, diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index c5ebfcd17..ecd0447a9 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -131,7 +131,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 p->tim = timerHardware->tim; *p->ccr = 0; - + return p; } diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index d940ddc85..878d5eacf 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void) #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0); - IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); + IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); #endif } @@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void) #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0); - IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); + IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); #endif } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 09b6663e8..852a60831 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -114,8 +114,8 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) { if (options & SERIAL_BIDIR) { - ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, - (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, + ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, + (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP ); diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 3adecfc89..f79a99ae6 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -64,17 +64,17 @@ typedef struct uartDevice_s { //static uartPort_t uartPort[MAX_UARTS]; #ifdef USE_UART1 -static uartDevice_t uart1 = -{ +static uartDevice_t uart1 = +{ .DMAChannel = DMA_Channel_4, .txDMAStream = DMA2_Stream7, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA2_Stream5, #endif - .dev = USART1, - .rx = IO_TAG(UART1_RX_PIN), - .tx = IO_TAG(UART1_TX_PIN), - .af = GPIO_AF_USART1, + .dev = USART1, + .rx = IO_TAG(UART1_RX_PIN), + .tx = IO_TAG(UART1_TX_PIN), + .af = GPIO_AF_USART1, #ifdef UART1_AHB1_PERIPHERALS .rcc_ahb1 = UART1_AHB1_PERIPHERALS, #endif @@ -87,17 +87,17 @@ static uartDevice_t uart1 = #endif #ifdef USE_UART2 -static uartDevice_t uart2 = -{ +static uartDevice_t uart2 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART2_RX_DMA .rxDMAStream = DMA1_Stream5, #endif .txDMAStream = DMA1_Stream6, - .dev = USART2, - .rx = IO_TAG(UART2_RX_PIN), - .tx = IO_TAG(UART2_TX_PIN), - .af = GPIO_AF_USART2, + .dev = USART2, + .rx = IO_TAG(UART2_RX_PIN), + .tx = IO_TAG(UART2_TX_PIN), + .af = GPIO_AF_USART2, #ifdef UART2_AHB1_PERIPHERALS .rcc_ahb1 = UART2_AHB1_PERIPHERALS, #endif @@ -110,17 +110,17 @@ static uartDevice_t uart2 = #endif #ifdef USE_UART3 -static uartDevice_t uart3 = -{ +static uartDevice_t uart3 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART3_RX_DMA .rxDMAStream = DMA1_Stream1, #endif .txDMAStream = DMA1_Stream3, - .dev = USART3, - .rx = IO_TAG(UART3_RX_PIN), - .tx = IO_TAG(UART3_TX_PIN), - .af = GPIO_AF_USART3, + .dev = USART3, + .rx = IO_TAG(UART3_RX_PIN), + .tx = IO_TAG(UART3_TX_PIN), + .af = GPIO_AF_USART3, #ifdef UART3_AHB1_PERIPHERALS .rcc_ahb1 = UART3_AHB1_PERIPHERALS, #endif @@ -133,17 +133,17 @@ static uartDevice_t uart3 = #endif #ifdef USE_UART4 -static uartDevice_t uart4 = -{ +static uartDevice_t uart4 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream2, #endif .txDMAStream = DMA1_Stream4, - .dev = UART4, - .rx = IO_TAG(UART4_RX_PIN), - .tx = IO_TAG(UART4_TX_PIN), - .af = GPIO_AF_UART4, + .dev = UART4, + .rx = IO_TAG(UART4_RX_PIN), + .tx = IO_TAG(UART4_TX_PIN), + .af = GPIO_AF_UART4, #ifdef UART4_AHB1_PERIPHERALS .rcc_ahb1 = UART4_AHB1_PERIPHERALS, #endif @@ -156,17 +156,17 @@ static uartDevice_t uart4 = #endif #ifdef USE_UART5 -static uartDevice_t uart5 = -{ +static uartDevice_t uart5 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream0, #endif .txDMAStream = DMA2_Stream7, - .dev = UART5, - .rx = IO_TAG(UART5_RX_PIN), - .tx = IO_TAG(UART5_TX_PIN), - .af = GPIO_AF_UART5, + .dev = UART5, + .rx = IO_TAG(UART5_RX_PIN), + .tx = IO_TAG(UART5_TX_PIN), + .af = GPIO_AF_UART5, #ifdef UART5_AHB1_PERIPHERALS .rcc_ahb1 = UART5_AHB1_PERIPHERALS, #endif @@ -179,17 +179,17 @@ static uartDevice_t uart5 = #endif #ifdef USE_UART6 -static uartDevice_t uart6 = -{ +static uartDevice_t uart6 = +{ .DMAChannel = DMA_Channel_5, #ifdef USE_UART6_RX_DMA .rxDMAStream = DMA2_Stream1, #endif .txDMAStream = DMA2_Stream6, - .dev = USART6, - .rx = IO_TAG(UART6_RX_PIN), - .tx = IO_TAG(UART6_TX_PIN), - .af = GPIO_AF_USART6, + .dev = USART6, + .rx = IO_TAG(UART6_RX_PIN), + .tx = IO_TAG(UART6_TX_PIN), + .af = GPIO_AF_USART6, #ifdef UART6_AHB1_PERIPHERALS .rcc_ahb1 = UART6_AHB1_PERIPHERALS, #endif @@ -344,7 +344,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); } - if (mode & MODE_RX) { + if (mode & MODE_RX) { IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index f5eab63fa..3e33c545b 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -36,7 +36,7 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index e0aaad1bb..fb3093696 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -34,7 +34,7 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 810197437..5c09ebdf6 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -41,7 +41,7 @@ void systemReset(void) NVIC_SystemReset(); } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { if (mpuConfiguration.reset) mpuConfiguration.reset(); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index a3b362437..15e36cce3 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -253,7 +253,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz) } #else TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; -#endif +#endif TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 26078d451..e11f5a897 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -87,7 +87,7 @@ typedef struct timerHardware_s { } timerHardware_t; enum { - TIMER_OUTPUT_ENABLED = 0x01, + TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_INVERTED = 0x02 }; diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c index 09ef0efc8..1a5085e63 100644 --- a/src/main/drivers/timer_stm32f10x.c +++ b/src/main/drivers/timer_stm32f10x.c @@ -23,10 +23,10 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TIM8, .rcc = RCC_APB1(TIM8) }, { .TIMx = TIM9, .rcc = RCC_APB2(TIM9) }, { .TIMx = TIM10, .rcc = RCC_APB2(TIM10) }, - { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, + { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, { .TIMx = TIM12, .rcc = RCC_APB1(TIM12) }, { .TIMx = TIM13, .rcc = RCC_APB1(TIM13) }, - { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, + { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, #endif }; diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index 033aa316c..04069b20c 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -54,7 +54,7 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { */ #define CCMR_OFFSET ((uint16_t)0x0018) #define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F) -#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) +#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode) { diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index d8a720610..8520ef8e5 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -66,7 +66,7 @@ bool usbCableIsInserted(void) void usbGenerateDisconnectPulse(void) { /* Pull down PA12 to create USB disconnect pulse */ - IO_t usbPin = IOGetByTag(IO_TAG(PA12)); + IO_t usbPin = IOGetByTag(IO_TAG(PA12)); IOConfigGPIO(usbPin, IOCFG_OUT_OD); IOHi(usbPin); diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index ee540da60..93ffa83ec 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -179,7 +179,7 @@ void rtc6705SetFreq(uint16_t freq) uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers) uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers) - + val_hex |= RTC6705_SET_WRITE; val_hex |= (val_a << 5); val_hex |= (val_n << 12); diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b0dee8749..25ca7c40a 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -71,12 +71,12 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using -void setTargetPidLooptime(uint8_t pidProcessDenom) +void setTargetPidLooptime(uint8_t pidProcessDenom) { targetPidLooptime = gyro.targetLooptime * pidProcessDenom; } -uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) +uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) { uint16_t dynamicKi; uint16_t resetRate; diff --git a/src/main/io/gps.c b/src/main/io/gps.c index cf8e141ae..af963adcd 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -1069,7 +1069,7 @@ static void gpsHandlePassthrough(uint8_t data) #endif } - + void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) { diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 68896a9a8..f354577f8 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -672,8 +672,8 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx applyStepAdjustment(controlRateConfig, adjustmentFunction, delta); } else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) { - uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); - uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; + uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); + uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; applySelectAdjustment(adjustmentFunction, position); } diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 890e21828..15aae3e46 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -465,7 +465,7 @@ static void nopConsumer(uint8_t data) arbitrary serial passthrough "proxy". Optional callbacks can be given to allow for specialized data processing. */ -void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer +void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC) { waitForSerialPortToFinishTransmitting(left); diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c index 9c81c8931..1c32e2c6b 100644 --- a/src/main/io/serial_4way_stk500v2.c +++ b/src/main/io/serial_4way_stk500v2.c @@ -16,7 +16,7 @@ * Author: 4712 * have a look at https://github.com/sim-/tgy/blob/master/boot.inc * for info about the stk500v2 implementation - */ + */ #include #include #include diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index aa6b563a5..995484389 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -112,7 +112,7 @@ static void cliRxFail(char *cmdline); static void cliAdjustmentRange(char *cmdline); static void cliMotorMix(char *cmdline); static void cliDefaults(char *cmdline); -void cliDfu(char *cmdLine); +void cliDfu(char *cmdLine); static void cliDump(char *cmdLine); void cliDumpProfile(uint8_t profileIndex); void cliDumpRateProfile(uint8_t rateProfileIndex) ; @@ -488,7 +488,7 @@ typedef enum { TABLE_GPS_SBAS_MODE, #endif #ifdef BLACKBOX - TABLE_BLACKBOX_DEVICE, + TABLE_BLACKBOX_DEVICE, #endif TABLE_CURRENT_SENSOR, TABLE_GIMBAL_MODE, @@ -1943,7 +1943,7 @@ static void cliDump(char *cmdline) dumpMask = DUMP_PROFILE; // only } if (strcasecmp(cmdline, "rates") == 0) { - dumpMask = DUMP_RATES; + dumpMask = DUMP_RATES; } if (strcasecmp(cmdline, "all") == 0) { @@ -2502,11 +2502,11 @@ static void cliName(char *cmdline) { uint32_t len = strlen(cmdline); if (len > 0) { - memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); - strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH)); + memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); + strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH)); } cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-"); - + return; } @@ -2697,7 +2697,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full) break; } } -static void cliPrintVarRange(const clivalue_t *var) +static void cliPrintVarRange(const clivalue_t *var) { switch (var->type & VALUE_MODE_MASK) { case (MODE_DIRECT): { @@ -2709,7 +2709,7 @@ static void cliPrintVarRange(const clivalue_t *var) cliPrint("Allowed values:"); uint8_t i; for (i = 0; i < tableEntry->valueCount ; i++) { - if (i > 0) + if (i > 0) cliPrint(","); cliPrintf(" %s", tableEntry->values[i]); } @@ -2923,7 +2923,7 @@ static void cliStatus(char *cmdline) #ifdef USE_SDCARD cliSdInfo(NULL); -#endif +#endif } #ifndef SKIP_TASK_STATISTICS diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index f28c68a60..c21680f77 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -1876,9 +1876,9 @@ static bool processInCommand(void) masterConfig.baro_hardware = read8(); masterConfig.mag_hardware = read8(); break; - + case MSP_SET_NAME: - memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); + memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); for (i = 0; i < MIN(MAX_NAME_LENGTH, currentPort->dataSize); i++) { masterConfig.name[i] = read8(); } diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index 942a77054..fdd5e506f 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -14,7 +14,7 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - + #pragma once #define VTX_BAND_MIN 1 diff --git a/src/main/main.c b/src/main/main.c index 8cf45ac7b..0daf40276 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -313,7 +313,7 @@ void init(void) bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; // Configurator feature abused for enabling Fast PWM - pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); + pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 0e6885489..bbf4848bb 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -226,7 +226,7 @@ static void xBusUnpackRJ01Frame(void) uint8_t outerCrc = 0; uint8_t i = 0; - // When using the Align RJ01 receiver with + // When using the Align RJ01 receiver with // a MODE B setting in the radio (XG14 tested) // the MODE_B -frame is packed within some // at the moment unknown bytes before and after: @@ -234,7 +234,7 @@ static void xBusUnpackRJ01Frame(void) // Compared to a standard MODE B frame that only // contains the "middle" package. // Hence, at the moment, the unknown header and footer - // of the RJ01 MODEB packages are discarded. + // of the RJ01 MODEB packages are discarded. // However, the LAST byte (CRC_OUTER) is infact an 8-bit // CRC for the whole package, using the Dallas-One-Wire CRC // method. diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 59fa7ef9a..fed53524e 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -91,7 +91,7 @@ void updateBattery(void) /* Actual battery state is calculated below, this is really BATTERY_PRESENT */ batteryState = BATTERY_OK; /* wait for VBatt to stabilise then we can calc number of cells - (using the filtered value takes a long time to ramp up) + (using the filtered value takes a long time to ramp up) We only do this on the ground so don't care if we do block, not worse than original code anyway*/ delay(VBATTERY_STABLE_DELAY); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 908606c36..38d81a1f4 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -89,7 +89,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) #if defined(MPU_INT_EXTI) static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; return &mpuIntExtiConfig; -#elif defined(USE_HARDWARE_REVISION_DETECTION) +#elif defined(USE_HARDWARE_REVISION_DETECTION) return selectMPUIntExtiConfigByHardwareRevision(); #else return NULL; diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 253af13be..10bc3a49b 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -21,7 +21,7 @@ #define USE_CLI #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + #define LED0 PB5 // Blue LED - PB5 #define BEEPER PA0 diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h index 7e60ddc55..9b23c614d 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.h +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h @@ -15,7 +15,7 @@ * along with Cleanflight. If not, see . */ #pragma once - + #include "drivers/exti.h" typedef enum awf3HardwareRevision_t { diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index f005e5d1a..b85e50f53 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -33,7 +33,7 @@ const uint16_t multiPPM[] = { }; const uint16_t multiPWM[] = { - PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM1 | (MAP_TO_PWM_INPUT << 8), PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index ffae24c92..34bdcf8aa 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -141,7 +141,7 @@ #define LED_STRIP // LED Strip can run off Pin 6 (PB1) of the ESC outputs. -#define WS2811_PIN PB1 +#define WS2811_PIN PB1 #define WS2811_TIMER TIM3 #define WS2811_TIMER_CHANNEL TIM_Channel_4 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index f60a7b7b2..a1d9453e2 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -22,8 +22,8 @@ #ifndef STM32F3DISCOVERY #define STM32F3DISCOVERY -#endif - +#endif + #define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_INVERTED #define LED1 PE10 // Orange LEDs - PE10/PE14 diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h index 4b3c13d67..89e3478c1 100755 --- a/src/main/target/CJMCU/hardware_revision.h +++ b/src/main/target/CJMCU/hardware_revision.h @@ -17,7 +17,7 @@ #pragma once #include "drivers/exti.h" - + typedef enum cjmcuHardwareRevision_t { UNKNOWN = 0, REV_1, // Blue LED3 diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index a40ba0083..f98d39eb3 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -23,7 +23,7 @@ #define TARGET_CONFIG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + #define LED0 PC15 #define LED1 PC14 #define LED2 PC13 diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index c813ceecb..05b642f08 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -43,7 +43,7 @@ const uint16_t multiPWM[] = { PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), 0xFFFF }; diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 8f57af76d..2399ede8d 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -20,7 +20,7 @@ #define TARGET_BOARD_IDENTIFIER "DOGE" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + // tqfp48 pin 34 #define LED0 PA13 // tqfp48 pin 37 diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index e023d7e96..a8d80e823 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -30,11 +30,11 @@ const uint16_t multiPWM[] = { PWM3 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), - PWM6 | (MAP_TO_PWM_INPUT << 8), - PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -69,11 +69,11 @@ const uint16_t airPWM[] = { PWM3 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), - PWM6 | (MAP_TO_PWM_INPUT << 8), - PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 @@ -101,7 +101,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT - + { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed }; diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 21b05ab5d..bf4ff7b20 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -76,7 +76,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2 { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3 { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4 - + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP }; diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 4ee1a3835..82323ad05 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -24,7 +24,7 @@ #define MPU_INT_EXTI PC4 #define USE_EXTI #define CONFIG_PREFER_ACC_ON - + #define LED0 PC14 #define BEEPER PC15 diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index 81fb3b3ce..ef5fc8547 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -21,7 +21,7 @@ #define BOARD_HAS_VOLTAGE_DIVIDER #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + #define LED0 PC15 #define LED1 PC14 #define LED2 PC13 diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 1414ae6be..1db54b988 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -21,7 +21,7 @@ #define USE_CLI #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + #define LED0 PB5 // Blue LEDs - PB5 //#define LED1 PB9 // Green LEDs - PB9 diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index a5a91199b..390dc39f2 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -73,7 +73,7 @@ //#define DEBUG_MAG_DATA_READY_INTERRUPT #define USE_MAG_DATA_READY_SIGNAL #define MAG_INT_EXTI PC14 - + #define GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050 diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 03f60516d..4e5aa61a1 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -93,7 +93,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN - + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index db1464f3d..f566b07da 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -107,7 +107,7 @@ #define VBAT_ADC_PIN PC2 #define RSSI_ADC_GPIO_PIN PA0 - + #define SENSORS_SET (SENSOR_ACC) diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 507536776..704845c1e 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -20,7 +20,7 @@ #define TARGET_BOARD_IDENTIFIER "SPEV" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + #define LED0 PB8 #define BEEPER PC15 diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index dc9f80cb2..aaa3635da 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -74,7 +74,7 @@ #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 - + #define MPU6500_CS_PIN PB9 #define MPU6500_SPI_INSTANCE SPI1 diff --git a/src/main/target/common.h b/src/main/target/common.h index c9a9a0f1b..65ab02c87 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -14,7 +14,7 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - + #pragma once #define I2C1_OVERCLOCK true diff --git a/src/main/target/system_stm32f30x.c b/src/main/target/system_stm32f30x.c index 09ba3fa47..5d62e47aa 100644 --- a/src/main/target/system_stm32f30x.c +++ b/src/main/target/system_stm32f30x.c @@ -9,17 +9,17 @@ * and is generated by the clock configuration tool * stm32f30x_Clock_Configuration_V1.0.0.xls * - * 1. This file provides two functions and one global variable to be called from + * 1. This file provides two functions and one global variable to be called from * user application: * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and * before branch to main program. This call is made inside * the "startup_stm32f30x.s" file. * * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick + * by the user application to setup the SysTick * timer or configure other parameters. * * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must @@ -31,7 +31,7 @@ * configure the system clock before to branch to main program. * * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and HSI still used as system clock source. User can + * function will do nothing and HSI still used as system clock source. User can * add some code to deal with this issue inside the SetSysClock() function. * * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define @@ -79,8 +79,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. @@ -93,8 +93,8 @@ /** @addtogroup stm32f30x_system * @{ - */ - + */ + /** @addtogroup STM32F30x_System_Private_Includes * @{ */ @@ -113,13 +113,13 @@ uint32_t hse_value = HSE_VALUE; * @{ */ /*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ + Internal SRAM. */ /* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ /** * @} - */ + */ /* Private macro -------------------------------------------------------------*/ @@ -151,7 +151,7 @@ void SetSysClock(void); /** * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the + * Initialize the Embedded Flash Interface, the PLL and update the * SystemFrequency variable. * @param None * @retval None @@ -184,19 +184,19 @@ void SystemInit(void) /* Reset USARTSW[1:0], I2CSW and TIMs bits */ RCC->CFGR3 &= (uint32_t)0xFF00FCCC; - + /* Disable all interrupts */ RCC->CIR = 0x00000000; - /* Configure the System clock source, PLL Multiplier and Divider factors, + /* Configure the System clock source, PLL Multiplier and Divider factors, AHB/APBx prescalers and Flash settings ----------------------------------*/ //SetSysClock(); // called from main() - + #ifdef VECT_TAB_SRAM SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ #else SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ -#endif +#endif } /** @@ -204,25 +204,25 @@ void SystemInit(void) * The SystemCoreClock variable contains the core clock (HCLK), it can * be used by the user application to setup the SysTick timer or configure * other parameters. - * + * * @note Each time the core clock (HCLK) changes, this function must be called * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined * constant and the selected clock source: * * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) * * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * + * * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz) but the real value may vary depending on the variations - * in voltage and temperature. + * in voltage and temperature. * * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz), user has to ensure that HSE_VALUE is same as the real @@ -231,7 +231,7 @@ void SystemInit(void) * * - The result of this function could be not correct when using fractional * value for HSE crystal. - * + * * @param None * @retval None */ @@ -241,7 +241,7 @@ void SystemCoreClockUpdate (void) /* Get SYSCLK source -------------------------------------------------------*/ tmp = RCC->CFGR & RCC_CFGR_SWS; - + switch (tmp) { case 0x00: /* HSI used as system clock */ @@ -255,7 +255,7 @@ void SystemCoreClockUpdate (void) pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; pllmull = ( pllmull >> 18) + 2; - + if (pllsource == 0x00) { /* HSI oscillator clock divided by 2 selected as PLL clock entry */ @@ -265,8 +265,8 @@ void SystemCoreClockUpdate (void) { prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; /* HSE oscillator clock selected as PREDIV1 clock entry */ - SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; - } + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } break; default: /* HSI used as system clock */ SystemCoreClock = HSI_VALUE; @@ -276,7 +276,7 @@ void SystemCoreClockUpdate (void) /* Get HCLK prescaler */ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; /* HCLK clock frequency */ - SystemCoreClock >>= tmp; + SystemCoreClock >>= tmp; } /** @@ -298,7 +298,7 @@ void SetSysClock(void) /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ /* Enable HSE */ RCC->CR |= ((uint32_t)RCC_CR_HSEON); - + /* Wait till HSE is ready and if Time out is reached exit */ do { @@ -319,13 +319,13 @@ void SetSysClock(void) { /* Enable Prefetch Buffer and set Flash Latency */ FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; - + /* HCLK = SYSCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - + /* PCLK2 = HCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - + /* PCLK1 = HCLK / 2 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; diff --git a/src/main/target/system_stm32f30x.h b/src/main/target/system_stm32f30x.h index 4f999d305..b213ad0b1 100644 --- a/src/main/target/system_stm32f30x.h +++ b/src/main/target/system_stm32f30x.h @@ -4,7 +4,7 @@ * @author MCD Application Team * @version V1.1.1 * @date 28-March-2014 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. + * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. ****************************************************************************** * @attention * @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. @@ -31,8 +31,8 @@ /** @addtogroup stm32f30x_system * @{ - */ - + */ + /** * @brief Define to prevent recursive inclusion */ @@ -41,7 +41,7 @@ #ifdef __cplusplus extern "C" { -#endif +#endif /* Exported types ------------------------------------------------------------*/ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ @@ -52,7 +52,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Cloc /** @addtogroup STM32F30x_System_Exported_Functions * @{ */ - + extern void SystemInit(void); extern void SystemCoreClockUpdate(void); @@ -69,8 +69,8 @@ extern void SystemCoreClockUpdate(void); /** * @} */ - + /** * @} - */ + */ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/target/system_stm32f4xx.h b/src/main/target/system_stm32f4xx.h index e26636680..45c811bb0 100644 --- a/src/main/target/system_stm32f4xx.h +++ b/src/main/target/system_stm32f4xx.h @@ -4,8 +4,8 @@ * @author MCD Application Team * @version V1.6.1 * @date 21-October-2015 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** + * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. + ****************************************************************************** * @attention * *

© COPYRIGHT 2015 STMicroelectronics

@@ -16,21 +16,21 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. * - ****************************************************************************** - */ + ****************************************************************************** + */ #ifndef __SYSTEM_STM32F4XX_H #define __SYSTEM_STM32F4XX_H #ifdef __cplusplus extern "C" { -#endif +#endif extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ extern void SystemInit(void); diff --git a/src/main/vcp/hw_config.c b/src/main/vcp/hw_config.c index 7384b1e0b..d7552ea0f 100644 --- a/src/main/vcp/hw_config.c +++ b/src/main/vcp/hw_config.c @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. @@ -68,13 +68,13 @@ void Set_System(void) { #if !defined(STM32L1XX_MD) && !defined(STM32L1XX_HD) && !defined(STM32L1XX_MD_PLUS) GPIO_InitTypeDef GPIO_InitStructure; -#endif /* STM32L1XX_MD && STM32L1XX_XD */ +#endif /* STM32L1XX_MD && STM32L1XX_XD */ #if defined(USB_USE_EXTERNAL_PULLUP) GPIO_InitTypeDef GPIO_InitStructure; -#endif /* USB_USE_EXTERNAL_PULLUP */ +#endif /* USB_USE_EXTERNAL_PULLUP */ - /*!< At this stage the microcontroller clock setting is already configured, + /*!< At this stage the microcontroller clock setting is already configured, this is done through SystemInit() function which is called from startup file (startup_stm32f10x_xx.s) before to branch to application main. To reconfigure the default setting of SystemInit() function, refer to @@ -83,7 +83,7 @@ void Set_System(void) #if defined(STM32L1XX_MD) || defined(STM32L1XX_HD)|| defined(STM32L1XX_MD_PLUS) || defined(STM32F37X) || defined(STM32F303xC) /* Enable the SYSCFG module clock */ RCC_APB2PeriphClockCmd(RCC_APB2Periph_SYSCFG, ENABLE); -#endif /* STM32L1XX_XD */ +#endif /* STM32L1XX_XD */ /*Pull down PA12 to create USB Disconnect Pulse*/ // HJI #if defined(STM32F303xC) // HJI @@ -277,7 +277,7 @@ static void IntToUnicode(uint32_t value, uint8_t *pbuf, uint8_t len) /******************************************************************************* * Function Name : Send DATA . - * Description : send the data received from the STM32 to the PC through USB + * Description : send the data received from the STM32 to the PC through USB * Input : None. * Output : None. * Return : None. diff --git a/src/main/vcp/platform_config.h b/src/main/vcp/platform_config.h index 35715588e..3f0972622 100644 --- a/src/main/vcp/platform_config.h +++ b/src/main/vcp/platform_config.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/stm32_it.h b/src/main/vcp/stm32_it.h index 959a1e6db..f3758882b 100644 --- a/src/main/vcp/stm32_it.h +++ b/src/main/vcp/stm32_it.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_conf.h b/src/main/vcp/usb_conf.h index 6b322297e..c0c17673f 100644 --- a/src/main/vcp/usb_conf.h +++ b/src/main/vcp/usb_conf.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_desc.c b/src/main/vcp/usb_desc.c index 64ead56f6..3db4216b6 100644 --- a/src/main/vcp/usb_desc.c +++ b/src/main/vcp/usb_desc.c @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_desc.h b/src/main/vcp/usb_desc.h index 92f38341a..9a21291c0 100644 --- a/src/main/vcp/usb_desc.h +++ b/src/main/vcp/usb_desc.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_istr.h b/src/main/vcp/usb_istr.h index 1d72d91c6..7285da685 100644 --- a/src/main/vcp/usb_istr.h +++ b/src/main/vcp/usb_istr.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_prop.c b/src/main/vcp/usb_prop.c index b070ce9cc..c8558de34 100644 --- a/src/main/vcp/usb_prop.c +++ b/src/main/vcp/usb_prop.c @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcp/usb_prop.h b/src/main/vcp/usb_prop.h index 12d050c38..f8e1d2024 100644 --- a/src/main/vcp/usb_prop.h +++ b/src/main/vcp/usb_prop.h @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. diff --git a/src/main/vcpf4/stm32f4xx_it.h b/src/main/vcpf4/stm32f4xx_it.h index 74f17c9cc..dd000126f 100644 --- a/src/main/vcpf4/stm32f4xx_it.h +++ b/src/main/vcpf4/stm32f4xx_it.h @@ -1,6 +1,6 @@ /** ****************************************************************************** - * @file GPIO/IOToggle/stm32f4xx_it.h + * @file GPIO/IOToggle/stm32f4xx_it.h * @author MCD Application Team * @version V1.0.0 * @date 19-September-2011 @@ -17,7 +17,7 @@ * *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** - */ + */ /* Define to prevent recursive inclusion -------------------------------------*/ #ifndef __STM32F4xx_IT_H @@ -25,7 +25,7 @@ #ifdef __cplusplus extern "C" { -#endif +#endif /* Includes ------------------------------------------------------------------*/ #include "stm32f4xx.h" diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h index ea8d49bcf..bd5bbe14f 100644 --- a/src/main/vcpf4/usb_conf.h +++ b/src/main/vcpf4/usb_conf.h @@ -30,15 +30,15 @@ /** @addtogroup USB_OTG_DRIVER * @{ */ - + /** @defgroup USB_CONF * @brief USB low level driver configuration file * @{ - */ + */ /** @defgroup USB_CONF_Exported_Defines * @{ - */ + */ /* USB Core and PHY interface configuration. Tip: To avoid modifying these defines each time you need to change the USB @@ -66,7 +66,7 @@ #endif /* USE_I2C_PHY */ -#ifdef USE_USB_OTG_FS +#ifdef USE_USB_OTG_FS #define USB_OTG_FS_CORE #endif @@ -76,35 +76,35 @@ /******************************************************************************* * FIFO Size Configuration in Device mode -* -* (i) Receive data FIFO size = RAM for setup packets + +* +* (i) Receive data FIFO size = RAM for setup packets + * OUT endpoint control information + * data OUT packets + miscellaneous * Space = ONE 32-bits words * --> RAM for setup packets = 10 spaces -* (n is the nbr of CTRL EPs the device core supports) +* (n is the nbr of CTRL EPs the device core supports) * --> OUT EP CTRL info = 1 space -* (one space for status information written to the FIFO along with each +* (one space for status information written to the FIFO along with each * received packet) -* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces +* --> data OUT packets = (Largest Packet Size / 4) + 1 spaces * (MINIMUM to receive packets) -* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces +* --> OR data OUT packets = at least 2*(Largest Packet Size / 4) + 1 spaces * (if high-bandwidth EP is enabled or multiple isochronous EPs) * --> miscellaneous = 1 space per OUT EP -* (one space for transfer complete status information also pushed to the +* (one space for transfer complete status information also pushed to the * FIFO with each endpoint's last packet) * -* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for +* (ii)MINIMUM RAM space required for each IN EP Tx FIFO = MAX packet size for * that particular IN EP. More space allocated in the IN EP Tx FIFO results * in a better performance on the USB and can hide latencies on the AHB. * * (iii) TXn min size = 16 words. (n : Transmit FIFO index) -* (iv) When a TxFIFO is not used, the Configuration should be as follows: +* (iv) When a TxFIFO is not used, the Configuration should be as follows: * case 1 : n > m and Txn is not used (n,m : Transmit FIFO indexes) * --> Txm can use the space allocated for Txn. * case2 : n < m and Txn is not used (n,m : Transmit FIFO indexes) * --> Txn should be configured with the minimum space of 16 words -* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top +* (v) The FIFO is used optimally when used TxFIFOs are allocated in the top * of the FIFO.Ex: use EP1 and EP2 as IN instead of EP1 and EP3 as IN ones. *******************************************************************************/ @@ -126,7 +126,7 @@ * then the space must be at least two times the maximum packet size for * that channel. *******************************************************************************/ - + /****************** USB OTG HS CONFIGURATION **********************************/ #ifdef USB_OTG_HS_CORE #define RX_FIFO_HS_SIZE 512 @@ -211,20 +211,20 @@ #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined (__GNUC__) /* GNU Compiler */ #define __ALIGN_END __attribute__ ((aligned (4))) - #define __ALIGN_BEGIN + #define __ALIGN_BEGIN #else #define __ALIGN_END #if defined (__CC_ARM) /* ARM Compiler */ - #define __ALIGN_BEGIN __align(4) - #elif defined (__ICCARM__) /* IAR Compiler */ - #define __ALIGN_BEGIN - #elif defined (__TASKING__) /* TASKING Compiler */ #define __ALIGN_BEGIN __align(4) - #endif /* __CC_ARM */ - #endif /* __GNUC__ */ + #elif defined (__ICCARM__) /* IAR Compiler */ + #define __ALIGN_BEGIN + #elif defined (__TASKING__) /* TASKING Compiler */ + #define __ALIGN_BEGIN __align(4) + #endif /* __CC_ARM */ + #endif /* __GNUC__ */ #else #define __ALIGN_BEGIN - #define __ALIGN_END + #define __ALIGN_END #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* __packed keyword used to decrease the data type alignment to 1-byte */ @@ -242,37 +242,37 @@ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Types * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Macros * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Variables * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_FunctionsPrototype * @{ - */ + */ /** * @} - */ + */ #endif //__USB_CONF__H__ @@ -280,10 +280,10 @@ /** * @} - */ + */ /** * @} - */ + */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 61e26a113..f312e4a34 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -19,8 +19,8 @@ ****************************************************************************** */ -#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED -#pragma data_alignment = 4 +#ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED +#pragma data_alignment = 4 #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* Includes ------------------------------------------------------------------*/ @@ -34,7 +34,7 @@ LINE_CODING g_lc; extern __IO uint8_t USB_Tx_State; __IO uint32_t bDeviceState = UNCONNECTED; /* USB device status */ -/* These are external variables imported from CDC core to be used for IN +/* These are external variables imported from CDC core to be used for IN transfer management. */ extern uint8_t APP_Rx_Buffer[]; /* Write CDC received data in this buffer. These data will be sent over USB IN endpoint @@ -105,7 +105,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) assert_param(Len>=sizeof(LINE_CODING)); switch (Cmd) { - /* Not needed for this driver, AT modem commands */ + /* Not needed for this driver, AT modem commands */ case SEND_ENCAPSULATED_COMMAND: case GET_ENCAPSULATED_RESPONSE: break; @@ -116,18 +116,18 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) case CLEAR_COMM_FEATURE: break; - + //Note - hw flow control on UART 1-3 and 6 only - case SET_LINE_CODING: + case SET_LINE_CODING: ust_cpy(&g_lc, plc); //Copy into structure to save for later break; - - + + case GET_LINE_CODING: ust_cpy(plc, &g_lc); break; - + case SET_CONTROL_LINE_STATE: /* Not needed for this driver */ //RSW - This tells how to set RTS and DTR @@ -153,7 +153,7 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) *******************************************************************************/ uint32_t CDC_Send_DATA(uint8_t *ptrBuffer, uint8_t sendLength) { - if (USB_Tx_State) + if (USB_Tx_State) return 0; VCP_DataTx(ptrBuffer, sendLength); @@ -177,7 +177,7 @@ static uint16_t VCP_DataTx(uint8_t* Buf, uint32_t Len) return USBD_OK; } -uint8_t usbAvailable(void) +uint8_t usbAvailable(void) { return (usbData.bufferInPosition != usbData.bufferOutPosition); } diff --git a/src/main/vcpf4/usbd_cdc_vcp.h b/src/main/vcpf4/usbd_cdc_vcp.h index df1e29001..553017ff2 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.h +++ b/src/main/vcpf4/usbd_cdc_vcp.h @@ -59,7 +59,7 @@ typedef enum _DEVICE_STATE { } DEVICE_STATE; /* Exported typef ------------------------------------------------------------*/ -/* The following structures groups all needed parameters to be configured for the +/* The following structures groups all needed parameters to be configured for the ComPort. These parameters can modified on the fly by the host through CDC class command class requests. */ typedef struct diff --git a/src/main/vcpf4/usbd_conf.h b/src/main/vcpf4/usbd_conf.h index a32176efe..02ceeae54 100644 --- a/src/main/vcpf4/usbd_conf.h +++ b/src/main/vcpf4/usbd_conf.h @@ -60,36 +60,36 @@ #define APP_FOPS VCP_fops /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Types * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Macros * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_Variables * @{ - */ + */ /** * @} - */ + */ /** @defgroup USB_CONF_Exported_FunctionsPrototype * @{ - */ + */ /** * @} - */ + */ #endif //__USBD_CONF__H__ diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index ab1a3e1d3..a0cf88191 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -17,7 +17,7 @@ * *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** - */ + */ /* Includes ------------------------------------------------------------------*/ #include "usbd_core.h" @@ -32,22 +32,22 @@ */ -/** @defgroup USBD_DESC +/** @defgroup USBD_DESC * @brief USBD descriptors module * @{ - */ + */ /** @defgroup USBD_DESC_Private_TypesDefinitions * @{ - */ + */ /** * @} - */ + */ /** @defgroup USBD_DESC_Private_Defines * @{ - */ + */ #define USBD_VID 0x0483 @@ -55,7 +55,7 @@ /** @defgroup USB_String_Descriptors * @{ - */ + */ #define USBD_LANGID_STRING 0x409 #define USBD_MANUFACTURER_STRING "BetaFlight" @@ -83,36 +83,36 @@ #define USBD_INTERFACE_FS_STRING "VCP Interface" /** * @} - */ + */ /** @defgroup USBD_DESC_Private_Macros * @{ - */ + */ /** * @} - */ + */ /** @defgroup USBD_DESC_Private_Variables * @{ - */ + */ USBD_DEVICE USR_desc = { USBD_USR_DeviceDescriptor, - USBD_USR_LangIDStrDescriptor, + USBD_USR_LangIDStrDescriptor, USBD_USR_ManufacturerStrDescriptor, USBD_USR_ProductStrDescriptor, USBD_USR_SerialStrDescriptor, USBD_USR_ConfigStrDescriptor, USBD_USR_InterfaceStrDescriptor, - + }; #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 + #pragma data_alignment=4 #endif #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* USB Standard Device Descriptor */ @@ -140,7 +140,7 @@ __ALIGN_BEGIN uint8_t USBD_DeviceDesc[USB_SIZ_DEVICE_DESC] __ALIGN_END = #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 + #pragma data_alignment=4 #endif #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* USB Standard Device Descriptor */ @@ -160,36 +160,36 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined ( __ICCARM__ ) /*!< IAR Compiler */ - #pragma data_alignment=4 + #pragma data_alignment=4 #endif #endif /* USB_OTG_HS_INTERNAL_DMA_ENABLED */ /* USB Standard Device Descriptor */ __ALIGN_BEGIN uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID] __ALIGN_END = { - USB_SIZ_STRING_LANGID, - USB_DESC_TYPE_STRING, + USB_SIZ_STRING_LANGID, + USB_DESC_TYPE_STRING, LOBYTE(USBD_LANGID_STRING), - HIBYTE(USBD_LANGID_STRING), + HIBYTE(USBD_LANGID_STRING), }; /** * @} - */ + */ /** @defgroup USBD_DESC_Private_FunctionPrototypes * @{ - */ + */ /** * @} - */ + */ /** @defgroup USBD_DESC_Private_Functions * @{ - */ + */ /** -* @brief USBD_USR_DeviceDescriptor +* @brief USBD_USR_DeviceDescriptor * return the device descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -203,7 +203,7 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length) } /** -* @brief USBD_USR_LangIDStrDescriptor +* @brief USBD_USR_LangIDStrDescriptor * return the LangID string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -212,13 +212,13 @@ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length) uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) { (void)speed; - *length = sizeof(USBD_LangIDDesc); + *length = sizeof(USBD_LangIDDesc); return USBD_LangIDDesc; } /** -* @brief USBD_USR_ProductStrDescriptor +* @brief USBD_USR_ProductStrDescriptor * return the product string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -226,8 +226,8 @@ uint8_t * USBD_USR_LangIDStrDescriptor( uint8_t speed , uint16_t *length) */ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) { + - if(speed == 0) USBD_GetString ((uint8_t*)USBD_PRODUCT_HS_STRING, USBD_StrDesc, length); else @@ -237,7 +237,7 @@ uint8_t * USBD_USR_ProductStrDescriptor( uint8_t speed , uint16_t *length) } /** -* @brief USBD_USR_ManufacturerStrDescriptor +* @brief USBD_USR_ManufacturerStrDescriptor * return the manufacturer string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -251,7 +251,7 @@ uint8_t * USBD_USR_ManufacturerStrDescriptor( uint8_t speed , uint16_t *length) } /** -* @brief USBD_USR_SerialStrDescriptor +* @brief USBD_USR_SerialStrDescriptor * return the serial number string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -268,7 +268,7 @@ uint8_t * USBD_USR_SerialStrDescriptor( uint8_t speed , uint16_t *length) } /** -* @brief USBD_USR_ConfigStrDescriptor +* @brief USBD_USR_ConfigStrDescriptor * return the configuration string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -281,12 +281,12 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length) else USBD_GetString ((uint8_t*)USBD_CONFIGURATION_FS_STRING, USBD_StrDesc, length); - return USBD_StrDesc; + return USBD_StrDesc; } /** -* @brief USBD_USR_InterfaceStrDescriptor +* @brief USBD_USR_InterfaceStrDescriptor * return the interface string descriptor * @param speed : current device speed * @param length : pointer to data length variable @@ -299,22 +299,22 @@ uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length) else USBD_GetString ((uint8_t*)USBD_INTERFACE_FS_STRING, USBD_StrDesc, length); - return USBD_StrDesc; + return USBD_StrDesc; } /** * @} - */ + */ /** * @} - */ + */ /** * @} - */ + */ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcpf4/usbd_desc.h b/src/main/vcpf4/usbd_desc.h index ed999dc62..f67799cf4 100644 --- a/src/main/vcpf4/usbd_desc.h +++ b/src/main/vcpf4/usbd_desc.h @@ -6,18 +6,18 @@ * @date 19-September-2011 * @brief header file for the usbd_desc.c file ****************************************************************************** - * @attention + * @attention * * THE PRESENT FIRMWARE WHICH IS FOR GUIDANCE ONLY AIMS AT PROVIDING CUSTOMERS * WITH CODING INFORMATION REGARDING THEIR PRODUCTS IN ORDER FOR THEM TO SAVE * TIME. AS A RESULT, STMICROELECTRONICS SHALL NOT BE HELD LIABLE FOR ANY * DIRECT, INDIRECT OR CONSEQUENTIAL DAMAGES WITH RESPECT TO ANY CLAIMS ARISING * FROM THE CONTENT OF SUCH FIRMWARE AND/OR THE USE MADE BY CUSTOMERS OF THE - * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. + * CODING INFORMATION CONTAINED HEREIN IN CONNECTION WITH THEIR PRODUCTS. * *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** - */ + */ /* Define to prevent recursive inclusion -------------------------------------*/ @@ -30,11 +30,11 @@ /** @addtogroup STM32_USB_OTG_DEVICE_LIBRARY * @{ */ - + /** @defgroup USB_DESC * @brief general defines for the usb device library file * @{ - */ + */ /** @defgroup USB_DESC_Exported_Defines * @{ @@ -49,7 +49,7 @@ /** * @} - */ + */ /** @defgroup USBD_DESC_Exported_TypesDefinitions @@ -57,33 +57,33 @@ */ /** * @} - */ + */ /** @defgroup USBD_DESC_Exported_Macros * @{ - */ + */ /** * @} - */ + */ /** @defgroup USBD_DESC_Exported_Variables * @{ - */ + */ extern uint8_t USBD_DeviceDesc [USB_SIZ_DEVICE_DESC]; extern uint8_t USBD_StrDesc[USB_MAX_STR_DESC_SIZ]; -extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; +extern uint8_t USBD_OtherSpeedCfgDesc[USB_LEN_CFG_DESC]; extern uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC]; extern uint8_t USBD_LangIDDesc[USB_SIZ_STRING_LANGID]; -extern USBD_DEVICE USR_desc; +extern USBD_DEVICE USR_desc; /** * @} - */ + */ /** @defgroup USBD_DESC_Exported_FunctionsPrototype * @{ - */ + */ uint8_t * USBD_USR_DeviceDescriptor( uint8_t speed , uint16_t *length); @@ -95,20 +95,20 @@ uint8_t * USBD_USR_ConfigStrDescriptor( uint8_t speed , uint16_t *length); uint8_t * USBD_USR_InterfaceStrDescriptor( uint8_t speed , uint16_t *length); #ifdef USB_SUPPORT_USER_STRING_DESC -uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length); -#endif /* USB_SUPPORT_USER_STRING_DESC */ - +uint8_t * USBD_USR_USRStringDesc (uint8_t speed, uint8_t idx , uint16_t *length); +#endif /* USB_SUPPORT_USER_STRING_DESC */ + /** * @} - */ + */ #endif /* __USBD_DESC_H */ /** * @} - */ + */ /** * @} -*/ +*/ /******************* (C) COPYRIGHT 2011 STMicroelectronics *****END OF FILE****/ diff --git a/src/main/vcpf4/usbd_usr.c b/src/main/vcpf4/usbd_usr.c index 958e77232..b3de6d44a 100644 --- a/src/main/vcpf4/usbd_usr.c +++ b/src/main/vcpf4/usbd_usr.c @@ -17,7 +17,7 @@ * *

© COPYRIGHT 2011 STMicroelectronics

****************************************************************************** - */ + */ #include "usbd_usr.h" #include "usbd_ioreq.h" @@ -29,25 +29,25 @@ USBD_Usr_cb_TypeDef USR_cb = USBD_USR_DeviceConfigured, USBD_USR_DeviceSuspended, USBD_USR_DeviceResumed, - + USBD_USR_DeviceConnected, USBD_USR_DeviceDisconnected, }; /** -* @brief USBD_USR_Init +* @brief USBD_USR_Init * Displays the message on LCD for host lib initialization * @param None * @retval None */ void USBD_USR_Init(void) -{ +{ } /** -* @brief USBD_USR_DeviceReset +* @brief USBD_USR_DeviceReset * Displays the message on LCD on device Reset Event * @param speed : device speed * @retval None @@ -56,14 +56,14 @@ void USBD_USR_DeviceReset(uint8_t speed ) { switch (speed) { - case USB_OTG_SPEED_HIGH: + case USB_OTG_SPEED_HIGH: break; - case USB_OTG_SPEED_FULL: + case USB_OTG_SPEED_FULL: break; default: break; - + } } @@ -101,7 +101,7 @@ void USBD_USR_DeviceDisconnected (void) } /** -* @brief USBD_USR_DeviceSuspended +* @brief USBD_USR_DeviceSuspended * Displays the message on LCD on device suspend Event * @param None * @retval None @@ -113,7 +113,7 @@ void USBD_USR_DeviceSuspended(void) /** -* @brief USBD_USR_DeviceResumed +* @brief USBD_USR_DeviceResumed * Displays the message on LCD on device resume Event * @param None * @retval None