diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 46bae1958..c529f4132 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -401,7 +401,7 @@ static bool testBlackboxConditionUncached(FlightLogFieldCondition condition) case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_7: case FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_8: return motorCount >= condition - FLIGHT_LOG_FIELD_CONDITION_AT_LEAST_MOTORS_1 + 1; - + case FLIGHT_LOG_FIELD_CONDITION_TRICOPTER: return masterConfig.mixerMode == MIXER_TRI || masterConfig.mixerMode == MIXER_CUSTOM_TRI; @@ -638,7 +638,7 @@ static void writeInterframe(void) */ arraySubInt32(deltas, blackboxCurrent->axisPID_I, blackboxLast->axisPID_I, XYZ_AXIS_COUNT); blackboxWriteTag2_3S32(deltas); - + /* * The PID D term is frequently set to zero for yaw, which makes the result from the calculation * always zero. So don't bother recording D results when PID D terms are zero. @@ -852,7 +852,7 @@ void startBlackbox(void) * cache those now. */ blackboxBuildConditionCache(); - + blackboxModeActivationConditionPresent = isModeActivationConditionPresent(masterConfig.modeActivationConditions, BOXBLACKBOX); blackboxIteration = 0; @@ -1359,7 +1359,7 @@ static void blackboxLogIteration() } else { blackboxCheckAndLogArmingBeep(); blackboxCheckAndLogFlightMode(); // Check for FlightMode status change event - + if (blackboxShouldLogPFrame(blackboxPFrameIndex)) { /* * We assume that slow frames are only interesting in that they aid the interpretation of the main data stream. @@ -1496,7 +1496,7 @@ void handleBlackbox(void) blackboxLogEvent(FLIGHT_LOG_EVENT_LOGGING_RESUME, (flightLogEventData_t *) &resume); blackboxSetState(BLACKBOX_STATE_RUNNING); - + blackboxLogIteration(); } diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 95e664a3c..7847fb303 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -87,7 +87,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) putf(putp, ch); written++; } else { char lz = 0; -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT char lng = 0; #endif int w = 0; @@ -99,7 +99,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) if (ch >= '0' && ch <= '9') { ch = a2i(ch, &fmt, 10, &w); } -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (ch == 'l') { ch = *(fmt++); lng = 1; @@ -109,7 +109,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) case 0: goto abort; case 'u':{ -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) uli2a(va_arg(va, unsigned long int), 10, 0, bf); else @@ -119,7 +119,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) break; } case 'd':{ -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) li2a(va_arg(va, unsigned long int), bf); else @@ -130,7 +130,7 @@ int tfp_format(void *putp, putcf putf, const char *fmt, va_list va) } case 'x': case 'X': -#ifdef REQUIRE_PRINTF_LONG_SUPPORT +#ifdef REQUIRE_PRINTF_LONG_SUPPORT if (lng) uli2a(va_arg(va, unsigned long int), 16, (ch == 'X'), bf); else diff --git a/src/main/common/printf.h b/src/main/common/printf.h index e7606fbb9..dff4efdd2 100644 --- a/src/main/common/printf.h +++ b/src/main/common/printf.h @@ -66,10 +66,10 @@ To use the printf you need to supply your own character output function, something like : void putc ( void* p, char c) - { - while (!SERIAL_PORT_EMPTY) ; - SERIAL_PORT_TX_REGISTER = c; - } + { + while (!SERIAL_PORT_EMPTY) ; + SERIAL_PORT_TX_REGISTER = c; + } Before you can call printf you need to initialize it to use your character output function with something like: diff --git a/src/main/common/utils.h b/src/main/common/utils.h index db9e8c0c5..a5c059191 100644 --- a/src/main/common/utils.h +++ b/src/main/common/utils.h @@ -56,7 +56,7 @@ http://resnet.uoregon.edu/~gurney_j/jmpc/bitwise.html (32*((v)/2L>>31 > 0) \ + LOG2_32BIT((v)*1L >>16*((v)/2L>>31 > 0) \ >>16*((v)/2L>>31 > 0))) - + #if 0 // ISO C version, but no type checking #define container_of(ptr, type, member) \ diff --git a/src/main/config/config.c b/src/main/config/config.c index 3d15e233e..06ba7c9c0 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -538,7 +538,7 @@ static void resetConf(void) masterConfig.motor_pwm_protocol = PWM_TYPE_ONESHOT125; #endif masterConfig.servo_pwm_rate = 50; - + #ifdef CC3D masterConfig.use_buzzer_p6 = 0; #endif @@ -556,7 +556,7 @@ static void resetConf(void) masterConfig.emf_avoidance = 0; // TODO - needs removal resetPidProfile(¤tProfile->pidProfile); - + for (int rI = 0; rI MAX_RATEPROFILES) { - profileIndex = MAX_RATEPROFILES - 1; - } - setControlRateProfile(profileIndex); - activateControlRateConfig(); +{ + if (profileIndex > MAX_RATEPROFILES) { + profileIndex = MAX_RATEPROFILES - 1; + } + setControlRateProfile(profileIndex); + activateControlRateConfig(); } void latchActiveFeatures() diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index ca684aa6e..9a3cd5725 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -165,7 +165,7 @@ static bool detectSPISensorsAndUpdateDetectionResult(void) return true; } #endif - + return false; } #endif @@ -236,7 +236,7 @@ void mpuIntExtiInit(void) #if defined(USE_MPU_DATA_READY_SIGNAL) && defined(USE_EXTI) IO_t mpuIntIO = IOGetByTag(mpuIntExtiConfig->tag); - + #ifdef ENSURE_MPU_DATA_READY_IS_LOW uint8_t status = IORead(mpuIntIO); if (status) { @@ -251,7 +251,7 @@ void mpuIntExtiInit(void) EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIEnable(mpuIntIO, true); #endif - + mpuExtiInitDone = true; } diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index b8c136025..8c277dea5 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -156,12 +156,12 @@ 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); IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG); - + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); mpu6000WriteRegister(MPU_RA_PWR_MGMT_1, BIT_H_RESET); diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 3e4d1635c..219bd51a2 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -193,7 +193,7 @@ bool mpu9250SpiDetect(void) #endif IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG); - + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); diff --git a/src/main/drivers/adc.c b/src/main/drivers/adc.c index d214b49d3..a65abf912 100644 --- a/src/main/drivers/adc.c +++ b/src/main/drivers/adc.c @@ -39,7 +39,7 @@ uint8_t adcChannelByTag(ioTag_t ioTag) if (ioTag == adcTagMap[i].tag) return adcTagMap[i].channel; } - return 0; + return 0; } uint16_t adcGetChannel(uint8_t channel) diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index ee2e92d40..258c8acc8 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -37,7 +37,7 @@ typedef enum ADCDevice { #elif defined(STM32F4) ADCDEV_2, ADCDEV_3, - ADCDEV_MAX = ADCDEV_3, + ADCDEV_MAX = ADCDEV_3, #else ADCDEV_MAX = ADCDEV_1, #endif @@ -47,7 +47,7 @@ typedef struct adcTagMap_s { ioTag_t tag; uint8_t channel; } adcTagMap_t; - + typedef struct adcDevice_s { ADC_TypeDef* ADCx; rccPeriphTag_t rccADC; diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index dc0598988..451c9296c 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -79,7 +79,7 @@ const adcTagMap_t adcTagMap[] = { void adcInit(drv_adc_config_t *init) { - + #if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN) UNUSED(init); #endif @@ -130,11 +130,11 @@ void adcInit(drv_adc_config_t *init) adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5; adcConfig[i].enabled = true; } - + RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI) RCC_ClockCmd(adc.rccADC, ENABLE); RCC_ClockCmd(adc.rccDMA, ENABLE); - + DMA_DeInit(adc.DMAy_Channelx); DMA_InitTypeDef DMA_InitStructure; DMA_StructInit(&DMA_InitStructure); diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index c9ae8dc47..6297c2bd1 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -132,8 +132,8 @@ void adcInit(drv_adc_config_t *init) ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); 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/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index 4466f3443..e1bb1ae61 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -70,7 +70,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA4, ADC_Channel_4 }, { DEFIO_TAG_E__PA5, ADC_Channel_5 }, { DEFIO_TAG_E__PA6, ADC_Channel_6 }, - { DEFIO_TAG_E__PA7, ADC_Channel_7 }, + { DEFIO_TAG_E__PA7, ADC_Channel_7 }, }; ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) @@ -109,7 +109,7 @@ void adcInit(drv_adc_config_t *init) adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL; } #endif - + #ifdef EXTERNAL1_ADC_PIN if (init->enableExternal1) { adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL; @@ -123,25 +123,25 @@ void adcInit(drv_adc_config_t *init) #endif //RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz - + ADCDevice device = adcDeviceByInstance(ADC_INSTANCE); if (device == ADCINVALID) return; - + adcDevice_t adc = adcHardware[device]; - + for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; adcConfig[i].sampleTime = ADC_SampleTime_480Cycles; adcConfig[i].enabled = true; } - + RCC_ClockCmd(adc.rccDMA, ENABLE); RCC_ClockCmd(adc.rccADC, ENABLE); diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index ad4c547bf..4c3e77985 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -367,7 +367,7 @@ static void bmp085_get_cal_param(void) bool bmp085TestEOCConnected(const bmp085Config_t *config) { UNUSED(config); - + if (!bmp085InitDone && eocIO) { bmp085_start_ut(); delayMicroseconds(UT_DELAY * 2); // wait twice as long as normal, just to be sure diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index cac5c6221..104c77c37 100644 --- a/src/main/drivers/bus_i2c_soft.c +++ b/src/main/drivers/bus_i2c_soft.c @@ -178,7 +178,7 @@ void i2cInit(I2CDevice device) bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t * data) { UNUSED(device); - + int i; if (!I2C_Start()) { i2cErrorCount++; @@ -206,7 +206,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, ui bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data) { UNUSED(device); - + if (!I2C_Start()) { return false; } @@ -227,7 +227,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t data) bool i2cRead(I2CDevice device, uint8_t addr, uint8_t reg, uint8_t len, uint8_t *buf) { UNUSED(device); - + if (!I2C_Start()) { return false; } diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 14049461a..281db6bf2 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -133,7 +133,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device) bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) { - + if (device == I2CINVALID) return false; @@ -141,10 +141,10 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + state->addr = addr_ << 1; state->reg = reg_; state->writing = 1; @@ -182,12 +182,12 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t { if (device == I2CINVALID) return false; - + uint32_t timeout = I2C_DEFAULT_TIMEOUT; I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); @@ -220,13 +220,13 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t } static void i2c_er_handler(I2CDevice device) { - + I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + // Read the I2C1 status register volatile uint32_t SR1Register = I2Cx->SR1; @@ -255,13 +255,13 @@ static void i2c_er_handler(I2CDevice device) { } void i2c_ev_handler(I2CDevice device) { - + I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + i2cState_t *state; state = &(i2cState[device]); - + static uint8_t subaddress_sent, final_stop; // flag to indicate if subaddess sent, flag to indicate final bus condition static int8_t index; // index is signed -1 == send the subaddress uint8_t SReg_1 = I2Cx->SR1; // read the status register here @@ -384,17 +384,17 @@ void i2cInit(I2CDevice device) IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); - - IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); - IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); + + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); // Enable RCC RCC_ClockCmd(i2c->rcc, ENABLE); - + 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); @@ -403,10 +403,10 @@ void i2cInit(I2CDevice device) IOConfigGPIO(scl, IOCFG_AF_OD); IOConfigGPIO(sda, IOCFG_AF_OD); #endif - + I2C_DeInit(i2c->dev); I2C_StructInit(&i2cInit); - + I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); // Disable EVT and ERR interrupts - they are enabled by the first request i2cInit.I2C_Mode = I2C_Mode_I2C; i2cInit.I2C_DutyCycle = I2C_DutyCycle_2; @@ -424,8 +424,8 @@ void i2cInit(I2CDevice device) I2C_Init(i2c->dev, &i2cInit); I2C_StretchClockCmd(i2c->dev, ENABLE); - - + + // I2C ER Interrupt nvic.NVIC_IRQChannel = i2c->er_irq; nvic.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_I2C_ER); diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index 39cdb3b23..58d0caff3 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -79,23 +79,23 @@ uint32_t i2cTimeoutUserCallback(void) void i2cInit(I2CDevice device) { - + i2cDevice_t *i2c; i2c = &(i2cHardwareMap[device]); I2C_TypeDef *I2Cx; I2Cx = i2c->dev; - + IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); - + RCC_ClockCmd(i2c->rcc, ENABLE); RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK); - IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); + IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device)); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); - IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { @@ -107,11 +107,11 @@ void i2cInit(I2CDevice device) .I2C_AcknowledgedAddress = I2C_AcknowledgedAddress_7bit, .I2C_Timing = (i2c->overClock ? I2C_HIGHSPEED_TIMING : I2C_STANDARD_TIMING) }; - + I2C_Init(I2Cx, &i2cInit); I2C_StretchClockCmd(I2Cx, ENABLE); - + I2C_Cmd(I2Cx, ENABLE); } @@ -126,7 +126,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { @@ -192,7 +192,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* I2C_TypeDef *I2Cx; I2Cx = i2cHardwareMap[device].dev; - + /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; while (I2C_GetFlagStatus(I2Cx, I2C_ISR_BUSY) != RESET) { diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index b3b3f992b..2eefe6edc 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -114,9 +114,9 @@ void spiInitDevice(SPIDevice device) RCC_ResetCmd(spi->rcc, ENABLE); IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1); - IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); - IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); - + IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1); + IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1); + #if defined(STM32F3) || defined(STM32F4) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); @@ -129,11 +129,11 @@ void spiInitDevice(SPIDevice device) IOConfigGPIO(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG); IOConfigGPIO(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG); IOConfigGPIO(IOGetByTag(spi->mosi), SPI_IO_AF_MOSI_CFG); - + if (spi->nss) IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG); #endif - + // Init SPI hardware SPI_I2S_DeInit(spi->dev); @@ -349,4 +349,4 @@ void spiResetErrorCounter(SPI_TypeDef *instance) SPIDevice device = spiDeviceByInstance(instance); if (device != SPIINVALID) spiHardwareMap[device].errorCount = 0; -} \ No newline at end of file +} diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index f4111e825..c788dd8fe 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -199,13 +199,13 @@ 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); IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG); - + DISABLE_M25P16; #ifndef M25P16_SPI_SHARED diff --git a/src/main/drivers/gpio.h b/src/main/drivers/gpio.h index 8f3a32a59..dfa8d3761 100644 --- a/src/main/drivers/gpio.h +++ b/src/main/drivers/gpio.h @@ -102,8 +102,8 @@ typedef struct #ifndef UNIT_TEST #ifdef STM32F4 -static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; } -static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; } +static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRRL = i; } +static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BSRRH = i; } #else static inline void digitalHi(GPIO_TypeDef *p, uint16_t i) { p->BSRR = i; } static inline void digitalLo(GPIO_TypeDef *p, uint16_t i) { p->BRR = i; } diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index 0b31d5d8e..fbbff6ffd 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -33,7 +33,7 @@ void initInverter(void) { IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0); IOConfigGPIO(pin, IOCFG_OUT_PP); - + inverterSet(false); } diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index bed28dab3..1b3cca2bc 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -13,7 +13,7 @@ typedef struct ioRec_s { uint16_t pin; resourceOwner_t owner; resourceType_t resource; - uint8_t index; + uint8_t index; } ioRec_t; extern ioRec_t ioRecs[DEFIO_IO_USED_COUNT]; diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 80582c1fa..5fe73a166 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -26,17 +26,17 @@ static const IO_t leds[] = { #ifdef LED0 DEFIO_IO(LED0), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #ifdef LED1 DEFIO_IO(LED1), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #ifdef LED2 DEFIO_IO(LED2), #else - DEFIO_IO(NONE), + DEFIO_IO(NONE), #endif #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) #ifdef LED0_A @@ -82,25 +82,25 @@ uint8_t ledOffset = 0; void ledInit(bool alternative_led) { - uint32_t i; + uint32_t i; #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) - if (alternative_led) - ledOffset = LED_NUMBER; + if (alternative_led) + ledOffset = LED_NUMBER; #else - UNUSED(alternative_led); + UNUSED(alternative_led); #endif - LED0_OFF; - LED1_OFF; - LED2_OFF; + LED0_OFF; + LED1_OFF; + LED2_OFF; - for (i = 0; i < LED_NUMBER; i++) { - if (leds[i + ledOffset]) { - IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); - IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); - } - } + for (i = 0; i < LED_NUMBER; i++) { + if (leds[i + ledOffset]) { + IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i)); + IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP); + } + } LED0_OFF; LED1_OFF; @@ -109,11 +109,11 @@ void ledInit(bool alternative_led) void ledToggle(int led) { - IOToggle(leds[led + ledOffset]); + IOToggle(leds[led + ledOffset]); } void ledSet(int led, bool on) { - bool inverted = (1 << (led + ledOffset)) & ledPolarity; - IOWrite(leds[led + ledOffset], on ? inverted : !inverted); + bool inverted = (1 << (led + ledOffset)) & ledPolarity; + IOWrite(leds[led + ledOffset], on ? inverted : !inverted); } diff --git a/src/main/drivers/light_ws2811strip_stm32f10x.c b/src/main/drivers/light_ws2811strip_stm32f10x.c index 863dd24ea..63c76baec 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -50,14 +50,14 @@ void ws2811LedStripHardwareInit(void) uint16_t prescalerValue; dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); - + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP)); - + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); - + /* Compute the prescaler value */ prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1; /* Time base configuration */ @@ -123,7 +123,7 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(TIM3, 0); TIM_Cmd(TIM3, ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f30x.c b/src/main/drivers/light_ws2811strip_stm32f30x.c index b27e30e51..782be0a98 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -59,14 +59,14 @@ void ws2811LedStripHardwareInit(void) DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; - + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); - + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); - + RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE); /* Compute the prescaler value */ @@ -134,7 +134,7 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(WS2811_TIMER, 0); TIM_Cmd(WS2811_TIMER, ENABLE); diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index cfde3411c..1b4c646a4 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -69,15 +69,15 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); + IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0); IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerGPIOAF(WS2811_TIMER)); - + // Stop timer TIM_Cmd(WS2811_TIMER, DISABLE); /* Compute the prescaler value */ prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1; - + /* Time base configuration */ TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue; @@ -94,7 +94,7 @@ void ws2811LedStripHardwareInit(void) TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable; TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable; TIM_OCInitStructure.TIM_Pulse = 0; - + uint32_t channelAddress = 0; switch (WS2811_TIMER_CHANNEL) { case TIM_Channel_1: @@ -102,28 +102,28 @@ void ws2811LedStripHardwareInit(void) timDMASource = TIM_DMA_CC1; channelAddress = (uint32_t)(&WS2811_TIMER->CCR1); TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_2: TIM_OC2Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC2; channelAddress = (uint32_t)(&WS2811_TIMER->CCR2); TIM_OC2PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_3: TIM_OC3Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC3; channelAddress = (uint32_t)(&WS2811_TIMER->CCR3); TIM_OC3PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; case TIM_Channel_4: TIM_OC4Init(WS2811_TIMER, &TIM_OCInitStructure); timDMASource = TIM_DMA_CC4; channelAddress = (uint32_t)(&WS2811_TIMER->CCR4); TIM_OC4PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable); - break; + break; } - - TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); + + TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE); TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE); TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable); @@ -132,7 +132,7 @@ void ws2811LedStripHardwareInit(void) dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, ws2811DMAHandler); /* configure DMA */ - DMA_Cmd(WS2811_DMA_STREAM, DISABLE); + DMA_Cmd(WS2811_DMA_STREAM, DISABLE); DMA_DeInit(WS2811_DMA_STREAM); DMA_StructInit(&DMA_InitStructure); DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL; @@ -151,13 +151,13 @@ void ws2811LedStripHardwareInit(void) DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single; DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single; - - RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); + + RCC_AHB1PeriphClockCmd(RCC_AHB1Periph_DMA1, ENABLE); DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure); DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE); - DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); - + DMA_ClearITPendingBit(WS2811_DMA_STREAM, WS2811_DMA_IT); + NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = WS2811_DMA_IRQ; @@ -175,11 +175,11 @@ void ws2811LedStripDMAEnable(void) { if (!ws2811Initialised) return; - + DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred TIM_SetCounter(WS2811_TIMER, 0); DMA_Cmd(WS2811_DMA_STREAM, ENABLE); TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE); } -#endif \ No newline at end of file +#endif diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 2636b6135..80d2b01d9 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -101,7 +101,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 diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index f9feb1a46..d75ff21c5 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -90,9 +90,9 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 configTimeBase(timerHardware->tim, period, mhz); - IO_t io = IOGetByTag(timerHardware->tag); - IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); - IOConfigGPIO(io, IOCFG_AF_PP); + IO_t io = IOGetByTag(timerHardware->tag); + IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); + IOConfigGPIO(io, IOCFG_AF_PP); pwmOCConfig(timerHardware->tim, timerHardware->channel, value, timerHardware->output & TIMER_OUTPUT_INVERTED); diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index 7250c6e79..a0f65f4e3 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -366,9 +366,9 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - IO_t io = IOGetByTag(timerHardwarePtr->tag); - IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); - IOConfigGPIO(io, timerHardwarePtr->ioMode); + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel)); + IOConfigGPIO(io, timerHardwarePtr->ioMode); pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); @@ -398,10 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - IO_t io = IOGetByTag(timerHardwarePtr->tag); - IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); - IOConfigGPIO(io, timerHardwarePtr->ioMode); - + IO_t io = IOGetByTag(timerHardwarePtr->tag); + IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0); + IOConfigGPIO(io, timerHardwarePtr->ioMode); + pwmICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Rising); timerConfigure(timerHardwarePtr, (uint16_t)PPM_TIMER_PERIOD, PWM_TIMER_MHZ); diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index 852c4adcf..722715fc1 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -550,7 +550,7 @@ void sdcard_init(bool useDMA) IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0); IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG); #endif // SDCARD_SPI_CS_PIN - + // Max frequency is initially 400kHz spiSetDivisor(SDCARD_SPI_INSTANCE, SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER); @@ -559,7 +559,7 @@ void sdcard_init(bool useDMA) // Transmit at least 74 dummy clock cycles with CS high so the SD card can start up SET_CS_HIGH; - + spiTransfer(SDCARD_SPI_INSTANCE, NULL, NULL, SDCARD_INIT_NUM_DUMMY_BYTES); // Wait for that transmission to finish before we enable the SDCard, so it receives the required number of cycles: @@ -1059,7 +1059,7 @@ bool sdcard_readBlock(uint32_t blockIndex, uint8_t *buffer, sdcard_operationComp sdcard.pendingOperation.blockIndex = blockIndex; sdcard.pendingOperation.callback = callback; sdcard.pendingOperation.callbackData = callbackData; - + sdcard.state = SDCARD_STATE_READING; sdcard.operationStartTime = millis(); diff --git a/src/main/drivers/serial_softserial.c b/src/main/drivers/serial_softserial.c index 082fddf9c..e44ff10a3 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -102,18 +102,18 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) void serialInputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); #ifdef STM32F1 - IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); + IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); #else - IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); + IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); #endif } static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); - IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); + IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); } static bool isTimerPeriodTooLarge(uint32_t timerPeriod) @@ -216,9 +216,9 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex); - + softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); - serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); + serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); setTxSignal(softSerial, ENABLE); delay(50); diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 8e73277fc..0a8515dc8 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -88,14 +88,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort1; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = rx1Buffer; s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; - + s->USARTx = USART1; @@ -179,14 +179,14 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort2; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; - + s->USARTx = USART2; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; @@ -207,7 +207,7 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); + IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } @@ -260,16 +260,16 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option RCC_ClockCmd(RCC_APB1(USART3), ENABLE); if (options & SERIAL_BIDIR) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TXRX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP); } if (mode & MODE_RX) { - IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); + IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); } } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index a7a3f004b..ae7516979 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -120,7 +120,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui } if (mode & MODE_RX) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); IOConfigGPIOAF(rx, ioCfg, af); } } @@ -136,14 +136,14 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort1; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = rx1Buffer; s->port.txBuffer = tx1Buffer; s->port.rxBufferSize = UART1_RX_BUFFER_SIZE; s->port.txBufferSize = UART1_TX_BUFFER_SIZE; - + #ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; #endif @@ -188,16 +188,16 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option s = &uartPort2; s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBufferSize = UART2_RX_BUFFER_SIZE; s->port.txBufferSize = UART2_TX_BUFFER_SIZE; s->port.rxBuffer = rx2Buffer; s->port.txBuffer = tx2Buffer; s->USARTx = USART2; - + #ifdef USE_UART2_RX_DMA s->rxDMAChannel = DMA1_Channel6; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 40f7a919e..d68942621 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -277,17 +277,17 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po uartDevice_t *uart = uartHardwareMap[device]; if (!uart) return NULL; - + s = &(uart->port); s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = uart->rxBuffer; s->port.txBuffer = uart->txBuffer; s->port.rxBufferSize = sizeof(uart->rxBuffer); s->port.txBufferSize = sizeof(uart->txBuffer); - + s->USARTx = uart->dev; if (uart->rxDMAStream) { s->rxDMAChannel = uart->DMAChannel; @@ -295,34 +295,34 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po } s->txDMAChannel = uart->DMAChannel; s->txDMAStream = uart->txDMAStream; - + s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - + IO_t tx = IOGetByTag(uart->tx); IO_t rx = IOGetByTag(uart->rx); - + if (uart->rcc_apb2) RCC_ClockCmd(uart->rcc_apb2, ENABLE); - + if (uart->rcc_apb1) RCC_ClockCmd(uart->rcc_apb1, ENABLE); - + if (uart->rcc_ahb1) RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE); - + if (options & SERIAL_BIDIR) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_OD, uart->af); } else { if (mode & MODE_TX) { - IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device)); IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); } - + if (mode & MODE_RX) { - IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); + IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } } diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index f489b16d3..5f1b22391 100644 --- a/src/main/drivers/serial_usb_vcp.c +++ b/src/main/drivers/serial_usb_vcp.c @@ -117,7 +117,7 @@ static bool usbVcpFlush(vcpPort_t *port) if (count == 0) { return true; } - + if (!usbIsConnected() || !usbIsConfigured()) { return false; } diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 0cf058a8a..cbfcf80a1 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -85,10 +85,10 @@ void hcsr04_init(sonarRange_t *sonarRange) triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); - + // echo pin echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); - IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); + IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); #ifdef USE_EXTI diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index 3e59fe734..c273c6f3d 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -69,10 +69,10 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); SetSysClock(false); - + #ifdef CC3D /* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */ extern void *isr_vector_table_base; @@ -115,4 +115,4 @@ void systemInit(void) void checkForBootLoaderRequest(void) { -} \ No newline at end of file +} diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index ee8aef1a0..d762e2c33 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -83,7 +83,7 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); // Enable FPU SCB->CPACR = (0x3 << (10 * 2)) | (0x3 << (11 * 2)); diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 53f3767a5..e7587aa9b 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -169,7 +169,7 @@ bool isMPUSoftReset(void) void systemInit(void) { - checkForBootLoaderRequest(); + checkForBootLoaderRequest(); SetSysClock(); @@ -183,7 +183,7 @@ void systemInit(void) extern void *isr_vector_table_base; NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0); RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE); - + RCC_ClearFlag(); enableGPIOPowerUsageAndNoiseReductions(); @@ -199,15 +199,15 @@ void systemInit(void) void(*bootJump)(void); void checkForBootLoaderRequest(void) { - if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { + if (*((uint32_t *)0x2001FFFC) == 0xDEADBEEF) { - *((uint32_t *)0x2001FFFC) = 0x0; + *((uint32_t *)0x2001FFFC) = 0x0; - __enable_irq(); - __set_MSP(0x20001000); - - bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); - bootJump(); - while (1); - } -} \ No newline at end of file + __enable_irq(); + __set_MSP(0x20001000); + + bootJump = (void(*)(void))(*((uint32_t *) 0x1fff0004)); + bootJump(); + while (1); + } +} diff --git a/src/main/flight/gtune.c b/src/main/flight/gtune.c index d32a93ad8..afef499d5 100644 --- a/src/main/flight/gtune.c +++ b/src/main/flight/gtune.c @@ -52,12 +52,12 @@ extern uint8_t motorCount; **************************************************************************** *** G_Tune *** **************************************************************************** - G_Tune Mode - This is the multiwii implementation of ZERO-PID Algorithm - http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html - The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) + G_Tune Mode + This is the multiwii implementation of ZERO-PID Algorithm + http://technicaladventure.blogspot.com/2014/06/zero-pids-tuner-for-multirotors.html + The algorithm has been originally developed by Mohammad Hefny (mohammad.hefny@gmail.com) - You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. + You may use/modify this algorithm on your own risk, kindly refer to above link in any future distribution. */ /* @@ -107,13 +107,13 @@ void init_Gtune(pidProfile_t *pidProfileToTune) uint8_t i; pidProfile = pidProfileToTune; - if (pidProfile->pidController == 2) { - floatPID = true; // LuxFloat is using float values for PID settings - } else { - floatPID = false; - } - updateDelayCycles(); - for (i = 0; i < 3; i++) { + if (pidProfile->pidController == 2) { + floatPID = true; // LuxFloat is using float values for PID settings + } else { + floatPID = false; + } + updateDelayCycles(); + for (i = 0; i < 3; i++) { if ((pidProfile->gtune_hilimP[i] && pidProfile->gtune_lolimP[i] > pidProfile->gtune_hilimP[i]) || (motorCount < 4 && i == FD_YAW)) { // User config error disable axisis for tuning pidProfile->gtune_hilimP[i] = 0; // Disable YAW tuning for everything below a quadcopter } diff --git a/src/main/flight/imu.c b/src/main/flight/imu.c index d885d30ea..8945e765e 100644 --- a/src/main/flight/imu.c +++ b/src/main/flight/imu.c @@ -84,7 +84,7 @@ STATIC_UNIT_TESTED void imuComputeRotationMatrix(void) float q1q1 = sq(q1); float q2q2 = sq(q2); float q3q3 = sq(q3); - + float q0q1 = q0 * q1; float q0q2 = q0 * q2; float q0q3 = q0 * q3; diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b5da4a017..fbde38a3f 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -395,7 +395,7 @@ void loadCustomServoMixer(void) // check if done if (customServoMixers[i].rate == 0) break; - + currentServoMixer[i] = customServoMixers[i]; servoRuleCount++; } @@ -426,9 +426,9 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura motorCount = 0; servoCount = pwmOutputConfiguration->servoCount; - + syncPwm = use_unsyncedPwm; - + if (currentMixerMode == MIXER_CUSTOM || currentMixerMode == MIXER_CUSTOM_TRI || currentMixerMode == MIXER_CUSTOM_AIRPLANE) { // load custom mixer into currentMixer for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) { @@ -454,7 +454,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura currentServoMixer[i] = servoMixers[currentMixerMode].rule[i]; } } - + // in 3D mode, mixer gain has to be halved if (feature(FEATURE_3D)) { if (motorCount > 1) { @@ -472,7 +472,7 @@ void mixerUsePWMOutputConfiguration(pwmOutputConfiguration_t *pwmOutputConfigura currentMixerMode == MIXER_CUSTOM_AIRPLANE ) { ENABLE_STATE(FIXED_WING); - + if (currentMixerMode == MIXER_CUSTOM_AIRPLANE) { loadCustomServoMixer(); } @@ -901,7 +901,7 @@ void mixTable(void) /* case MIXER_GIMBAL: - servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); + servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); break; */ diff --git a/src/main/main.c b/src/main/main.c index 455d4b260..01865fdbf 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -166,8 +166,8 @@ void init(void) //i2cSetOverclock(masterConfig.i2c_overclock); // initialize IO (needed for all IO operations) - IOInitGlobal(); - + IOInitGlobal(); + debugMode = masterConfig.debug_mode; #ifdef USE_HARDWARE_REVISION_DETECTION @@ -188,7 +188,7 @@ void init(void) ledInit(false); #endif LED2_ON; - + #ifdef USE_EXTI EXTIInit(); #endif @@ -286,7 +286,7 @@ void init(void) #endif #if defined(USE_UART6) && defined(STM32F40_41xxx) pwm_params.useUART6 = doesConfigurationUsePort(SERIAL_PORT_USART6); -#endif +#endif pwm_params.useVbat = feature(FEATURE_VBAT); pwm_params.useSoftSerial = feature(FEATURE_SOFTSERIAL); pwm_params.useParallelPWM = feature(FEATURE_RX_PARALLEL_PWM); @@ -309,7 +309,7 @@ void init(void) } else { featureClear(FEATURE_ONESHOT125); } - + bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; // Configurator feature abused for enabling Fast PWM @@ -319,7 +319,7 @@ void init(void) pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; if (feature(FEATURE_3D)) pwm_params.idlePulse = masterConfig.flight3DConfig.neutral3d; - + if (masterConfig.motor_pwm_protocol == PWM_TYPE_BRUSHED) { featureClear(FEATURE_3D); pwm_params.idlePulse = 0; // brushed motors @@ -363,7 +363,7 @@ void init(void) #endif #ifdef CC3D if (masterConfig.use_buzzer_p6 == 1) - beeperConfig.ioTag = IO_TAG(BEEPER_OPT); + beeperConfig.ioTag = IO_TAG(BEEPER_OPT); #endif beeperInit(&beeperConfig); @@ -501,7 +501,7 @@ void init(void) LED1_ON; LED0_OFF; LED2_OFF; - + for (int i = 0; i < 10; i++) { LED1_TOGGLE; LED0_TOGGLE; diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 255fb547e..50fe4f457 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -590,12 +590,12 @@ void updateRSSIPWM(void) int16_t pwmRssi = 0; // Read value of AUX channel as rssi pwmRssi = rcData[rxConfig->rssi_channel - 1]; - - // RSSI_Invert option - if (rxConfig->rssi_ppm_invert) { - pwmRssi = ((2000 - pwmRssi) + 1000); - } - + + // RSSI_Invert option + if (rxConfig->rssi_ppm_invert) { + pwmRssi = ((2000 - pwmRssi) + 1000); + } + // Range of rawPwmRssi is [1000;2000]. rssi should be in [0;1023]; rssi = (uint16_t)((constrain(pwmRssi - 1000, 0, 1000) / 1000.0f) * 1023.0f); } diff --git a/src/main/rx/spektrum.c b/src/main/rx/spektrum.c index ef6a8fa3d..fb211bfcf 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -245,7 +245,7 @@ void spektrumBind(rxConfig_t *rxConfig) #ifndef HARDWARE_BIND_PLUG // If we came here as a result of hard reset (power up, with spektrum_sat_bind set), then reset it back to zero and write config // Don't reset if hardware bind plug is present - // Reset only when autoreset is enabled + // Reset only when autoreset is enabled if (rxConfig->spektrum_sat_bind_autoreset == 1 && !isMPUSoftReset()) { rxConfig->spektrum_sat_bind = 0; saveConfigAndNotify(); diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index ba70eb579..0e6885489 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -71,7 +71,7 @@ // 2200µs -> 0xFFF // Total range is: 2200 - 800 = 1400 <==> 4095 // Use formula: 800 + value * 1400 / 4096 (i.e. a shift by 12) -#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12)) +#define XBUS_CONVERT_TO_USEC(V) (800 + ((V * 1400) >> 12)) static bool xBusFrameReceived = false; static bool xBusDataIncoming = false; @@ -148,7 +148,7 @@ bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRa static uint16_t xBusCRC16(uint16_t crc, uint8_t value) { uint8_t i; - + crc = crc ^ (int16_t)value << 8; for (i = 0; i < 8; i++) { @@ -181,7 +181,7 @@ uint8_t xBusRj01CRC8(uint8_t inData, uint8_t seed) inData >>= 1; } - return seed; + return seed; } @@ -240,7 +240,7 @@ static void xBusUnpackRJ01Frame(void) // method. // So, we check both these values as well as the provided length // of the outer/full message (LEN) - + // // Check we have correct length of message // @@ -249,14 +249,14 @@ static void xBusUnpackRJ01Frame(void) // Unknown package as length is not ok return; } - + // // CRC calculation & check for full message // for (i = 0; i < xBusFrameLength - 1; i++) { outerCrc = xBusRj01CRC8(outerCrc, xBusFrame[i]); } - + if (outerCrc != xBusFrame[xBusFrameLength - 1]) { // CRC does not match, skip this frame @@ -281,7 +281,7 @@ static void xBusDataReceive(uint16_t c) xBusFramePosition = 0; xBusDataIncoming = false; } - + // Check if we shall start a frame? if ((xBusFramePosition == 0) && (c == XBUS_START_OF_FRAME_BYTE)) { xBusDataIncoming = true; @@ -293,7 +293,7 @@ static void xBusDataReceive(uint16_t c) xBusFrame[xBusFramePosition] = (uint8_t)c; xBusFramePosition++; } - + // Done? if (xBusFramePosition == xBusFrameLength) { switch (xBusProvider) { diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index 7fe3fea8e..cff97d77e 100755 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -139,7 +139,7 @@ void rescheduleTask(cfTaskId_e taskId, uint32_t newPeriodMicros) { if (taskId == TASK_SELF || taskId < TASK_COUNT) { cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId]; - task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging + task->desiredPeriod = MAX(SCHEDULER_DELAY_LIMIT, newPeriodMicros); // Limit delay to 100us (10 kHz) to prevent scheduler clogging } } diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index ab3b9c5cf..2d7b44e55 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -68,7 +68,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading) static int currentFilterSampleIndex = 0; static bool medianFilterReady = false; int nextSampleIndex; - + nextSampleIndex = (currentFilterSampleIndex + 1); if (nextSampleIndex == PRESSURE_SAMPLES_MEDIAN) { nextSampleIndex = 0; @@ -77,7 +77,7 @@ static int32_t applyBarometerMedianFilter(int32_t newPressureReading) barometerFilterSamples[currentFilterSampleIndex] = newPressureReading; currentFilterSampleIndex = nextSampleIndex; - + if (medianFilterReady) return quickMedianFilter3(barometerFilterSamples); else diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 84888e310..c6e3be93c 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -86,7 +86,7 @@ static void updateBatteryVoltage(void) void updateBattery(void) { updateBatteryVoltage(); - + /* battery has just been connected*/ if (batteryState == BATTERY_NOT_PRESENT && vbat > VBATT_PRESENT_THRESHOLD_MV) { @@ -115,7 +115,7 @@ void updateBattery(void) batteryCellCount = 0; batteryWarningVoltage = 0; batteryCriticalVoltage = 0; - } + } switch(batteryState) { diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 870959879..eb206627b 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -93,7 +93,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) return selectMPUIntExtiConfigByHardwareRevision(); #else return NULL; -#endif +#endif } #ifdef USE_FAKE_GYRO @@ -233,7 +233,7 @@ bool detectGyro(void) } #endif ; // fallthrough - + case GYRO_MPU9250: #ifdef USE_GYRO_SPI_MPU9250 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 4d3b7a58a..e83499615 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -94,7 +94,7 @@ #define USE_VCP //#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_ENABLED - + #define USE_UART1 #define UART1_RX_PIN PA10 #define UART1_TX_PIN PA9 diff --git a/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c index f23932a6e..655f19cfe 100644 --- a/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c +++ b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c @@ -237,7 +237,7 @@ void bstInitPort(I2C_TypeDef *BSTx/*, uint8_t Address*/) NVIC_Init(&nvic); I2C_ITConfig(I2C1, I2C_IT_ADDRI | I2C_IT_RXI | I2C_IT_STOPI | I2C_IT_NACKI | I2C_IT_ERRI, ENABLE); - + I2C_Cmd(I2C1, ENABLE); } diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index c07a92541..c813ceecb 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -78,7 +78,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM2 - PB8 { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM3 - PB9 - + { TIM2, IO_TAG(PA10), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PMW4 - PA10 { TIM2, IO_TAG(PA9), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10 }, // PWM5 - PA9 { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM6 - PA0 diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index e52da0ab2..21b05ab5d 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -23,7 +23,7 @@ const uint16_t multiPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -46,7 +46,7 @@ const uint16_t multiPWM[] = { const uint16_t airPPM[] = { PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), PWM6 | (MAP_TO_SERVO_OUTPUT << 8), diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index d71edde62..3f87237db 100755 --- a/src/main/target/NAZE/hardware_revision.c +++ b/src/main/target/NAZE/hardware_revision.c @@ -70,7 +70,7 @@ uint8_t detectSpiDevice(void) #ifdef NAZE_SPI_CS_PIN nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); #endif - + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; uint8_t in[4]; uint32_t flash_id; diff --git a/src/main/target/system_stm32f30x.c b/src/main/target/system_stm32f30x.c index 78274ac32..09ba3fa47 100644 --- a/src/main/target/system_stm32f30x.c +++ b/src/main/target/system_stm32f30x.c @@ -8,7 +8,7 @@ * This file contains the system clock configuration for STM32F30x devices, * 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 * user application: * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier @@ -21,7 +21,7 @@ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used * by the user application to setup the SysTick * timer or configure other parameters. - * + * * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must * be called whenever the core clock is changed * during program execution. @@ -41,7 +41,7 @@ * * 5. This file configures the system clock as follows: *============================================================================= - * Supported STM32F30x device + * Supported STM32F30x device *----------------------------------------------------------------------------- * System Clock source | PLL (HSE) *----------------------------------------------------------------------------- @@ -204,34 +204,34 @@ 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. - * + * 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(**) * 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. - * + * * (**) 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 * frequency of the crystal used. Otherwise, this function may * have wrong result. - * + * * - The result of this function could be not correct when using fractional * value for HSE crystal. - * + * * @param None * @retval None */ @@ -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 */ @@ -266,7 +266,7 @@ void SystemCoreClockUpdate (void) prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; /* HSE oscillator clock selected as PREDIV1 clock entry */ SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; - } + } break; default: /* HSI used as system clock */ SystemCoreClock = HSI_VALUE; @@ -282,8 +282,8 @@ void SystemCoreClockUpdate (void) /** * @brief Configures the System clock source, PLL Multiplier and Divider factors, * AHB/APBx prescalers and Flash settings - * @note This function should be called only once the RCC clock configuration - * is reset to the default reset state (done in SystemInit() function). + * @note This function should be called only once the RCC clock configuration + * is reset to the default reset state (done in SystemInit() function). * @param None * @retval None */ @@ -322,10 +322,10 @@ void SetSysClock(void) /* 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; @@ -340,7 +340,7 @@ void SetSysClock(void) while((RCC->CR & RCC_CR_PLLRDY) == 0) { } - + /* Select PLL as system clock source */ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW)); RCC->CFGR |= (uint32_t)RCC_CFGR_SW_PLL; diff --git a/src/main/target/system_stm32f4xx.h b/src/main/target/system_stm32f4xx.h index 6d130d851..e26636680 100644 --- a/src/main/target/system_stm32f4xx.h +++ b/src/main/target/system_stm32f4xx.h @@ -4,7 +4,7 @@ * @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 * diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 36b7c9556..28daadc40 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -279,7 +279,7 @@ void checkSmartPortTelemetryState(void) void handleSmartPortTelemetry(void) { uint32_t smartPortLastServiceTime = millis(); - + if (!smartPortTelemetryEnabled) { return; } @@ -307,7 +307,7 @@ void handleSmartPortTelemetry(void) smartPortHasRequest = 0; return; } - + // we can send back any data we want, our table keeps track of the order and frequency of each data type we send uint16_t id = frSkyDataIdTable[smartPortIdCnt]; if (id == 0) { // end of table reached, loop back diff --git a/src/main/telemetry/telemetry.c b/src/main/telemetry/telemetry.c index f4f38ba94..e3871aead 100644 --- a/src/main/telemetry/telemetry.c +++ b/src/main/telemetry/telemetry.c @@ -56,7 +56,7 @@ void telemetryInit(void) initSmartPortTelemetry(telemetryConfig); initLtmTelemetry(telemetryConfig); initJetiExBusTelemetry(telemetryConfig); - + telemetryCheckState(); } diff --git a/src/main/vcpf4/usb_conf.h b/src/main/vcpf4/usb_conf.h index 60c803620..ea8d49bcf 100644 --- a/src/main/vcpf4/usb_conf.h +++ b/src/main/vcpf4/usb_conf.h @@ -207,12 +207,12 @@ /****************** C Compilers dependant keywords ****************************/ /* In HS mode and when the DMA is used, all variables and data structures dealing - with the DMA during the transaction process should be 4-bytes aligned */ + with the DMA during the transaction process should be 4-bytes aligned */ #ifdef USB_OTG_HS_INTERNAL_DMA_ENABLED #if defined (__GNUC__) /* GNU Compiler */ #define __ALIGN_END __attribute__ ((aligned (4))) - #define __ALIGN_BEGIN - #else + #define __ALIGN_BEGIN + #else #define __ALIGN_END #if defined (__CC_ARM) /* ARM Compiler */ #define __ALIGN_BEGIN __align(4) diff --git a/src/main/vcpf4/usbd_cdc_vcp.c b/src/main/vcpf4/usbd_cdc_vcp.c index 8b789fa48..5672eeae5 100644 --- a/src/main/vcpf4/usbd_cdc_vcp.c +++ b/src/main/vcpf4/usbd_cdc_vcp.c @@ -111,23 +111,23 @@ static uint16_t VCP_Ctrl(uint32_t Cmd, uint8_t* Buf, uint32_t Len) break; // Not needed for this driver - case SET_COMM_FEATURE: + case SET_COMM_FEATURE: case GET_COMM_FEATURE: case CLEAR_COMM_FEATURE: break; - + //Note - hw flow control on UART 1-3 and 6 only 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 @@ -234,7 +234,7 @@ static uint16_t VCP_DataRx(uint8_t* Buf, uint32_t Len) if(receiveLength > (USB_RX_BUFSIZE-1)) return USBD_FAIL; - + return USBD_OK; } diff --git a/src/main/vcpf4/usbd_desc.c b/src/main/vcpf4/usbd_desc.c index f3f9a3af9..ab1a3e1d3 100644 --- a/src/main/vcpf4/usbd_desc.c +++ b/src/main/vcpf4/usbd_desc.c @@ -166,8 +166,8 @@ __ALIGN_BEGIN uint8_t USBD_DeviceQualifierDesc[USB_LEN_DEV_QUALIFIER_DESC] __ALI /* 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), }; diff --git a/src/main/vcpf4/usbd_usr.c b/src/main/vcpf4/usbd_usr.c index 395400d29..958e77232 100644 --- a/src/main/vcpf4/usbd_usr.c +++ b/src/main/vcpf4/usbd_usr.c @@ -63,7 +63,7 @@ void USBD_USR_DeviceReset(uint8_t speed ) break; default: break; - + } }