diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 46bae19584..c529f4132b 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/atomic.h b/src/main/common/atomic.h index 9473c85a0e..b2aea26282 100644 --- a/src/main/common/atomic.h +++ b/src/main/common/atomic.h @@ -85,7 +85,7 @@ static inline uint8_t __basepriSetRetVal(uint8_t prio) // ideally this would only protect memory passed as parameter (any type should work), but gcc is curently creating almost full barrier // this macro can be used only ONCE PER LINE, but multiple uses per block are fine -#if (__GNUC__ > 4) +#if (__GNUC__ > 5) #warning "Please verify that ATOMIC_BARRIER works as intended" // increment version number is BARRIER works // TODO - use flag to disable ATOMIC_BARRIER and use full barrier instead diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 95e664a3cf..7847fb3035 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 e7606fbb94..dff4efdd2d 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 db9e8c0c52..a5c0591918 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 003b7c32a7..06ba7c9c09 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/config/config.h b/src/main/config/config.h index c26bbe6455..5a46a78c33 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -17,7 +17,11 @@ #pragma once +#if FLASH_SIZE <= 128 #define MAX_PROFILE_COUNT 2 +#else +#define MAX_PROFILE_COUNT 3 +#endif #define MAX_RATEPROFILES 3 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 diff --git a/src/main/drivers/accgyro_l3gd20.c b/src/main/drivers/accgyro_l3gd20.c index aade7445b2..e227d7f8d4 100644 --- a/src/main/drivers/accgyro_l3gd20.c +++ b/src/main/drivers/accgyro_l3gd20.c @@ -76,7 +76,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx) UNUSED(SPIx); // FIXME mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN)); - IOInit(mpul3gd20CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpul3gd20CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG); DISABLE_L3GD20; diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 4adbe59ab8..202b90e804 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -105,7 +105,7 @@ static inline void mma8451ConfigureInterrupt(void) // PA5 - ACC_INT2 output on NAZE rev3/4 hardware // NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board // OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code. - IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_SYSTEM, RESOURCE_I2C); + IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0); IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? #endif diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index b52a2fb796..9a3cd57253 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) { @@ -244,14 +244,14 @@ void mpuIntExtiInit(void) } #endif - IOInit(mpuIntIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI); + IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0); IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler); 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 cb78ffe102..8c277dea5c 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_SYSTEM, RESOURCE_SPI); + 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_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c index 2731797258..32ae6a1ce8 100755 --- a/src/main/drivers/accgyro_spi_mpu6500.c +++ b/src/main/drivers/accgyro_spi_mpu6500.c @@ -69,7 +69,7 @@ static void mpu6500SpiInit(void) } mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN)); - IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(mpuSpi6500CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG); spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST); diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index 95c0b3f50f..219bd51a21 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -191,9 +191,9 @@ bool mpu9250SpiDetect(void) #ifdef MPU9250_CS_PIN mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN)); #endif - IOInit(mpuSpi9250CsPin, OWNER_SYSTEM, RESOURCE_SPI); + 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 d214b49d35..a65abf9128 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 ee2e92d40f..258c8acc8d 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 9d94742468..451c9296c6 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 @@ -123,18 +123,18 @@ void adcInit(drv_adc_config_t *init) if (!adcConfig[i].tag) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i, 0); IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0)); adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag); adcConfig[i].dmaIndex = configuredAdcChannels++; 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 0116a6734a..6297c2bd16 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -132,14 +132,14 @@ 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) continue; - IOInit(IOGetByTag(adcConfig[i].tag), OWNER_SYSTEM, RESOURCE_ADC); + 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 = adcChannelCount++; diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index e0b36a5f33..e1bb1ae617 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_SYSTEM, RESOURCE_ADC); + 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 34a01cd38e..4c3e779855 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -143,7 +143,7 @@ void bmp085InitXclrIO(const bmp085Config_t *config) { if (!xclrIO && config && config->xclrIO) { xclrIO = IOGetByTag(config->xclrIO); - IOInit(xclrIO, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(xclrIO, OWNER_BARO, RESOURCE_OUTPUT, 0); IOConfigGPIO(xclrIO, IOCFG_OUT_PP); } } @@ -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/barometer_spi_bmp280.c b/src/main/drivers/barometer_spi_bmp280.c index 3838ba4328..d7a7491959 100644 --- a/src/main/drivers/barometer_spi_bmp280.c +++ b/src/main/drivers/barometer_spi_bmp280.c @@ -65,7 +65,7 @@ void bmp280SpiInit(void) } bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN)); - IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI); + IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI_CS, 0); IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP); DISABLE_BMP280; diff --git a/src/main/drivers/bus_i2c_soft.c b/src/main/drivers/bus_i2c_soft.c index cac5c62211..104c77c379 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 72cf8769c2..281db6bf2d 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_SYSTEM, RESOURCE_I2C); - IOInit(sda, OWNER_SYSTEM, RESOURCE_I2C); + + 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 11704a3f90..58d0caff31 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -79,20 +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)); IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4); + + IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device)); IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4); I2C_InitTypeDef i2cInit = { @@ -104,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); } @@ -123,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) { @@ -189,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 6aa32a1e8f..2eefe6edc6 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -113,19 +113,13 @@ void spiInitDevice(SPIDevice device) RCC_ClockCmd(spi->rcc, ENABLE); RCC_ResetCmd(spi->rcc, ENABLE); - IOInit(IOGetByTag(spi->sck), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->miso), OWNER_SYSTEM, RESOURCE_SPI); - IOInit(IOGetByTag(spi->mosi), OWNER_SYSTEM, RESOURCE_SPI); - -#if defined(STM32F303xC) || defined(STM32F4) - if (spi->sdcard) { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_MISO_CFG, spi->af); - } - else { - IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af); - IOConfigGPIOAF(IOGetByTag(spi->miso), SPI_IO_AF_CFG, spi->af); - } + 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); + +#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); IOConfigGPIOAF(IOGetByTag(spi->mosi), SPI_IO_AF_CFG, spi->af); if (spi->nss) @@ -135,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); diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index 64046904fe..dbba94881c 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -30,7 +30,7 @@ #define SPI_IO_AF_SCK_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_MOSI_CFG IO_CONFIG(GPIO_Mode_AF_PP, GPIO_Speed_50MHz) #define SPI_IO_AF_MISO_CFG IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz) -#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_OD, GPIO_Speed_50MHz) +#define SPI_IO_CS_CFG IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz) #else #error "Unknown processor" #endif diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 1063debae6..c788dd8fe1 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); + 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 8f3a32a59a..dfa8d3761f 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 e0231ddb78..fbbff6ffd4 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -31,9 +31,9 @@ static const IO_t pin = DEFIO_IO(INVERTER); void initInverter(void) { - IOInit(pin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 0); IOConfigGPIO(pin, IOCFG_OUT_PP); - + inverterSet(false); } diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 11562cfc98..980168abba 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -53,6 +53,19 @@ const struct ioPortDef_s ioPortDefs[] = { }; # endif +const char * const ownerNames[OWNER_TOTAL_COUNT] = { + "FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER", + "SONAR", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD", + "BARO", "MPU", "INVERTER", "LED STRIP", "LED", "RECEIVER", "TRANSMITTER" +}; + +const char * const resourceNames[RESOURCE_TOTAL_COUNT] = { + "", // NONE + "IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL", + "SDA", "SCK","MOSI","MISO","CS","BATTERY","RSSI","EXT","CURRENT" +}; + + ioRec_t* IO_Rec(IO_t io) { return io; @@ -190,12 +203,12 @@ void IOToggle(IO_t io) } // claim IO pin, set owner and resources -void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources) +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index) { ioRec_t *ioRec = IO_Rec(io); - if (owner != OWNER_FREE) // pass OWNER_FREE to keep old owner - ioRec->owner = owner; - ioRec->resourcesUsed |= resources; + ioRec->owner = owner; + ioRec->resource = resource; + ioRec->index = index; } void IORelease(IO_t io) @@ -210,10 +223,10 @@ resourceOwner_t IOGetOwner(IO_t io) return ioRec->owner; } -resourceType_t IOGetResources(IO_t io) +resourceType_t IOGetResource(IO_t io) { ioRec_t *ioRec = IO_Rec(io); - return ioRec->resourcesUsed; + return ioRec->resource; } #if defined(STM32F1) diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 315560e430..07c53a2032 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -86,7 +86,7 @@ void IOHi(IO_t io); void IOLo(IO_t io); void IOToggle(IO_t io); -void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resources); +void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index); void IORelease(IO_t io); // unimplemented resourceOwner_t IOGetOwner(IO_t io); resourceType_t IOGetResources(IO_t io); diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 3a084949fe..1b3cca2bcf 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -12,7 +12,8 @@ typedef struct ioRec_s { GPIO_TypeDef *gpio; uint16_t pin; resourceOwner_t owner; - resourceType_t resourcesUsed; // TODO! + resourceType_t resource; + 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 15075580b6..5fe73a1664 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_SYSTEM, RESOURCE_OUTPUT); - 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 6e164e0fb3..96bb85fd26 100644 --- a/src/main/drivers/light_ws2811strip_stm32f10x.c +++ b/src/main/drivers/light_ws2811strip_stm32f10x.c @@ -48,13 +48,15 @@ void ws2811LedStripHardwareInit(void) uint16_t prescalerValue; + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + 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 */ @@ -103,8 +105,6 @@ void ws2811LedStripHardwareInit(void) DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE); - dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); - ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); @@ -114,7 +114,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 c1db3b19c3..ff52a64836 100644 --- a/src/main/drivers/light_ws2811strip_stm32f30x.c +++ b/src/main/drivers/light_ws2811strip_stm32f30x.c @@ -56,12 +56,14 @@ void ws2811LedStripHardwareInit(void) DMA_InitTypeDef DMA_InitStructure; uint16_t prescalerValue; - + + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); + ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + 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 */ @@ -109,8 +111,6 @@ void ws2811LedStripHardwareInit(void) DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE); - dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); - ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); @@ -120,7 +120,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 3aff176780..3a888bd21b 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -67,15 +67,15 @@ void ws2811LedStripHardwareInit(void) ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN)); /* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */ - IOInit(ws2811IO, OWNER_SYSTEM, RESOURCE_OUTPUT); + 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; @@ -92,7 +92,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: @@ -100,35 +100,35 @@ 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); TIM_Cmd(WS2811_TIMER, ENABLE); /* 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; @@ -150,10 +150,10 @@ void ws2811LedStripHardwareInit(void) 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); + dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0); - + ws2811Initialised = true; setStripColor(&hsv_white); ws2811UpdateStrip(); @@ -163,7 +163,7 @@ 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); diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index eeefa940d9..793f6f77eb 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -55,7 +55,8 @@ MAX7456_CHAR_TYPE* max7456_get_screen_buffer(void) { return SCREEN_BUFFER; } -static uint8_t max7456_send(uint8_t add, uint8_t data) { +static uint8_t max7456_send(uint8_t add, uint8_t data) +{ spiTransferByte(MAX7456_SPI_INSTANCE, add); return spiTransferByte(MAX7456_SPI_INSTANCE, data); } @@ -157,7 +158,7 @@ void max7456_init(uint8_t video_system) #ifdef MAX7456_SPI_CS_PIN max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN)); #endif - IOInit(max7456CsPin, OWNER_SYSTEM, RESOURCE_SPI); + IOInit(max7456CsPin, OWNER_OSD, RESOURCE_SPI_CS, 0); IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG); //Minimum spi clock period for max7456 is 100ns (10Mhz) diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 5e797ea2f0..80d2b01d92 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -93,16 +93,6 @@ pwmOutputConfiguration_t *pwmGetOutputConfiguration(void) return &pwmOutputConfiguration; } -bool CheckGPIOPin(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) -{ - return IO_GPIOBYTAG(tag) == gpio && IO_PINBYTAG(tag) == pin; -} - -bool CheckGPIOPinSource(ioTag_t tag, GPIO_TypeDef *gpio, uint16_t pin) -{ - return IO_GPIOBYTAG(tag) == gpio && IO_GPIO_PinSource(IOGetByTag(tag)) == pin; -} - pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) { int i = 0; @@ -111,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 @@ -142,9 +132,9 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) continue; #endif -#if defined(STM32F303xC) && defined(USE_USART3) +#if defined(STM32F303xC) && defined(USE_UART3) // skip UART3 ports (PB10/PB11) - if (init->useUART3 && (CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_TX_PIN) || CheckGPIOPin(timerHardwarePtr->tag, UART3_GPIO, UART3_RX_PIN))) + if (init->useUART3 && (timerHardwarePtr->tag == IO_TAG(UART3_TX_PIN) || timerHardwarePtr->tag == IO_TAG(UART3_RX_PIN))) continue; #endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 277b47736d..d75ff21c57 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -84,18 +84,15 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8 } } -static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) -{ - IOInit(IOGetByTag(pin), OWNER_PWMOUTPUT_MOTOR, RESOURCE_OUTPUT); - IOConfigGPIO(IOGetByTag(pin), mode); -} - static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8_t mhz, uint16_t period, uint16_t value) { pwmOutputPort_t *p = &pwmOutputPorts[allocatedOutputPortCount++]; configTimeBase(timerHardware->tim, period, mhz); - pwmGPIOConfig(timerHardware->tag, 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 856613d2b3..a0f65f4e3a 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -337,12 +337,6 @@ static void pwmEdgeCallback(timerCCHandlerRec_t *cbRec, captureCompare_t capture } } -static void pwmGPIOConfig(ioTag_t pin, ioConfig_t mode) -{ - IOInit(IOGetByTag(pin), OWNER_PWMINPUT, RESOURCE_INPUT); - IOConfigGPIO(IOGetByTag(pin), mode); -} - void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) { TIM_ICInitTypeDef TIM_ICInitStructure; @@ -372,7 +366,10 @@ void pwmInConfig(const timerHardware_t *timerHardwarePtr, uint8_t channel) self->mode = INPUT_MODE_PWM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->tag, 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); timerConfigure(timerHardwarePtr, (uint16_t)PWM_TIMER_PERIOD, PWM_TIMER_MHZ); @@ -401,7 +398,10 @@ void ppmInConfig(const timerHardware_t *timerHardwarePtr) self->mode = INPUT_MODE_PPM; self->timerHardware = timerHardwarePtr; - pwmGPIOConfig(timerHardwarePtr->tag, 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/resource.h b/src/main/drivers/resource.h index a81739bf12..a177dab1da 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -1,46 +1,52 @@ #pragma once +#define RESOURCE_INDEX(x) x + 1 + typedef enum { OWNER_FREE = 0, OWNER_PWMINPUT, OWNER_PPMINPUT, - OWNER_PWMOUTPUT_MOTOR, - OWNER_PWMOUTPUT_SERVO, - OWNER_SOFTSERIAL_RX, - OWNER_SOFTSERIAL_TX, - OWNER_SOFTSERIAL_RXTX, // bidirectional pin for softserial - OWNER_SOFTSERIAL_AUXTIMER, // timer channel is used for softserial. No IO function on pin + OWNER_MOTOR, + OWNER_SERVO, + OWNER_SOFTSERIAL, OWNER_ADC, - OWNER_SERIAL_RX, - OWNER_SERIAL_TX, - OWNER_SERIAL_RXTX, + OWNER_SERIAL, OWNER_PINDEBUG, OWNER_TIMER, OWNER_SONAR, OWNER_SYSTEM, + OWNER_SPI, + OWNER_I2C, OWNER_SDCARD, OWNER_FLASH, OWNER_USB, OWNER_BEEPER, OWNER_OSD, OWNER_BARO, + OWNER_MPU, + OWNER_INVERTER, + OWNER_LED_STRIP, + OWNER_LED, + OWNER_RX, + OWNER_TX, OWNER_TOTAL_COUNT } resourceOwner_t; +extern const char * const ownerNames[OWNER_TOTAL_COUNT]; + // Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function) // with mode switching (shared serial ports, ...) this will need some improvement typedef enum { RESOURCE_NONE = 0, - RESOURCE_INPUT = 1 << 0, - RESOURCE_OUTPUT = 1 << 1, - RESOURCE_IO = RESOURCE_INPUT | RESOURCE_OUTPUT, - RESOURCE_TIMER = 1 << 2, - RESOURCE_TIMER_DUAL = 1 << 3, // channel used in dual-capture, other channel will be allocated too - RESOURCE_USART = 1 << 4, - RESOURCE_ADC = 1 << 5, - RESOURCE_EXTI = 1 << 6, - RESOURCE_I2C = 1 << 7, - RESOURCE_SPI = 1 << 8, + RESOURCE_INPUT, RESOURCE_OUTPUT, RESOURCE_IO, + RESOURCE_TIMER, + RESOURCE_UART_TX, RESOURCE_UART_RX, RESOURCE_UART_TXRX, + RESOURCE_EXTI, + RESOURCE_I2C_SCL, RESOURCE_I2C_SDA, + RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS, + RESOURCE_ADC_BATTERY, RESOURCE_ADC_RSSI, RESOURCE_ADC_EXTERNAL1, RESOURCE_ADC_CURRENT, + RESOURCE_TOTAL_COUNT } resourceType_t; +extern const char * const resourceNames[RESOURCE_TOTAL_COUNT]; diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index d5ac385e42..722715fc16 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_SYSTEM, RESOURCE_SPI); + IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0); 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); + IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0); IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); #endif } @@ -547,10 +547,10 @@ void sdcard_init(bool useDMA) #ifdef SDCARD_SPI_CS_PIN sdCardCsPin = IOGetByTag(IO_TAG(SDCARD_SPI_CS_PIN)); - IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI); + 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 da2c032681..e44ff10a33 100644 --- a/src/main/drivers/serial_softserial.c +++ b/src/main/drivers/serial_softserial.c @@ -100,19 +100,20 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state) } } -static void softSerialGPIOConfig(ioTag_t pin, ioConfig_t mode) +void serialInputPortConfig(ioTag_t pin, uint8_t portIndex) { - IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL_RXTX, RESOURCE_USART); - IOConfigGPIO(IOGetByTag(pin), mode); + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex)); +#ifdef STM32F1 + IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU); +#else + IOConfigGPIO(IOGetByTag(pin), IOCFG_AF_PP_UP); +#endif } -void serialInputPortConfig(ioTag_t pin) +static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex) { -#ifdef STM32F1 - softSerialGPIOConfig(pin, IOCFG_IPU); -#else - softSerialGPIOConfig(pin, IOCFG_AF_PP_UP); -#endif + IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex)); + IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP); } static bool isTimerPeriodTooLarge(uint32_t timerPeriod) @@ -164,11 +165,6 @@ static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t timerChConfigCallbacks(timerHardwarePtr, &softSerialPorts[reference].edgeCb, NULL); } -static void serialOutputPortConfig(ioTag_t pin) -{ - softSerialGPIOConfig(pin, IOCFG_OUT_PP); -} - static void resetBuffers(softSerial_t *softSerial) { softSerial->port.rxBufferSize = SOFTSERIAL_BUFFER_SIZE; @@ -219,10 +215,10 @@ serialPort_t *openSoftSerial(softSerialPortIndex_e portIndex, serialReceiveCallb softSerial->softSerialPortIndex = portIndex; softSerial->txIO = IOGetByTag(softSerial->txTimerHardware->tag); - serialOutputPortConfig(softSerial->txTimerHardware->tag); - + serialOutputPortConfig(softSerial->txTimerHardware->tag, portIndex); + softSerial->rxIO = IOGetByTag(softSerial->rxTimerHardware->tag); - serialInputPortConfig(softSerial->rxTimerHardware->tag); + serialInputPortConfig(softSerial->rxTimerHardware->tag, portIndex); setTxSignal(softSerial, ENABLE); delay(50); @@ -271,8 +267,6 @@ void processTxState(softSerial_t *softSerial) softSerial->isTransmittingData = false; } - - enum { TRAILING, LEADING diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index 8a7999bea5..3bee96b89e 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -99,26 +99,26 @@ serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr callback, uartPort_t *s = NULL; if (USARTx == USART1) { - s = serialUSART1(baudRate, mode, options); -#ifdef USE_USART2 + s = serialUART1(baudRate, mode, options); +#ifdef USE_UART2 } else if (USARTx == USART2) { - s = serialUSART2(baudRate, mode, options); + s = serialUART2(baudRate, mode, options); #endif -#ifdef USE_USART3 +#ifdef USE_UART3 } else if (USARTx == USART3) { - s = serialUSART3(baudRate, mode, options); + s = serialUART3(baudRate, mode, options); #endif -#ifdef USE_USART4 +#ifdef USE_UART4 } else if (USARTx == UART4) { - s = serialUSART4(baudRate, mode, options); + s = serialUART4(baudRate, mode, options); #endif -#ifdef USE_USART5 +#ifdef USE_UART5 } else if (USARTx == UART5) { - s = serialUSART5(baudRate, mode, options); + s = serialUART5(baudRate, mode, options); #endif -#ifdef USE_USART6 +#ifdef USE_UART6 } else if (USARTx == USART6) { - s = serialUSART6(baudRate, mode, options); + s = serialUART6(baudRate, mode, options); #endif } else { diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index 5b0c2b3e08..a4549de344 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -23,10 +23,10 @@ extern const struct serialPortVTable uartVTable[]; void uartStartTxDMA(uartPort_t *s); -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options); -uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options); +uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options); diff --git a/src/main/drivers/serial_uart_stm32f10x.c b/src/main/drivers/serial_uart_stm32f10x.c index 999df9bd5b..4cf886d075 100644 --- a/src/main/drivers/serial_uart_stm32f10x.c +++ b/src/main/drivers/serial_uart_stm32f10x.c @@ -29,34 +29,28 @@ #include #include "system.h" -#include "gpio.h" +#include "io.h" #include "nvic.h" #include "dma.h" +#include "rcc.h" #include "serial.h" #include "serial_uart.h" #include "serial_uart_impl.h" -#ifdef USE_USART1 +#ifdef USE_UART1 static uartPort_t uartPort1; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartPort_t uartPort2; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartPort_t uartPort3; #endif -// Using RX DMA disables the use of receive callbacks -#define USE_USART1_RX_DMA - -#if defined(CC3D) // FIXME move board specific code to target.h files. -#undef USE_USART1_RX_DMA -#endif - -void usartIrqCallback(uartPort_t *s) +void uartIrqCallback(uartPort_t *s) { uint16_t SR = s->USARTx->SR; @@ -83,12 +77,10 @@ void usartIrqCallback(uartPort_t *s) } } -#ifdef USE_USART1 - // USART1 Tx DMA Handler -void USART1_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) +void uart_tx_dma_IRQHandler(dmaChannelDescriptor_t* descriptor) { - uartPort_t *s = &uartPort1; + uartPort_t *s = (uartPort_t*)(descriptor->userParam); DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF); DMA_Cmd(descriptor->channel, DISABLE); @@ -98,64 +90,58 @@ void USART1_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) s->txDMAEmpty = true; } - - +#ifdef USE_UART1 // USART1 - Telemetry (RX/TX by DMA) -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; - gpio_config_t gpio; 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; -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; #endif s->txDMAChannel = DMA1_Channel4; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB2(USART1), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - // USART1_TX PA9 - // USART1_RX PA10 - gpio.speed = Speed_2MHz; - - gpio.pin = Pin_9; + // UART1_TX PA9 + // UART1_RX PA10 if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TXRX, 1); + IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - gpio.mode = Mode_AF_PP; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TX, 1); + IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP); } if (mode & MODE_RX) { - gpio.pin = Pin_10; - gpio.mode = Mode_IPU; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL, RESOURCE_UART_RX, 1); + IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU); } } // DMA TX Interrupt - dmaSetHandler(DMA1_CH4_HANDLER, USART1_DMA_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, 0); + dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1); -#ifndef USE_USART1_RX_DMA +#ifndef USE_UART1_RX_DMA // RX/TX Interrupt NVIC_InitTypeDef NVIC_InitStructure; @@ -169,62 +155,57 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio return s; } - // USART1 Rx/Tx IRQ Handler void USART1_IRQHandler(void) { uartPort_t *s = &uartPort1; - usartIrqCallback(s); + uartIrqCallback(s); } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 // USART2 - GPS or Spektrum or ?? (RX + TX by IRQ) -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; - gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; 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; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB1(USART2), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - // USART2_TX PA2 - // USART2_RX PA3 - gpio.speed = Speed_2MHz; - - gpio.pin = Pin_2; + // UART2_TX PA2 + // UART2_RX PA3 if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TXRX, 2); + IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_OD); } else { if (mode & MODE_TX) { - gpio.mode = Mode_AF_PP; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TX, 2); + IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP); } if (mode & MODE_RX) { - gpio.pin = Pin_3; - gpio.mode = Mode_IPU; - gpioInit(GPIOA, &gpio); + IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2); + IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU); } } @@ -243,19 +224,19 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio void USART2_IRQHandler(void) { uartPort_t *s = &uartPort2; - usartIrqCallback(s); + uartIrqCallback(s); } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 // USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE]; - gpio_config_t gpio; + NVIC_InitTypeDef NVIC_InitStructure; s = &uartPort3; @@ -273,29 +254,20 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; -#ifdef USART3_APB1_PERIPHERALS - RCC_APB1PeriphClockCmd(USART3_APB1_PERIPHERALS, ENABLE); -#endif -#ifdef USART3_APB2_PERIPHERALS - RCC_APB2PeriphClockCmd(USART3_APB2_PERIPHERALS, ENABLE); -#endif + RCC_ClockCmd(RCC_APB1(USART3), ENABLE); - gpio.speed = Speed_2MHz; - - gpio.pin = USART3_TX_PIN; if (options & SERIAL_BIDIR) { - gpio.mode = Mode_AF_OD; - gpioInit(USART3_GPIO, &gpio); + 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) { - gpio.mode = Mode_AF_PP; - gpioInit(USART3_GPIO, &gpio); + 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) { - gpio.pin = USART3_RX_PIN; - gpio.mode = Mode_IPU; - gpioInit(USART3_GPIO, &gpio); + IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3); + IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU); } } @@ -313,6 +285,6 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio void USART3_IRQHandler(void) { uartPort_t *s = &uartPort3; - usartIrqCallback(s); + uartIrqCallback(s); } #endif diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 5883772cf5..f586ee5276 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -30,79 +30,73 @@ #include #include "system.h" -#include "gpio.h" +#include "io.h" #include "nvic.h" #include "dma.h" +#include "rcc.h" #include "serial.h" #include "serial_uart.h" #include "serial_uart_impl.h" -// Using RX DMA disables the use of receive callbacks -//#define USE_USART1_RX_DMA -//#define USE_USART2_RX_DMA -//#define USE_USART2_TX_DMA -//#define USE_USART3_RX_DMA -//#define USE_USART3_TX_DMA - -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#ifdef USE_UART1 +#ifndef UART1_TX_PIN +#define UART1_TX_PIN PA9 // PA9 +#endif +#ifndef UART1_RX_PIN +#define UART1_RX_PIN PA10 // PA10 +#endif #endif -#ifndef UART2_GPIO -#define UART2_TX_PIN GPIO_Pin_5 // PD5 -#define UART2_RX_PIN GPIO_Pin_6 // PD6 -#define UART2_GPIO GPIOD -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource5 -#define UART2_RX_PINSOURCE GPIO_PinSource6 +#ifdef USE_UART2 +#ifndef UART2_TX_PIN +#define UART2_TX_PIN PD5 // PD5 +#endif +#ifndef UART2_RX_PIN +#define UART2_RX_PIN PD6 // PD6 +#endif #endif -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#ifdef USE_UART3 +#ifndef UART3_TX_PIN +#define UART3_TX_PIN PB10 // PB10 (AF7) +#endif +#ifndef UART3_RX_PIN +#define UART3_RX_PIN PB11 // PB11 (AF7) +#endif #endif -#ifndef UART4_GPIO -#define UART4_TX_PIN GPIO_Pin_10 // PC10 (AF5) -#define UART4_RX_PIN GPIO_Pin_11 // PC11 (AF5) -#define UART4_GPIO_AF GPIO_AF_5 -#define UART4_GPIO GPIOC -#define UART4_TX_PINSOURCE GPIO_PinSource10 -#define UART4_RX_PINSOURCE GPIO_PinSource11 +#ifdef USE_UART4 +#ifndef UART4_TX_PIN +#define UART4_TX_PIN PC10 // PC10 (AF5) +#endif +#ifndef UART4_RX_PIN +#define UART4_RX_PIN PC11 // PC11 (AF5) +#endif #endif -#ifndef UART5_GPIO // The real UART5_RX is on PD2, no board is using. -#define UART5_TX_PIN GPIO_Pin_12 // PC12 (AF5) -#define UART5_RX_PIN GPIO_Pin_12 // PC12 (AF5) -#define UART5_GPIO_AF GPIO_AF_5 -#define UART5_GPIO GPIOC -#define UART5_TX_PINSOURCE GPIO_PinSource12 -#define UART5_RX_PINSOURCE GPIO_PinSource12 +#ifdef USE_UART5 +#ifndef UART5_TX_PIN // The real UART5_RX is on PD2, no board is using. +#define UART5_TX_PIN PC12 // PC12 (AF5) +#endif +#ifndef UART5_RX_PIN +#define UART5_RX_PIN PC12 // PC12 (AF5) +#endif #endif -#ifdef USE_USART1 +#ifdef USE_UART1 static uartPort_t uartPort1; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartPort_t uartPort2; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartPort_t uartPort3; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 static uartPort_t uartPort4; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 static uartPort_t uartPort5; #endif @@ -118,25 +112,51 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) s->txDMAEmpty = true; } -#ifdef USE_USART1 -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +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, + (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP + ); + + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, index); + IOConfigGPIOAF(tx, ioCfg, af); + + if (!(options & SERIAL_INVERTED)) + IOLo(tx); // OpenDrain output should be inactive + } else { + ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP); + if (mode & MODE_TX) { + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); + IOConfigGPIOAF(tx, ioCfg, af); + } + + if (mode & MODE_RX) { + IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index); + IOConfigGPIOAF(rx, ioCfg, af); + } + } +} + +#ifdef USE_UART1 +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx1Buffer[UART1_RX_BUFFER_SIZE]; static volatile uint8_t tx1Buffer[UART1_TX_BUFFER_SIZE]; - GPIO_InitTypeDef GPIO_InitStructure; 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_USART1_RX_DMA + +#ifdef USE_UART1_RX_DMA s->rxDMAChannel = DMA1_Channel5; #endif s->txDMAChannel = DMA1_Channel4; @@ -146,39 +166,14 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; - RCC_APB2PeriphClockCmd(RCC_APB2Periph_USART1, ENABLE); - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); + RCC_ClockCmd(RCC_APB2(USART1), ENABLE); + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; + serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1); - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART1_GPIO, UART1_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART1_TX_PIN; - GPIO_PinAFConfig(UART1_GPIO, UART1_TX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - } + dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, &uartPort1); - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART1_RX_PIN; - GPIO_PinAFConfig(UART1_GPIO, UART1_RX_PINSOURCE, UART1_GPIO_AF); - GPIO_Init(UART1_GPIO, &GPIO_InitStructure); - } - } - - dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, 0); - - -#ifndef USE_USART1_RX_DMA +#ifndef USE_UART1_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = USART1_IRQn; @@ -192,73 +187,48 @@ uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART2 -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART2 +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx2Buffer[UART2_RX_BUFFER_SIZE]; static volatile uint8_t tx2Buffer[UART2_TX_BUFFER_SIZE]; - GPIO_InitTypeDef GPIO_InitStructure; 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_USART2_RX_DMA + +#ifdef USE_UART2_RX_DMA s->rxDMAChannel = DMA1_Channel6; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; #endif -#ifdef USE_USART2_TX_DMA +#ifdef USE_UART2_TX_DMA s->txDMAChannel = DMA1_Channel7; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART2, ENABLE); + RCC_ClockCmd(RCC_APB1(USART2), ENABLE); -#if defined(USE_USART2_TX_DMA) || defined(USE_USART2_RX_DMA) - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); +#if defined(USE_UART2_TX_DMA) || defined(USE_UART2_RX_DMA) + RCC_ClockCmd(RCC_AHB(DMA1), ENABLE); #endif - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; + serialUARTInit(IOGetByTag(IO_TAG(UART2_TX_PIN)), IOGetByTag(IO_TAG(UART2_RX_PIN)), mode, options, GPIO_AF_7, 2); - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART2_GPIO, UART2_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART2_TX_PIN; - GPIO_PinAFConfig(UART2_GPIO, UART2_TX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART2_RX_PIN; - GPIO_PinAFConfig(UART2_GPIO, UART2_RX_PINSOURCE, UART2_GPIO_AF); - GPIO_Init(UART2_GPIO, &GPIO_InitStructure); - } - } - -#ifdef USE_USART2_TX_DMA +#ifdef USE_UART2_TX_DMA // DMA TX Interrupt - dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, 0); + dmaSetHandler(DMA1_CH7_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART2_TXDMA, &uartPort2); #endif -#ifndef USE_USART2_RX_DMA +#ifndef USE_UART2_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = USART2_IRQn; @@ -272,13 +242,12 @@ uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART3 +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx3Buffer[UART3_RX_BUFFER_SIZE]; static volatile uint8_t tx3Buffer[UART3_TX_BUFFER_SIZE]; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort3; s->port.vTable = uartVTable; @@ -292,53 +261,29 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = USART3; -#ifdef USE_USART3_RX_DMA +#ifdef USE_UART3_RX_DMA s->rxDMAChannel = DMA1_Channel3; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR; #endif -#ifdef USE_USART3_TX_DMA +#ifdef USE_UART3_TX_DMA s->txDMAChannel = DMA1_Channel2; s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR; #endif - RCC_APB1PeriphClockCmd(RCC_APB1Periph_USART3, ENABLE); + RCC_ClockCmd(RCC_APB1(USART3), ENABLE); -#if defined(USE_USART3_TX_DMA) || defined(USE_USART3_RX_DMA) - RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE); +#if defined(USE_UART3_TX_DMA) || defined(USE_UART3_RX_DMA) + RCC_AHBClockCmd(RCC_AHB(DMA1), ENABLE); #endif - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; + serialUARTInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOGetByTag(IO_TAG(UART3_RX_PIN)), mode, options, GPIO_AF_7, 3); - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART3_GPIO, UART3_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART3_TX_PIN; - GPIO_PinAFConfig(UART3_GPIO, UART3_TX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART3_RX_PIN; - GPIO_PinAFConfig(UART3_GPIO, UART3_RX_PINSOURCE, UART3_GPIO_AF); - GPIO_Init(UART3_GPIO, &GPIO_InitStructure); - } - } - -#ifdef USE_USART3_TX_DMA +#ifdef USE_UART3_TX_DMA // DMA TX Interrupt - dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, 0); + dmaSetHandler(DMA1_CH2_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART3_TXDMA, &uartPort3); #endif -#ifndef USE_USART3_RX_DMA +#ifndef USE_UART3_RX_DMA NVIC_InitTypeDef NVIC_InitStructure; NVIC_InitStructure.NVIC_IRQChannel = USART3_IRQn; @@ -352,14 +297,13 @@ uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART4 -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART4 +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx4Buffer[UART4_RX_BUFFER_SIZE]; static volatile uint8_t tx4Buffer[UART4_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort4; s->port.vTable = uartVTable; @@ -373,33 +317,9 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = UART4; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART4, ENABLE); + RCC_ClockCmd(RCC_APB1(UART4), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART4_GPIO, UART4_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART4_TX_PIN; - GPIO_PinAFConfig(UART4_GPIO, UART4_TX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART4_RX_PIN; - GPIO_PinAFConfig(UART4_GPIO, UART4_RX_PINSOURCE, UART4_GPIO_AF); - GPIO_Init(UART4_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART4_TX_PIN)), IOGetByTag(IO_TAG(UART4_RX_PIN)), mode, options, GPIO_AF_5, 4); NVIC_InitStructure.NVIC_IRQChannel = UART4_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART4); @@ -411,14 +331,13 @@ uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t optio } #endif -#ifdef USE_USART5 -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART5 +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; static volatile uint8_t rx5Buffer[UART5_RX_BUFFER_SIZE]; static volatile uint8_t tx5Buffer[UART5_TX_BUFFER_SIZE]; NVIC_InitTypeDef NVIC_InitStructure; - GPIO_InitTypeDef GPIO_InitStructure; s = &uartPort5; s->port.vTable = uartVTable; @@ -432,33 +351,9 @@ uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t optio s->USARTx = UART5; - RCC_APB1PeriphClockCmd(RCC_APB1Periph_UART5, ENABLE); + RCC_ClockCmd(RCC_APB1(UART5), ENABLE); - GPIO_InitStructure.GPIO_Mode = GPIO_Mode_AF; - GPIO_InitStructure.GPIO_Speed = GPIO_Speed_50MHz; - GPIO_InitStructure.GPIO_OType = GPIO_OType_PP; - GPIO_InitStructure.GPIO_PuPd = (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP; - - if (options & SERIAL_BIDIR) { - GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN; - GPIO_InitStructure.GPIO_OType = (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD; - GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - if(!(options & SERIAL_INVERTED)) - GPIO_SetBits(UART5_GPIO, UART5_TX_PIN); // OpenDrain output should be inactive - } else { - if (mode & MODE_TX) { - GPIO_InitStructure.GPIO_Pin = UART5_TX_PIN; - GPIO_PinAFConfig(UART5_GPIO, UART5_TX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - } - - if (mode & MODE_RX) { - GPIO_InitStructure.GPIO_Pin = UART5_RX_PIN; - GPIO_PinAFConfig(UART5_GPIO, UART5_RX_PINSOURCE, UART5_GPIO_AF); - GPIO_Init(UART5_GPIO, &GPIO_InitStructure); - } - } + serialUARTInit(IOGetByTag(IO_TAG(UART5_TX_PIN)), IOGetByTag(IO_TAG(UART5_RX_PIN)), mode, options, GPIO_AF_5, 5); NVIC_InitStructure.NVIC_IRQChannel = UART5_IRQn; NVIC_InitStructure.NVIC_IRQChannelPreemptionPriority = NVIC_PRIORITY_BASE(NVIC_PRIO_SERIALUART5); @@ -502,7 +397,7 @@ void usartIrqHandler(uartPort_t *s) } } -#ifdef USE_USART1 +#ifdef USE_UART1 void USART1_IRQHandler(void) { uartPort_t *s = &uartPort1; @@ -511,7 +406,7 @@ void USART1_IRQHandler(void) } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 void USART2_IRQHandler(void) { uartPort_t *s = &uartPort2; @@ -520,7 +415,7 @@ void USART2_IRQHandler(void) } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 void USART3_IRQHandler(void) { uartPort_t *s = &uartPort3; @@ -529,7 +424,7 @@ void USART3_IRQHandler(void) } #endif -#ifdef USE_USART4 +#ifdef USE_UART4 void UART4_IRQHandler(void) { uartPort_t *s = &uartPort4; @@ -538,7 +433,7 @@ void UART4_IRQHandler(void) } #endif -#ifdef USE_USART5 +#ifdef USE_UART5 void UART5_IRQHandler(void) { uartPort_t *s = &uartPort5; diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 4d9bf82dbd..91577628b0 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -31,14 +31,6 @@ #include "serial_uart.h" #include "serial_uart_impl.h" -// Using RX DMA disables the use of receive callbacks -//#define USE_USART1_RX_DMA -//#define USE_USART2_RX_DMA -//#define USE_USART3_RX_DMA -//#define USE_USART4_RX_DMA -//#define USE_USART5_RX_DMA -//#define USE_USART6_RX_DMA - #define UART_RX_BUFFER_SIZE UART1_RX_BUFFER_SIZE #define UART_TX_BUFFER_SIZE UART1_TX_BUFFER_SIZE @@ -72,20 +64,20 @@ typedef struct uartDevice_s { } uartDevice_t; //static uartPort_t uartPort[MAX_UARTS]; -#ifdef USE_USART1 +#ifdef USE_UART1 static uartDevice_t uart1 = { .DMAChannel = DMA_Channel_4, .txDMAStream = DMA2_Stream7, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA2_Stream5, #endif .dev = USART1, - .rx = IO_TAG(USART1_RX_PIN), - .tx = IO_TAG(USART1_TX_PIN), + .rx = IO_TAG(UART1_RX_PIN), + .tx = IO_TAG(UART1_TX_PIN), .af = GPIO_AF_USART1, -#ifdef USART1_AHB1_PERIPHERALS - .rcc_ahb1 = USART1_AHB1_PERIPHERALS, +#ifdef UART1_AHB1_PERIPHERALS + .rcc_ahb1 = UART1_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART1), .txIrq = DMA2_ST7_HANDLER, @@ -95,20 +87,20 @@ static uartDevice_t uart1 = }; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 static uartDevice_t uart2 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART2_RX_DMA +#ifdef USE_UART2_RX_DMA .rxDMAStream = DMA1_Stream5, #endif .txDMAStream = DMA1_Stream6, .dev = USART2, - .rx = IO_TAG(USART2_RX_PIN), - .tx = IO_TAG(USART2_TX_PIN), + .rx = IO_TAG(UART2_RX_PIN), + .tx = IO_TAG(UART2_TX_PIN), .af = GPIO_AF_USART2, -#ifdef USART2_AHB1_PERIPHERALS - .rcc_ahb1 = USART2_AHB1_PERIPHERALS, +#ifdef UART2_AHB1_PERIPHERALS + .rcc_ahb1 = UART2_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART2), .txIrq = DMA1_ST6_HANDLER, @@ -118,20 +110,20 @@ static uartDevice_t uart2 = }; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 static uartDevice_t uart3 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART3_RX_DMA +#ifdef USE_UART3_RX_DMA .rxDMAStream = DMA1_Stream1, #endif .txDMAStream = DMA1_Stream3, .dev = USART3, - .rx = IO_TAG(USART3_RX_PIN), - .tx = IO_TAG(USART3_TX_PIN), + .rx = IO_TAG(UART3_RX_PIN), + .tx = IO_TAG(UART3_TX_PIN), .af = GPIO_AF_USART3, -#ifdef USART3_AHB1_PERIPHERALS - .rcc_ahb1 = USART3_AHB1_PERIPHERALS, +#ifdef UART3_AHB1_PERIPHERALS + .rcc_ahb1 = UART3_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(USART3), .txIrq = DMA1_ST3_HANDLER, @@ -141,20 +133,20 @@ static uartDevice_t uart3 = }; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 static uartDevice_t uart4 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream2, #endif .txDMAStream = DMA1_Stream4, .dev = UART4, - .rx = IO_TAG(USART4_RX_PIN), - .tx = IO_TAG(USART4_TX_PIN), + .rx = IO_TAG(UART4_RX_PIN), + .tx = IO_TAG(UART4_TX_PIN), .af = GPIO_AF_UART4, -#ifdef USART4_AHB1_PERIPHERALS - .rcc_ahb1 = USART4_AHB1_PERIPHERALS, +#ifdef UART4_AHB1_PERIPHERALS + .rcc_ahb1 = UART4_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART4), .txIrq = DMA1_ST4_HANDLER, @@ -164,20 +156,20 @@ static uartDevice_t uart4 = }; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 static uartDevice_t uart5 = { .DMAChannel = DMA_Channel_4, -#ifdef USE_USART1_RX_DMA +#ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream0, #endif .txDMAStream = DMA2_Stream7, .dev = UART5, - .rx = IO_TAG(USART5_RX_PIN), - .tx = IO_TAG(USART5_TX_PIN), + .rx = IO_TAG(UART5_RX_PIN), + .tx = IO_TAG(UART5_TX_PIN), .af = GPIO_AF_UART5, -#ifdef USART5_AHB1_PERIPHERALS - .rcc_ahb1 = USART5_AHB1_PERIPHERALS, +#ifdef UART5_AHB1_PERIPHERALS + .rcc_ahb1 = UART5_AHB1_PERIPHERALS, #endif .rcc_apb1 = RCC_APB1(UART5), .txIrq = DMA2_ST7_HANDLER, @@ -187,20 +179,20 @@ static uartDevice_t uart5 = }; #endif -#ifdef USE_USART6 +#ifdef USE_UART6 static uartDevice_t uart6 = { .DMAChannel = DMA_Channel_5, -#ifdef USE_USART6_RX_DMA +#ifdef USE_UART6_RX_DMA .rxDMAStream = DMA2_Stream1, #endif .txDMAStream = DMA2_Stream6, .dev = USART6, - .rx = IO_TAG(USART6_RX_PIN), - .tx = IO_TAG(USART6_TX_PIN), + .rx = IO_TAG(UART6_RX_PIN), + .tx = IO_TAG(UART6_TX_PIN), .af = GPIO_AF_USART6, -#ifdef USART6_AHB1_PERIPHERALS - .rcc_ahb1 = USART6_AHB1_PERIPHERALS, +#ifdef UART6_AHB1_PERIPHERALS + .rcc_ahb1 = UART6_AHB1_PERIPHERALS, #endif .rcc_apb2 = RCC_APB2(USART6), .txIrq = DMA2_ST6_HANDLER, @@ -211,39 +203,39 @@ static uartDevice_t uart6 = #endif static uartDevice_t* uartHardwareMap[] = { -#ifdef USE_USART1 +#ifdef USE_UART1 &uart1, #else NULL, #endif -#ifdef USE_USART2 +#ifdef USE_UART2 &uart2, #else NULL, #endif -#ifdef USE_USART3 +#ifdef USE_UART3 &uart3, #else NULL, #endif -#ifdef USE_USART4 +#ifdef USE_UART4 &uart4, #else NULL, #endif -#ifdef USE_USART5 +#ifdef USE_UART5 &uart5, #else NULL, #endif -#ifdef USE_USART6 +#ifdef USE_UART6 &uart6, #else NULL, #endif }; -void usartIrqHandler(uartPort_t *s) +void uartIrqHandler(uartPort_t *s) { if (!s->rxDMAStream && (USART_GetITStatus(s->USARTx, USART_IT_RXNE) == SET)) { if (s->port.callback) { @@ -302,24 +294,24 @@ void dmaIRQHandler(dmaChannelDescriptor_t* descriptor) } } -uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, portOptions_t options) { uartPort_t *s; NVIC_InitTypeDef NVIC_InitStructure; uartDevice_t *uart = uartHardwareMap[device]; if (!uart) return NULL; - + s = &(uart->port); s->port.vTable = uartVTable; - + s->port.baudRate = baudRate; - + s->port.rxBuffer = uart->rxBuffer; s->port.txBuffer = uart->txBuffer; s->port.rxBufferSize = sizeof(uart->rxBuffer); s->port.txBufferSize = sizeof(uart->txBuffer); - + s->USARTx = uart->dev; if (uart->rxDMAStream) { s->rxDMAChannel = uart->DMAChannel; @@ -327,34 +319,34 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p } s->txDMAChannel = uart->DMAChannel; s->txDMAStream = uart->txDMAStream; - + s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR; - + IO_t tx = IOGetByTag(uart->tx); IO_t rx = IOGetByTag(uart->rx); - + if (uart->rcc_apb2) RCC_ClockCmd(uart->rcc_apb2, ENABLE); - + if (uart->rcc_apb1) RCC_ClockCmd(uart->rcc_apb1, ENABLE); - + if (uart->rcc_ahb1) RCC_AHB1PeriphClockCmd(uart->rcc_ahb1, ENABLE); - + if (options & SERIAL_BIDIR) { - IOInit(tx, OWNER_SERIAL_TX, RESOURCE_USART); + 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_TX, RESOURCE_USART); + 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_RX, RESOURCE_USART); + IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } } @@ -373,86 +365,86 @@ uartPort_t *serialUSART(UARTDevice device, uint32_t baudRate, portMode_t mode, p return s; } -#ifdef USE_USART1 -uartPort_t *serialUSART1(uint32_t baudRate, portMode_t mode, portOptions_t options) +#ifdef USE_UART1 +uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_1, baudRate, mode, options); + return serialUART(UARTDEV_1, baudRate, mode, options); } // USART1 Rx/Tx IRQ Handler void USART1_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART2 +#ifdef USE_UART2 // USART2 - GPS or Spektrum or ?? (RX + TX by IRQ) -uartPort_t *serialUSART2(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_2, baudRate, mode, options); + return serialUART(UARTDEV_2, baudRate, mode, options); } void USART2_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_2]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART3 +#ifdef USE_UART3 // USART3 -uartPort_t *serialUSART3(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_3, baudRate, mode, options); + return serialUART(UARTDEV_3, baudRate, mode, options); } void USART3_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_3]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART4 +#ifdef USE_UART4 // USART4 -uartPort_t *serialUSART4(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART4(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_4, baudRate, mode, options); + return serialUART(UARTDEV_4, baudRate, mode, options); } void UART4_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_4]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART5 +#ifdef USE_UART5 // USART5 -uartPort_t *serialUSART5(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART5(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_5, baudRate, mode, options); + return serialUART(UARTDEV_5, baudRate, mode, options); } void UART5_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_5]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif -#ifdef USE_USART6 +#ifdef USE_UART6 // USART6 -uartPort_t *serialUSART6(uint32_t baudRate, portMode_t mode, portOptions_t options) +uartPort_t *serialUART6(uint32_t baudRate, portMode_t mode, portOptions_t options) { - return serialUSART(UARTDEV_6, baudRate, mode, options); + return serialUART(UARTDEV_6, baudRate, mode, options); } void USART6_IRQHandler(void) { uartPort_t *s = &(uartHardwareMap[UARTDEV_6]->port); - usartIrqHandler(s); + uartIrqHandler(s); } #endif diff --git a/src/main/drivers/serial_usb_vcp.c b/src/main/drivers/serial_usb_vcp.c index bb74b36b3d..5f1b223918 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; } @@ -181,8 +181,8 @@ serialPort_t *usbVcpOpen(void) vcpPort_t *s; #ifdef STM32F4 - IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_IO); - IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_IO); + IOInit(IOGetByTag(IO_TAG(PA11)), OWNER_USB, RESOURCE_INPUT, 0); + IOInit(IOGetByTag(IO_TAG(PA12)), OWNER_USB, RESOURCE_OUTPUT, 0); USBD_Init(&USB_OTG_dev, USB_OTG_FS_CORE_ID, &USR_desc, &USBD_CDC_cb, &USR_cb); #else Set_System(); diff --git a/src/main/drivers/sonar_hcsr04.c b/src/main/drivers/sonar_hcsr04.c index 3b8ec91f7e..cbfcf80a1a 100644 --- a/src/main/drivers/sonar_hcsr04.c +++ b/src/main/drivers/sonar_hcsr04.c @@ -83,12 +83,12 @@ void hcsr04_init(sonarRange_t *sonarRange) // trigger pin triggerIO = IOGetByTag(sonarHardwareHCSR04.triggerTag); - IOInit(triggerIO, OWNER_SONAR, RESOURCE_INPUT); + IOInit(triggerIO, OWNER_SONAR, RESOURCE_OUTPUT, 0); IOConfigGPIO(triggerIO, IOCFG_OUT_PP); - + // echo pin echoIO = IOGetByTag(sonarHardwareHCSR04.echoTag); - IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT); + IOInit(echoIO, OWNER_SONAR, RESOURCE_INPUT, 0); IOConfigGPIO(echoIO, IOCFG_IN_FLOATING); #ifdef USE_EXTI diff --git a/src/main/drivers/sound_beeper.c b/src/main/drivers/sound_beeper.c index cba9a2a5c4..0c60ca4eb4 100644 --- a/src/main/drivers/sound_beeper.c +++ b/src/main/drivers/sound_beeper.c @@ -61,7 +61,7 @@ void beeperInit(const beeperConfig_t *config) beeperInverted = config->isInverted; if (beeperIO) { - IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT); + IOInit(beeperIO, OWNER_BEEPER, RESOURCE_OUTPUT, 0); IOConfigGPIO(beeperIO, config->isOD ? IOCFG_OUT_OD : IOCFG_OUT_PP); } systemBeep(false); diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index 3e59fe7342..c273c6f3dc 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 ee8aef1a0e..d762e2c333 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 53f3767a5e..e7587aa9b3 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/drivers/timer.c b/src/main/drivers/timer.c index e168a46dfe..7938b9a5be 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -374,7 +374,7 @@ void timerChClearCCFlag(const timerHardware_t *timHw) // configure timer channel GPIO mode void timerChConfigGPIO(const timerHardware_t* timHw, ioConfig_t mode) { - IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER); + IOInit(IOGetByTag(timHw->tag), OWNER_TIMER, RESOURCE_TIMER, 0); IOConfigGPIO(IOGetByTag(timHw->tag), mode); } diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index 51ac90ad4f..14a01bcd65 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -36,7 +36,7 @@ static IO_t usbDetectPin = IO_NONE; void usbCableDetectDeinit(void) { #ifdef USB_DETECT_PIN - IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE); + IOInit(usbDetectPin, OWNER_FREE, RESOURCE_NONE, 0); IOConfigGPIO(usbDetectPin, IOCFG_IN_FLOATING); usbDetectPin = IO_NONE; #endif @@ -47,7 +47,7 @@ void usbCableDetectInit(void) #ifdef USB_DETECT_PIN usbDetectPin = IOGetByTag(IO_TAG(USB_DETECT_PIN)); - IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT); + IOInit(usbDetectPin, OWNER_USB, RESOURCE_INPUT, 0); IOConfigGPIO(usbDetectPin, IOCFG_OUT_PP); #endif } diff --git a/src/main/drivers/vtx_soft_spi_rtc6705.c b/src/main/drivers/vtx_soft_spi_rtc6705.c index cdeb23d5b4..6572540c66 100644 --- a/src/main/drivers/vtx_soft_spi_rtc6705.c +++ b/src/main/drivers/vtx_soft_spi_rtc6705.c @@ -53,23 +53,24 @@ static IO_t rtc6705DataPin = IO_NONE; static IO_t rtc6705LePin = IO_NONE; static IO_t rtc6705ClkPin = IO_NONE; -void rtc6705_soft_spi_init(void) { - +void rtc6705_soft_spi_init(void) +{ rtc6705DataPin = IOGetByTag(IO_TAG(RTC6705_SPIDATA_PIN)); rtc6705LePin = IOGetByTag(IO_TAG(RTC6705_SPILE_PIN)); rtc6705ClkPin = IOGetByTag(IO_TAG(RTC6705_SPICLK_PIN)); - IOInit(rtc6705DataPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705DataPin, OWNER_TX, RESOURCE_SPI_MOSI, 0); IOConfigGPIO(rtc6705DataPin, IOCFG_OUT_PP); - IOInit(rtc6705LePin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705LePin, OWNER_TX, RESOURCE_SPI_CS, 0); IOConfigGPIO(rtc6705LePin, IOCFG_OUT_PP); - IOInit(rtc6705ClkPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(rtc6705ClkPin, OWNER_TX, RESOURCE_SPI_SCK, 0); IOConfigGPIO(rtc6705ClkPin, IOCFG_OUT_PP); } -static void rtc6705_write_register(uint8_t addr, uint32_t data) { +static void rtc6705_write_register(uint8_t addr, uint32_t data) +{ uint8_t i; RTC6705_SPILE_OFF; @@ -107,7 +108,8 @@ static void rtc6705_write_register(uint8_t addr, uint32_t data) { } -void rtc6705_soft_spi_set_channel(uint16_t channel_freq) { +void rtc6705_soft_spi_set_channel(uint16_t channel_freq) +{ uint32_t freq = (uint32_t)channel_freq * 1000; uint32_t N, A; @@ -119,7 +121,8 @@ void rtc6705_soft_spi_set_channel(uint16_t channel_freq) { rtc6705_write_register(1, (N << 7) | A); } -void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) { +void rtc6705_soft_spi_set_rf_power(uint8_t reduce_power) +{ rtc6705_write_register(7, (reduce_power ? (PA_CONTROL_DEFAULT | PD_Q5G_MASK) & (~(PA5G_PW_MASK | PA5G_BS_MASK)) : PA_CONTROL_DEFAULT)); } diff --git a/src/main/flight/gtune.c b/src/main/flight/gtune.c index d32a93ad8d..afef499d59 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 d885d30eaa..8945e765e6 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 b5da4a0170..b851fd355e 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(); } @@ -666,9 +666,10 @@ void stopMotors(void) delay(50); // give the timers and ESCs a chance to react. } -void StopPwmAllMotors() +void stopPwmAllMotors() { pwmShutdownPulsesForAllMotors(motorCount); + delayMicroseconds(1500); } #ifndef USE_QUAD_MIXER_ONLY @@ -901,7 +902,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/flight/mixer.h b/src/main/flight/mixer.h index f3999517c7..4f4869b205 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -215,4 +215,4 @@ void mixTable(void); void syncMotors(bool enabled); void writeMotors(void); void stopMotors(void); -void StopPwmAllMotors(void); +void stopPwmAllMotors(void); diff --git a/src/main/io/asyncfatfs/asyncfatfs.c b/src/main/io/asyncfatfs/asyncfatfs.c index 0fc5c23b97..57b8f0c861 100644 --- a/src/main/io/asyncfatfs/asyncfatfs.c +++ b/src/main/io/asyncfatfs/asyncfatfs.c @@ -2912,7 +2912,7 @@ bool afatfs_chdir(afatfsFilePtr_t directory) afatfs_initFileHandle(&afatfs.currentDirectory); afatfs.currentDirectory.mode = AFATFS_FILE_MODE_READ | AFATFS_FILE_MODE_WRITE; - + if (afatfs.filesystemType == FAT_FILESYSTEM_TYPE_FAT16) afatfs.currentDirectory.type = AFATFS_FILE_TYPE_FAT16_ROOT_DIRECTORY; else diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index f1ac9e3520..716cf84b36 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -172,7 +172,7 @@ typedef struct beeperTableEntry_s { { BEEPER_ENTRY(BEEPER_SYSTEM_INIT, 16, NULL, "SYSTEM_INIT") }, { BEEPER_ENTRY(BEEPER_USB, 17, NULL, "ON_USB") }, - { BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") }, + { BEEPER_ENTRY(BEEPER_ALL, 18, NULL, "ALL") }, { BEEPER_ENTRY(BEEPER_PREFERENCE, 19, NULL, "PREFERRED") }, }; @@ -308,7 +308,7 @@ void beeperUpdate(void) if (!beeperIsOn) { beeperIsOn = 1; if (currentBeeperEntry->sequence[beeperPos] != 0) { - if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1)))) + if (!(getBeeperOffMask() & (1 << (currentBeeperEntry->mode - 1)))) BEEP_ON; warningLedEnable(); warningLedRefresh(); diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 0f9f488ef6..b4ed924130 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -29,7 +29,7 @@ typedef enum { BEEPER_ARMING_GPS_FIX, // Beep a special tone when arming the board and GPS has fix BEEPER_BAT_CRIT_LOW, // Longer warning beeps when battery is critically low (repeats) BEEPER_BAT_LOW, // Warning beeps when battery is getting low (repeats) - BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB **** + BEEPER_GPS_STATUS, // FIXME **** Disable beeper when connected to USB **** BEEPER_RX_SET, // Beeps when aux channel is set for beep or beep sequence how many satellites has found if GPS enabled BEEPER_DISARM_REPEAT, // Beeps sounded while stick held in disarm position BEEPER_ACC_CALIBRATION, // ACC inflight calibration completed confirmation @@ -40,7 +40,7 @@ typedef enum { BEEPER_SYSTEM_INIT, // Initialisation beeps when board is powered on BEEPER_USB, // Some boards have beeper powered USB connected - BEEPER_ALL, // Turn ON or OFF all beeper conditions + BEEPER_ALL, // Turn ON or OFF all beeper conditions BEEPER_PREFERENCE, // Save prefered beeper configuration // BEEPER_ALL and BEEPER_PREFERENCE must remain at the bottom of this enum } beeperMode_e; diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 3c71c48be8..3006d09114 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -239,7 +239,7 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) // only RX is needed for NMEA-style GPS #if !defined(COLIBRI_RACE) || !defined(LUX_RACE) if (gpsConfig->provider == GPS_NMEA) - mode &= ~MODE_TX; + mode &= ~MODE_TX; #endif // no callback - buffer will be consumed in gpsThread() @@ -256,47 +256,47 @@ void gpsInit(serialConfig_t *initialSerialConfig, gpsConfig_t *initialGpsConfig) void gpsInitNmea(void) { #if defined(COLIBRI_RACE) || defined(LUX_RACE) - uint32_t now; + uint32_t now; #endif switch(gpsData.state) { case GPS_INITIALIZING: #if defined(COLIBRI_RACE) || defined(LUX_RACE) - now = millis(); - if (now - gpsData.state_ts < 1000) - return; - gpsData.state_ts = now; - if (gpsData.state_position < 1) { - serialSetBaudRate(gpsPort, 4800); - gpsData.state_position++; - } else if (gpsData.state_position < 2) { - // print our FIXED init string for the baudrate we want to be at - serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n"); - gpsData.state_position++; - } else { - // we're now (hopefully) at the correct rate, next state will switch to it - gpsSetState(GPS_CHANGE_BAUD); - } - break; + now = millis(); + if (now - gpsData.state_ts < 1000) + return; + gpsData.state_ts = now; + if (gpsData.state_position < 1) { + serialSetBaudRate(gpsPort, 4800); + gpsData.state_position++; + } else if (gpsData.state_position < 2) { + // print our FIXED init string for the baudrate we want to be at + serialPrint(gpsPort, "$PSRF100,1,115200,8,1,0*05\r\n"); + gpsData.state_position++; + } else { + // we're now (hopefully) at the correct rate, next state will switch to it + gpsSetState(GPS_CHANGE_BAUD); + } + break; #endif case GPS_CHANGE_BAUD: #if defined(COLIBRI_RACE) || defined(LUX_RACE) - now = millis(); - if (now - gpsData.state_ts < 1000) - return; - gpsData.state_ts = now; - if (gpsData.state_position < 1) { - serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); - gpsData.state_position++; - } else if (gpsData.state_position < 2) { - serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n"); - gpsData.state_position++; - } else { + now = millis(); + if (now - gpsData.state_ts < 1000) + return; + gpsData.state_ts = now; + if (gpsData.state_position < 1) { + serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); + gpsData.state_position++; + } else if (gpsData.state_position < 2) { + serialPrint(gpsPort, "$PSRF103,00,6,00,0*23\r\n"); + gpsData.state_position++; + } else { #else serialSetBaudRate(gpsPort, baudRates[gpsInitData[gpsData.baudrateIndex].baudrateIndex]); #endif gpsSetState(GPS_RECEIVING_DATA); #if defined(COLIBRI_RACE) || defined(LUX_RACE) - } + } #endif break; } @@ -1066,7 +1066,7 @@ static void gpsHandlePassthrough(uint8_t data) updateDisplay(); } #endif - + } @@ -1083,7 +1083,7 @@ void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) displayShowFixedPage(PAGE_GPS); } #endif - + serialPassthrough(gpsPort, gpsPassthroughPort, &gpsHandlePassthrough, NULL); } diff --git a/src/main/io/ledstrip.c b/src/main/io/ledstrip.c index 863f3a8b6b..e74ca001a0 100644 --- a/src/main/io/ledstrip.c +++ b/src/main/io/ledstrip.c @@ -273,16 +273,16 @@ const ledConfig_t defaultLedStripConfig[] = { }; #elif defined(USE_COLIBTI_RACE_LED_DEFAULT_CONFIG) const ledConfig_t defaultLedStripConfig[] = { - { CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, - { CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 0), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 1), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 0, 8), 6, LED_DIRECTION_WEST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 7, 15), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 8, 15), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 7, 14), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 8, 14), 6, LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 8), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 1), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, + { CALCULATE_LED_XY( 15, 0), 6, LED_DIRECTION_EAST | LED_FUNCTION_WARNING | LED_FUNCTION_COLOR }, }; #else const ledConfig_t defaultLedStripConfig[] = { @@ -370,8 +370,8 @@ static const uint16_t functionMappings[FUNCTION_COUNT] = { LED_FUNCTION_FLIGHT_MODE, LED_FUNCTION_ARM_STATE, LED_FUNCTION_THROTTLE, - LED_FUNCTION_THRUST_RING, - LED_FUNCTION_COLOR + LED_FUNCTION_THRUST_RING, + LED_FUNCTION_COLOR }; // grid offsets @@ -938,7 +938,7 @@ static void applyLedAnimationLayer(void) void updateLedStrip(void) { - if (!(ledStripInitialised && isWS2811LedStripReady())) { + if (!(ledStripInitialised && isWS2811LedStripReady())) { return; } @@ -950,11 +950,11 @@ void updateLedStrip(void) } else { ledStripEnabled = true; } - + if (!ledStripEnabled){ return; } - + uint32_t now = micros(); @@ -1115,8 +1115,8 @@ void ledStripEnable(void) static void ledStripDisable(void) { - setStripColor(&hsv_black); - - ws2811UpdateStrip(); + setStripColor(&hsv_black); + + ws2811UpdateStrip(); } #endif diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index fdea810034..68896a9a89 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -328,12 +328,12 @@ bool isModeActivationConditionPresent(modeActivationCondition_t *modeActivationC for (index = 0; index < MAX_MODE_ACTIVATION_CONDITION_COUNT; index++) { modeActivationCondition_t *modeActivationCondition = &modeActivationConditions[index]; - + if (modeActivationCondition->modeId == modeId && IS_RANGE_USABLE(&modeActivationCondition->range)) { return true; } } - + return false; } @@ -607,7 +607,7 @@ void applySelectAdjustment(uint8_t adjustmentFunction, uint8_t position) switch(adjustmentFunction) { case ADJUSTMENT_RATE_PROFILE: if (getCurrentControlRateProfile() != position) { - changeControlRateProfile(position); + changeControlRateProfile(position); blackboxLogInflightAdjustmentEvent(ADJUSTMENT_RATE_PROFILE, position); applied = true; } diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 6fbdad7c0c..be6372b479 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -32,7 +32,7 @@ #include "drivers/serial_softserial.h" #endif -#if defined(USE_USART1) || defined(USE_USART2) || defined(USE_USART3) || defined(USE_USART4) || defined(USE_USART5) || defined(USE_USART6) +#if defined(USE_UART1) || defined(USE_UART2) || defined(USE_UART3) || defined(USE_UART4) || defined(USE_UART5) || defined(USE_UART6) #include "drivers/serial_uart.h" #endif @@ -60,22 +60,22 @@ const serialPortIdentifier_e serialPortIdentifiers[SERIAL_PORT_COUNT] = { #ifdef USE_VCP SERIAL_PORT_USB_VCP, #endif -#ifdef USE_USART1 +#ifdef USE_UART1 SERIAL_PORT_USART1, #endif -#ifdef USE_USART2 +#ifdef USE_UART2 SERIAL_PORT_USART2, #endif -#ifdef USE_USART3 +#ifdef USE_UART3 SERIAL_PORT_USART3, #endif -#ifdef USE_USART4 +#ifdef USE_UART4 SERIAL_PORT_USART4, #endif -#ifdef USE_USART5 +#ifdef USE_UART5 SERIAL_PORT_USART5, #endif -#ifdef USE_USART6 +#ifdef USE_UART6 SERIAL_PORT_USART6, #endif #ifdef USE_SOFTSERIAL1 @@ -273,7 +273,7 @@ serialPort_t *openSerialPort( portMode_t mode, portOptions_t options) { -#if (!defined(USE_VCP) && !defined(USE_USART1) && !defined(USE_USART2) && !defined(USE_USART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) +#if (!defined(USE_VCP) && !defined(USE_UART1) && !defined(USE_UART2) && !defined(USE_UART3) && !defined(USE_SOFTSERIAL1) && !defined(USE_SOFTSERIAL1)) UNUSED(callback); UNUSED(baudRate); UNUSED(mode); @@ -294,32 +294,32 @@ serialPort_t *openSerialPort( serialPort = usbVcpOpen(); break; #endif -#ifdef USE_USART1 +#ifdef USE_UART1 case SERIAL_PORT_USART1: serialPort = uartOpen(USART1, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART2 +#ifdef USE_UART2 case SERIAL_PORT_USART2: serialPort = uartOpen(USART2, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART3 +#ifdef USE_UART3 case SERIAL_PORT_USART3: serialPort = uartOpen(USART3, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART4 +#ifdef USE_UART4 case SERIAL_PORT_USART4: serialPort = uartOpen(UART4, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART5 +#ifdef USE_UART5 case SERIAL_PORT_USART5: serialPort = uartOpen(UART5, callback, baudRate, mode, options); break; #endif -#ifdef USE_USART6 +#ifdef USE_UART6 case SERIAL_PORT_USART6: serialPort = uartOpen(USART6, callback, baudRate, mode, options); break; diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index bcea2f8a1e..7b783422fa 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -380,7 +380,7 @@ void esc4wayProcess(serialPort_t *serial) writeByte(crcOut >> 8); writeByte(crcOut & 0xff); serialEndWrite(port); - + #ifdef STM32F4 delay(50); #endif diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c index 872e8dce7d..9c81c89317 100644 --- a/src/main/io/serial_4way_stk500v2.c +++ b/src/main/io/serial_4way_stk500v2.c @@ -89,7 +89,7 @@ static uint8_t ckSumOut; static void StkSendByte(uint8_t dat) { ckSumOut ^= dat; - for (uint8_t i = 0; i < 8; i++) { + for (uint8_t i = 0; i < 8; i++) { if (dat & 0x01) { // 1-bits are encoded as 64.0us high, 72.8us low (135.8us total). ESC_SET_HI; @@ -248,9 +248,9 @@ static uint8_t _CMD_SPI_MULTI_EX(uint8_t * resByte, uint8_t subcmd, uint16_t add StkSendByte(4); // NumTX StkSendByte(4); // NumRX StkSendByte(0); // RxStartAdr - StkSendByte(subcmd); // {TxData} Cmd + StkSendByte(subcmd); // {TxData} Cmd StkSendByte(addr >> 8); // {TxData} AdrHi - StkSendByte(addr & 0xff); // {TxData} AdrLow + StkSendByte(addr & 0xff); // {TxData} AdrLow StkSendByte(0); // {TxData} 0 StkSendPacketFooter(); if (StkRcvPacket(stkInBuf, sizeof(stkInBuf))) { // NumRX + 3 diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index e160869df0..c0f3a8c417 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -1983,7 +1983,7 @@ static void cliDump(char *cmdline) cliPrintf("%s\r\n", ftoa(yaw, buf)); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } #ifdef USE_SERVOS @@ -2008,7 +2008,7 @@ static void cliDump(char *cmdline) #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } #endif @@ -2023,7 +2023,7 @@ static void cliDump(char *cmdline) cliPrintf("feature -%s\r\n", featureNames[i]); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } for (i = 0; ; i++) { // reenable what we want. if (featureNames[i] == NULL) @@ -2032,7 +2032,7 @@ static void cliDump(char *cmdline) cliPrintf("feature %s\r\n", featureNames[i]); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } @@ -2094,7 +2094,7 @@ static void cliDump(char *cmdline) cliPrintf("smix reverse %d %d r\r\n", i , channel); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } } } @@ -2111,7 +2111,7 @@ static void cliDump(char *cmdline) cliPrint("\r\n# rxfail\r\n"); cliRxFail(""); - + if (dumpMask & DUMP_ALL) { uint8_t activeProfile = masterConfig.current_profile_index; uint8_t profileCount; @@ -2129,7 +2129,7 @@ static void cliDump(char *cmdline) cliRateProfile(""); #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } cliPrint("\r\n# restore original profile selection\r\n"); @@ -2158,7 +2158,7 @@ void cliDumpProfile(uint8_t profileIndex) { if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values return; - + changeProfile(profileIndex); cliPrint("\r\n# profile\r\n"); cliProfile(""); @@ -2174,7 +2174,7 @@ void cliDumpRateProfile(uint8_t rateProfileIndex) { if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values return; - + changeControlRateProfile(rateProfileIndex); cliPrint("\r\n# rateprofile\r\n"); cliRateProfile(""); @@ -2551,7 +2551,7 @@ static void cliProfile(char *cmdline) static void cliRateProfile(char *cmdline) { int i; - + if (isEmpty(cmdline)) { cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile()); return; @@ -2566,18 +2566,18 @@ static void cliRateProfile(char *cmdline) { static void cliReboot(void) { - cliRebootEx(false); + cliRebootEx(false); } static void cliRebootEx(bool bootLoader) { - cliPrint("\r\nRebooting"); + cliPrint("\r\nRebooting"); bufWriterFlush(cliWriter); waitForSerialPortToFinishTransmitting(cliPort); - stopMotors(); + stopPwmAllMotors(); if (bootLoader) { - systemResetToBootloader(); - return; + systemResetToBootloader(); + return; } systemReset(); } @@ -2749,10 +2749,10 @@ static void cliSet(char *cmdline) cliPrintf("%s = ", valueTable[i].name); cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui cliPrint("\r\n"); - + #ifdef USE_SLOW_SERIAL_CLI delay(2); -#endif +#endif } } else if ((eqptr = strstr(cmdline, "=")) != NULL) { // has equals @@ -3074,55 +3074,30 @@ void cliProcess(void) } } -const char * const ownerNames[OWNER_TOTAL_COUNT] = { - "FREE", - "PWM IN", - "PPM IN", - "MOTOR", - "SERVO", - "SOFTSERIAL RX", - "SOFTSERIAL TX", - "SOFTSERIAL RXTX", // bidirectional pin for softserial - "SOFTSERIAL AUXTIMER", // timer channel is used for softserial. No IO function on pin - "ADC", - "SERIAL RX", - "SERIAL TX", - "SERIAL RXTX", - "PINDEBUG", - "TIMER", - "SONAR", - "SYSTEM", - "SDCARD", - "FLASH", - "USB", - "BEEPER", - "OSD", - "BARO", -}; - static void cliResource(char *cmdline) { UNUSED(cmdline); - cliPrintf("IO:\r\n"); + cliPrintf("IO:\r\n----------------------\r\n"); for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) { const char* owner; - char buff[15]; - if (ioRecs[i].owner < ARRAYLEN(ownerNames)) { - owner = ownerNames[ioRecs[i].owner]; + owner = ownerNames[ioRecs[i].owner]; + + const char* resource; + resource = resourceNames[ioRecs[i].resource]; + + if (ioRecs[i].index > 0) { + cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource); + } else { + cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource); } - else { - sprintf(buff, "O=%d", ioRecs[i].owner); - owner = buff; - } - cliPrintf("%c%02d: %19s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner); } } void cliDfu(char *cmdLine) { - UNUSED(cmdLine); - cliPrint("\r\nRestarting in DFU mode"); - cliRebootEx(true); + UNUSED(cmdLine); + cliPrint("\r\nRestarting in DFU mode"); + cliRebootEx(true); } void cliInit(serialConfig_t *serialConfig) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 4eb59402c8..48d6ae92e8 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -293,7 +293,7 @@ static uint32_t read32(void) static void headSerialResponse(uint8_t err, uint8_t responseBodySize) { serialBeginWrite(mspSerialPort); - + serialize8('$'); serialize8('M'); serialize8(err ? '!' : '>'); @@ -1967,7 +1967,7 @@ void mspProcess(void) if (isRebootScheduled) { waitForSerialPortToFinishTransmitting(candidatePort->port); - stopMotors(); + stopPwmAllMotors(); // On real flight controllers, systemReset() will do a soft reset of the device, // reloading the program. But to support offline testing this flag needs to be // cleared so that the software doesn't continuously attempt to reboot itself. diff --git a/src/main/io/vtx.c b/src/main/io/vtx.c index cfccf5c5d1..15a3de3347 100644 --- a/src/main/io/vtx.c +++ b/src/main/io/vtx.c @@ -76,7 +76,7 @@ static uint8_t locked = 0; void vtxInit(void) { - rtc6705Init(); + rtc6705Init(); if (masterConfig.vtx_mode == 0) { rtc6705SetChannel(masterConfig.vtx_band, masterConfig.vtx_channel); } else if (masterConfig.vtx_mode == 1) { diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index d49c2c7078..942a770547 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -17,11 +17,11 @@ #pragma once -#define VTX_BAND_MIN 1 -#define VTX_BAND_MAX 5 -#define VTX_CHANNEL_MIN 1 -#define VTX_CHANNEL_MAX 8 -#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 +#define VTX_BAND_MIN 1 +#define VTX_BAND_MAX 5 +#define VTX_CHANNEL_MIN 1 +#define VTX_CHANNEL_MAX 8 +#define MAX_CHANNEL_ACTIVATION_CONDITION_COUNT 10 typedef struct vtxChannelActivationCondition_s { uint8_t auxChannelIndex; diff --git a/src/main/main.c b/src/main/main.c index 1d94e96575..a411117617 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 @@ -275,18 +275,18 @@ void init(void) pwm_params.airplane = true; else pwm_params.airplane = false; -#if defined(USE_USART2) && defined(STM32F10X) +#if defined(USE_UART2) && defined(STM32F10X) pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2); #endif #ifdef STM32F303xC pwm_params.useUART3 = doesConfigurationUsePort(SERIAL_PORT_USART3); #endif -#if defined(USE_USART2) && defined(STM32F40_41xxx) +#if defined(USE_UART2) && defined(STM32F40_41xxx) pwm_params.useUART2 = doesConfigurationUsePort(SERIAL_PORT_USART2); #endif -#if defined(USE_USART6) && defined(STM32F40_41xxx) +#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 @@ -335,12 +335,6 @@ void init(void) mixerUsePWMOutputConfiguration(pwmOutputConfiguration, use_unsyncedPwm); -/* - // TODO is this needed here? enables at the end - if (!feature(FEATURE_ONESHOT125)) - motorControlEnable = true; - -*/ systemState |= SYSTEM_STATE_MOTORS_READY; #ifdef BEEPER @@ -363,7 +357,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 +495,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 255fb547ea..50fe4f4578 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 9c0f211028..fb211bfcf7 100644 --- a/src/main/rx/spektrum.c +++ b/src/main/rx/spektrum.c @@ -184,7 +184,7 @@ bool spekShouldBind(uint8_t spektrum_sat_bind) { #ifdef HARDWARE_BIND_PLUG BindPlug = IOGetByTag(IO_TAG(BINDPLUG_PIN)); - IOInit(BindPlug, OWNER_SYSTEM, RESOURCE_INPUT); + IOInit(BindPlug, OWNER_RX, RESOURCE_INPUT, 0); IOConfigGPIO(BindPlug, IOCFG_IPU); // Check status of bind plug and exit if not active @@ -216,7 +216,7 @@ void spektrumBind(rxConfig_t *rxConfig) LED1_ON; BindPin = IOGetByTag(IO_TAG(BIND_PIN)); - IOInit(BindPin, OWNER_SYSTEM, RESOURCE_OUTPUT); + IOInit(BindPin, OWNER_RX, RESOURCE_OUTPUT, 0); IOConfigGPIO(BindPin, IOCFG_OUT_PP); // RX line, set high @@ -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 ba70eb579b..0e68854897 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 7fe3fea8ec..cff97d77e4 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 1793e37948..2d7b44e551 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 @@ -117,7 +117,7 @@ typedef enum { bool isBaroReady(void) { - return baroReady; + return baroReady; } uint32_t baroUpdate(void) diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 23159d87cd..c6e3be93ca 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) { @@ -213,7 +213,7 @@ void updateCurrentMeter(int32_t lastUpdateAt, rxConfig_t *rxConfig, uint16_t dea } fix12_t calculateVbatPidCompensation(void) { - fix12_t batteryScaler; + fix12_t batteryScaler; if (batteryConfig->vbatPidCompensation && feature(FEATURE_VBAT) && batteryCellCount > 1) { uint16_t maxCalculatedVoltage = batteryConfig->vbatmaxcellvoltage * batteryCellCount; batteryScaler = qConstruct(maxCalculatedVoltage, constrain(vbat, maxCalculatedVoltage - batteryConfig->vbatmaxcellvoltage, maxCalculatedVoltage)); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 0e75ad15f5..eb206627b4 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 @@ -418,20 +418,20 @@ static void detectBaro(baroSensor_e baroHardwareToUse) #ifdef USE_BARO_BMP085 - const bmp085Config_t *bmp085Config = NULL; + const bmp085Config_t *bmp085Config = NULL; #if defined(BARO_XCLR_GPIO) && defined(BARO_EOC_GPIO) - static const bmp085Config_t defaultBMP085Config = { - .xclrIO = IO_TAG(BARO_XCLR_PIN), - .eocIO = IO_TAG(BARO_EOC_PIN), - }; - bmp085Config = &defaultBMP085Config; + static const bmp085Config_t defaultBMP085Config = { + .xclrIO = IO_TAG(BARO_XCLR_PIN), + .eocIO = IO_TAG(BARO_EOC_PIN), + }; + bmp085Config = &defaultBMP085Config; #endif #ifdef NAZE - if (hardwareRevision == NAZE32) { - bmp085Disable(bmp085Config); - } + if (hardwareRevision == NAZE32) { + bmp085Disable(bmp085Config); + } #endif #endif @@ -455,7 +455,7 @@ static void detectBaro(baroSensor_e baroHardwareToUse) break; } #endif - ; // fallthough + ; // fallthough case BARO_BMP280: #ifdef USE_BARO_BMP280 if (bmp280Detect(&baro)) { @@ -503,7 +503,7 @@ static void detectMag(magSensor_e magHardwareToUse) .intTag = IO_TAG(MAG_INT_EXTI) }; - hmc5883Config = &extiHmc5883Config; + hmc5883Config = &extiHmc5883Config; #endif #endif diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c index b51d38658f..a8f1ebdb7e 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.c +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c @@ -40,7 +40,7 @@ static IO_t HWDetectPin = IO_NONE; void detectHardwareRevision(void) { HWDetectPin = IOGetByTag(IO_TAG(HW_PIN)); - IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT); + IOInit(HWDetectPin, OWNER_SYSTEM, RESOURCE_INPUT, 0); IOConfigGPIO(HWDetectPin, IOCFG_IPU); // Check hardware revision diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 57fc417638..2ced9687ac 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -84,7 +84,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // USART3 RX/TX // RX conflicts with PPM port - //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, USART3_RX (AF7) - PWM11 - //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, USART3_TX (AF7) - PWM12 + //{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource11, GPIO_AF_1 } // RX - PB11 - *TIM2_CH4, UART3_RX (AF7) - PWM11 + //{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_PinSource10, GPIO_AF_1 } // TX - PB10 - *TIM2_CH3, UART3_TX (AF7) - PWM12 }; diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 1df1d3c4fd..b05cdb33a4 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -69,32 +69,19 @@ #define MAG_AK8963_ALIGN CW0_DEG_FLIP #define USE_VCP -#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7) -#define USE_USART2 // Receiver - RX (PA3) -#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10) +#define USE_UART1 // Not connected - TX (PB6) RX PB7 (AF7) +#define USE_UART2 // Receiver - RX (PA3) +#define USE_UART3 // Not connected - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_2 // PA2 -#define UART2_RX_PIN GPIO_Pin_3 // PA3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 - -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART2_TX_PIN PA2 // PA2 +#define UART2_RX_PIN PA3 // PA3 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 54983b3d2e..909026c021 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -97,26 +97,26 @@ #define USE_VCP -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART2 -#define USART2_RX_PIN PA3 -#define USART2_TX_PIN PA2 //inverter +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 //inverter -//#define USE_USART3 -//#define USART3_RX_PIN PB11 -//#define USART3_TX_PIN PB10 +//#define USE_UART3 +//#define UART3_RX_PIN PB11 +//#define UART3_TX_PIN PB10 -#define USE_USART4 -#define USART4_RX_PIN PC10 -#define USART4_TX_PIN PC11 +#define USE_UART4 +#define UART4_RX_PIN PC10 +#define UART4_TX_PIN PC11 -//#define USE_USART5 -//#define USART5_RX_PIN PD2 -//#define USART5_TX_PIN PC12 +//#define USE_UART5 +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 8d9d1c633a..e83499615a 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -94,21 +94,27 @@ #define USE_VCP //#define VBUS_SENSING_PIN PA8 //#define VBUS_SENSING_ENABLED - -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define USE_SOFTSERIAL1 +#define SERIAL_PORT_COUNT 5 + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SERIAL_PORT_COUNT 4 #define USE_ESCSERIAL #define ESCSERIAL_TIMER_TX_HARDWARE 0 @@ -160,3 +166,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9)) + diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 5e6c1b8ad0..a1425bc538 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -69,20 +69,21 @@ #define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART3 +#define USE_UART1 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 4 +#ifdef USE_UART1_RX_DMA +#undef USE_UART1_RX_DMA +#endif + #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 -#define USART3_RX_PIN Pin_11 -#define USART3_TX_PIN Pin_10 -#define USART3_GPIO GPIOB -#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 -#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_SPI #define USE_SPI_DEVICE_1 diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 5e7f79ce05..52bea95ba2 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -55,7 +55,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -93,8 +93,8 @@ #define MAG_AK8975_ALIGN CW90_DEG_FLIP #define USE_VCP -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 3 #define USE_I2C @@ -111,7 +111,7 @@ #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTD (BIT(2)|BIT(5)|BIT(6)|BIT(10)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTE 0xffff #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)|BIT(9)|BIT(10)) diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index d92a591ab8..d84e98eae1 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -35,8 +35,8 @@ #define BRUSHED_MOTORS -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 2 diff --git a/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c b/src/main/target/COLIBRI_RACE/bus_bst_stm32f30x.c index f23932a6e6..655f19cfe6 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/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 0492926e55..65ab62d5d6 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -32,11 +32,6 @@ #define BEEPER_INVERTED #define USE_EXTI -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 - -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 #define USE_SPI #define USE_SPI_DEVICE_1 @@ -44,6 +39,13 @@ #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 +#define SPI1_NSS_PIN PA4 + +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 + +#define MPU6000_CS_PIN SPI1_NSS_PIN +#define MPU6000_SPI_INSTANCE SPI1 #define USABLE_TIMER_CHANNEL_COUNT 11 @@ -75,31 +77,19 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_4 -#define UART1_RX_PIN GPIO_Pin_5 -#define UART1_GPIO GPIOC -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource4 -#define UART1_RX_PINSOURCE GPIO_PinSource5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN GPIO_Pin_14 -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index c07a925414..c813ceecba 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/DOGE/target.h b/src/main/target/DOGE/target.h index 7ca509ea28..e4c2f76ba0 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -33,14 +33,6 @@ #define BEEPER PB2 #define BEEPER_INVERTED -// tqfp48 pin 3 -#define MPU6500_CS_PIN PC14 -#define MPU6500_SPI_INSTANCE SPI1 - -// tqfp48 pin 25 -#define BMP280_CS_PIN PB12 -#define BMP280_SPI_INSTANCE SPI2 - #define USE_SPI #define USE_SPI_DEVICE_1 #define USE_SPI_DEVICE_2 @@ -51,18 +43,31 @@ #define SPI1_MISO_PIN PB4 // tqfp48 pin 41 #define SPI1_MOSI_PIN PB5 +// tqfp48 pin 3 +#define SPI1_NSS_PIN PC14 + // tqfp48 pin 26 #define SPI2_SCK_PIN PB13 // tqfp48 pin 27 #define SPI2_MISO_PIN PB14 // tqfp48 pin 28 #define SPI2_MOSI_PIN PB15 +// tqfp48 pin 25 +#define SPI2_NSS_PIN PB12 + +// tqfp48 pin 3 +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 + +// tqfp48 pin 25 +#define BMP280_CS_PIN SPI2_NSS_PIN +#define BMP280_SPI_INSTANCE SPI2 #define USE_FLASHFS #define USE_FLASH_M25P16 #define M25P16_SPI_SHARED -#define M25P16_CS_PIN PC15 -#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_CS_PIN PC15 +#define M25P16_SPI_INSTANCE SPI2 // timer definitions in drivers/timer.c // channel mapping in drivers/pwm_mapping.c @@ -90,37 +95,19 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -// tqfp48 pin 42 -#define UART1_TX_PIN GPIO_Pin_6 -// tqfp48 pin 43 -#define UART1_RX_PIN GPIO_Pin_7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -// tqfp48 pin 12 -#define UART2_TX_PIN GPIO_Pin_2 -// tqfp48 pin 13 -#define UART2_RX_PIN GPIO_Pin_3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 -// tqfp48 pin 21 -#define UART3_TX_PIN GPIO_Pin_10 -// tqfp48 pin 22 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index 0869dd46b1..ee893670dd 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -76,8 +76,8 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index e52da0ab27..21b05ab5d4 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/FURYF3/target.h b/src/main/target/FURYF3/target.h index db4ddd7457..e67a920cc6 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -95,7 +95,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -107,36 +107,20 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 2559e2d27d..b9631d6124 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -106,18 +106,18 @@ #define VBUS_SENSING_PIN PC5 #define VBUS_SENSING_ENABLED -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 diff --git a/src/main/target/IRCFUSIONF3/target.c b/src/main/target/IRCFUSIONF3/target.c index e31aa3a7b6..dd87a86410 100644 --- a/src/main/target/IRCFUSIONF3/target.c +++ b/src/main/target/IRCFUSIONF3/target.c @@ -99,8 +99,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 9588159722..8e41030edf 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -44,35 +44,19 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 3 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index 13550a2545..de059f7b46 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -23,8 +23,9 @@ #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR) -#define LED0 PB1 +#define LED0 PB1 #define BEEPER PB13 +#define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 @@ -43,32 +44,20 @@ #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_3 -#define UART2_RX_PIN GPIO_Pin_4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index cef9b31b0a..ac7d2c06dd 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -29,17 +29,16 @@ #define BEEPER PB13 #define BEEPER_INVERTED -#define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_AHBPeriph_GPIOA -#define MPU6500_CS_GPIO GPIOA -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 - #define USE_SPI #define USE_SPI_DEVICE_1 #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 +#define SPI1_NSS_PIN PA4 + +#define MPU6500_CS_PIN SPI1_NSS_PIN +#define MPU6500_SPI_INSTANCE SPI1 #define USABLE_TIMER_CHANNEL_COUNT 11 @@ -58,31 +57,19 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_4 -#define UART1_RX_PIN GPIO_Pin_5 -#define UART1_GPIO GPIOC -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource4 -#define UART1_RX_PINSOURCE GPIO_PinSource5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN GPIO_Pin_14 -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO GPIOB -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 183e1326d5..958924fabe 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -63,45 +63,24 @@ //#define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_3 // PB3 -#define UART2_RX_PIN GPIO_Pin_4 // PB4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 // PB3 +#define UART2_RX_PIN PB4 // PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C -#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) - -#define I2C2_SCL_GPIO GPIOA -#define I2C2_SCL_GPIO_AF GPIO_AF_4 -#define I2C2_SCL_PIN PA9 -#define I2C2_SCL_PIN_SOURCE GPIO_PinSource9 -#define I2C2_SCL_CLK_SOURCE RCC_AHBPeriph_GPIOA -#define I2C2_SDA_GPIO GPIOA -#define I2C2_SDA_GPIO_AF GPIO_AF_4 -#define I2C2_SDA_PIN PA10 -#define I2C2_SDA_PIN_SOURCE GPIO_PinSource10 -#define I2C2_SDA_CLK_SOURCE RCC_AHBPeriph_GPIOA +#define I2C_DEVICE (I2CDEV_2) +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 #define USE_SPI #define USE_SPI_DEVICE_2 diff --git a/src/main/target/NAZE/hardware_revision.c b/src/main/target/NAZE/hardware_revision.c index d71edde627..3f87237dbb 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/NAZE/target.h b/src/main/target/NAZE/target.h index cc8b93c09f..adca1659a7 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -119,9 +119,9 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 @@ -134,11 +134,8 @@ #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 // USART3 only on NAZE32_SP - Flex Port -#define USART3_RX_PIN Pin_11 -#define USART3_TX_PIN Pin_10 -#define USART3_GPIO GPIOB -#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 -#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index 3ff23fd8d3..c526310333 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -28,7 +28,7 @@ #ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER // "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit() -#define LED1 PA1 // D3, PA1/USART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow +#define LED1 PA1 // D3, PA1/UART2_RTS/ADC1/TIM2_CH3 - "LED2" on silkscreen, Yellow #endif #define GYRO @@ -62,8 +62,8 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index d895b571ce..a41891d696 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -97,8 +97,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) // LED Strip Pad { 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/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 250cc0c5e2..bab30522f7 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -70,36 +70,20 @@ #define USB_DETECT_PIN PB5 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3 @@ -152,7 +136,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 36ee217725..938af8f98b 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -49,31 +49,19 @@ #define MPU6000_SPI_INSTANCE SPI2 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_3 // PB3 -#define UART2_RX_PIN GPIO_Pin_4 // PB4 -#define UART2_GPIO GPIOB -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource3 -#define UART2_RX_PINSOURCE GPIO_PinSource4 +#define UART2_TX_PIN PB3 // PB3 +#define UART2_RX_PIN PB4 // PB4 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_SPI #define USE_SPI_DEVICE_2 diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index d5d0850d93..417f889c9f 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -89,8 +89,8 @@ #define DISPLAY -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 4 diff --git a/src/main/target/PORT103R/target.mk b/src/main/target/PORT103R/target.mk index 411a04e02b..2246dc6051 100644 --- a/src/main/target/PORT103R/target.mk +++ b/src/main/target/PORT103R/target.mk @@ -1,4 +1,7 @@ F1_TARGETS += $(TARGET) +256K_TARGETS += $(TARGET) +FLASH_SIZE = 256 + FEATURES = ONBOARDFLASH HIGHEND DEVICE_FLAGS = -DSTM32F10X_HD diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 2532d43878..05c58aa979 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -74,18 +74,18 @@ #define USE_VCP #define VBUS_SENSING_PIN PC5 -#define USE_USART1 -#define USART1_RX_PIN PA10 -#define USART1_TX_PIN PA9 -#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 -#define USE_USART3 -#define USART3_RX_PIN PB11 -#define USART3_TX_PIN PB10 +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 -#define USE_USART6 -#define USART6_RX_PIN PC7 -#define USART6_TX_PIN PC6 +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 14912fffc1..6e461c5eb2 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -62,13 +62,13 @@ #define USE_VCP #define VBUS_SENSING_PIN PA9 -#define USE_USART1 -#define USART1_RX_PIN PB7 -#define USART1_TX_PIN PB6 +#define USE_UART1 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 -#define USE_USART2 -#define USART2_RX_PIN PA3 -#define USART2_TX_PIN PA2 +#define USE_UART2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 #define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2 diff --git a/src/main/target/RMDO/target.c b/src/main/target/RMDO/target.c index 1bea16f50c..ee96272c11 100644 --- a/src/main/target/RMDO/target.c +++ b/src/main/target/RMDO/target.c @@ -99,8 +99,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 602609862e..14fd760c8e 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -55,37 +55,21 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 0d89f4226a..06e9f3cfee 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -43,32 +43,21 @@ #define USE_FLASH_M25P16 #define USE_VCP -#define USE_USART1 // JST-SH Serial - TX (PA9) RX (PA10) -#define USE_USART2 // Input - TX (NC) RX (PA15) -#define USE_USART3 // Solder Pads - TX (PB10) RX (PB11) +#define USE_UART1 // JST-SH Serial - TX (PA9) RX (PA10) +#define USE_UART2 // Input - TX (NC) RX (PA15) +#define USE_UART3 // Solder Pads - TX (PB10) RX (PB11) #define USE_SOFTSERIAL1 // Telemetry #define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN GPIO_Pin_9 -#define UART1_RX_PIN GPIO_Pin_10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN GPIO_Pin_14 //Not connected -#define UART2_RX_PIN GPIO_Pin_15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 //Not connected +#define UART2_RX_PIN PA15 + +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 -#define UART3_TX_PIN GPIO_Pin_10 -#define UART3_RX_PIN GPIO_Pin_11 -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 #define SOFTSERIAL_1_TIMER TIM15 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 76ca16fe9f..42f2378c66 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -56,35 +56,19 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_3 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #undef USE_I2C @@ -133,7 +117,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index 0913d0ec16..f82be07689 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -56,31 +56,19 @@ #define MAG_AK8975_ALIGN CW180_DEG_FLIP #define USE_VCP -#define USE_USART1 // Conn 1 - TX (PB6) RX PB7 (AF7) -#define USE_USART2 // Input - RX (PA3) -#define USE_USART3 // Servo out - 10/RX (PB11) 11/TX (PB10) +#define USE_UART1 // Conn 1 - TX (PB6) RX PB7 (AF7) +#define USE_UART2 // Input - RX (PA3) +#define USE_UART3 // Servo out - 10/RX (PB11) 11/TX (PB10) #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN GPIO_Pin_6 // PB6 -#define UART1_RX_PIN GPIO_Pin_7 // PB7 -#define UART1_GPIO GPIOB -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource6 -#define UART1_RX_PINSOURCE GPIO_PinSource7 +#define UART1_TX_PIN PB6 // PB6 +#define UART1_RX_PIN PB7 // PB7 -#define UART2_TX_PIN GPIO_Pin_2 // PA2 - Clashes with PWM6 input. -#define UART2_RX_PIN GPIO_Pin_3 // PA3 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input. +#define UART2_RX_PIN PA3 // PA3 -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) // Note: PA5 and PA0 are N/C on the sparky - potentially use for ADC or LED STRIP? diff --git a/src/main/target/SPRACINGF3/target.c b/src/main/target/SPRACINGF3/target.c index bf2a06da44..ec9176a27f 100644 --- a/src/main/target/SPRACINGF3/target.c +++ b/src/main/target/SPRACINGF3/target.c @@ -100,8 +100,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N // Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype. - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 840dda225a..2380fd1008 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -65,37 +65,21 @@ #define SONAR_ECHO_PIN PB1 #define SONAR_TRIGGER_PIN PB0 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/SPRACINGF3EVO/target.c b/src/main/target/SPRACINGF3EVO/target.c index 171f6be27a..843ad3d9aa 100644 --- a/src/main/target/SPRACINGF3EVO/target.c +++ b/src/main/target/SPRACINGF3EVO/target.c @@ -91,8 +91,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM6 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM7 { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM8 - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) { 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/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 4adbe0d563..0bae984252 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -65,35 +65,19 @@ #define USB_IO #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 4 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA @@ -126,7 +110,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/SPRACINGF3MINI/target.c b/src/main/target/SPRACINGF3MINI/target.c index 214dab6564..d1e3a0d8b2 100644 --- a/src/main/target/SPRACINGF3MINI/target.c +++ b/src/main/target/SPRACINGF3MINI/target.c @@ -100,8 +100,8 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM8 - PA1 // UART3 RX/TX - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / USART3_TX (AF7) - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / USART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM9 - PB10 - TIM2_CH3 / UART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM10 - PB11 - TIM2_CH4 / UART3_RX (AF7) // LED Strip Pad { 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/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index 61b4bd9b5e..d76558a9c2 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -73,36 +73,20 @@ #define USB_DETECT_PIN PB5 #define USE_VCP -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 9 // PA0 / PAD3 @@ -133,7 +117,7 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. #define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 #define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 7664b47e0c..8ac7eca05f 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -112,7 +112,7 @@ //// Divide to under 25MHz for normal operation: //#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 // -//// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +//// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. //#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 //#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 @@ -123,8 +123,8 @@ #define USE_MAG_HMC5883 #define USE_VCP -#define USE_USART1 -#define USE_USART2 +#define USE_UART1 +#define USE_UART2 #define SERIAL_PORT_COUNT 3 // uart2 gpio for shared serial rx/ppm diff --git a/src/main/target/X_RACERSPI/target.c b/src/main/target/X_RACERSPI/target.c index f2ad959f8d..85db79093c 100644 --- a/src/main/target/X_RACERSPI/target.c +++ b/src/main/target/X_RACERSPI/target.c @@ -84,8 +84,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 217765adcf..4a38e233fb 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -55,37 +55,21 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 #define SERIAL_PORT_COUNT 5 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif +#define UART1_TX_PIN PA9 // PA9 +#define UART1_RX_PIN PA10 // PA10 -#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_3 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource2 -#define UART2_RX_PINSOURCE GPIO_PinSource3 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 diff --git a/src/main/target/ZCOREF3/target.c b/src/main/target/ZCOREF3/target.c index a3cfdc7339..b72400e6fd 100644 --- a/src/main/target/ZCOREF3/target.c +++ b/src/main/target/ZCOREF3/target.c @@ -83,8 +83,8 @@ const uint16_t airPWM[] = { const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH1 - PA0 - *TIM2_CH1 { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N - { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7) - { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7) + { TIM2, IO_TAG(PB11), TIM_Channel_4, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH3 - PB11 - *TIM2_CH4, UART3_RX (AF7) + { TIM2, IO_TAG(PB10), TIM_Channel_3, TIM2_IRQn, 0, IOCFG_AF_PP, GPIO_AF_1 }, // RC_CH4 - PB10 - *TIM2_CH3, UART3_TX (AF7) { TIM3, IO_TAG(PB4), TIM_Channel_1, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH5 - PB4 - *TIM3_CH1 { TIM3, IO_TAG(PB5), TIM_Channel_2, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH6 - PB5 - *TIM3_CH2 { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, 0, IOCFG_AF_PP, GPIO_AF_2 }, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index d8ac143e88..dc9f80cb23 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -51,35 +51,17 @@ #define BARO #define USE_BARO_BMP280 -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 +#define USE_UART1 +#define USE_UART2 +#define USE_UART3 #define SERIAL_PORT_COUNT 3 -#ifndef UART1_GPIO -#define UART1_TX_PIN GPIO_Pin_9 // PA9 -#define UART1_RX_PIN GPIO_Pin_10 // PA10 -#define UART1_GPIO GPIOA -#define UART1_GPIO_AF GPIO_AF_7 -#define UART1_TX_PINSOURCE GPIO_PinSource9 -#define UART1_RX_PINSOURCE GPIO_PinSource10 -#endif -#define UART2_TX_PIN GPIO_Pin_14 // PA14 / SWCLK -#define UART2_RX_PIN GPIO_Pin_15 // PA15 -#define UART2_GPIO GPIOA -#define UART2_GPIO_AF GPIO_AF_7 -#define UART2_TX_PINSOURCE GPIO_PinSource14 -#define UART2_RX_PINSOURCE GPIO_PinSource15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#ifndef UART3_GPIO -#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7) -#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7) -#define UART3_GPIO_AF GPIO_AF_7 -#define UART3_GPIO GPIOB -#define UART3_TX_PINSOURCE GPIO_PinSource10 -#define UART3_RX_PINSOURCE GPIO_PinSource11 -#endif +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA diff --git a/src/main/target/common.h b/src/main/target/common.h index dbe2c3a374..c9a9a0f1b3 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -36,6 +36,12 @@ #endif +#ifdef STM32F1 +// Using RX DMA disables the use of receive callbacks +#define USE_UART1_RX_DMA + +#endif + #define SERIAL_RX #define USE_CLI diff --git a/src/main/target/system_stm32f30x.c b/src/main/target/system_stm32f30x.c index 78274ac322..09ba3fa47c 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 6d130d8512..e266366801 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/hott.c b/src/main/telemetry/hott.c index 6fb0bc1a92..7ccf8ea197 100644 --- a/src/main/telemetry/hott.c +++ b/src/main/telemetry/hott.c @@ -193,15 +193,15 @@ void hottPrepareGPSResponse(HOTT_GPS_MSG_t *hottGPSMessage) addGPSCoordinates(hottGPSMessage, GPS_coord[LAT], GPS_coord[LON]); - // GPS Speed in km/h - uint16_t speed = (GPS_speed * 36) / 100; // 0->1m/s * 0->36 = km/h + // GPS Speed is returned in cm/s (from io/gps.c) and must be sent in km/h (Hott requirement) + const uint16_t speed = (GPS_speed * 36) / 1000; hottGPSMessage->gps_speed_L = speed & 0x00FF; hottGPSMessage->gps_speed_H = speed >> 8; hottGPSMessage->home_distance_L = GPS_distanceToHome & 0x00FF; hottGPSMessage->home_distance_H = GPS_distanceToHome >> 8; - uint16_t hottGpsAltitude = (GPS_altitude) + HOTT_GPS_ALTITUDE_OFFSET; // GPS_altitude in m ; offset = 500 -> O m + const uint16_t hottGpsAltitude = (GPS_altitude) + HOTT_GPS_ALTITUDE_OFFSET; // GPS_altitude in m ; offset = 500 -> O m hottGPSMessage->altitude_L = hottGpsAltitude & 0x00FF; hottGPSMessage->altitude_H = hottGpsAltitude >> 8; diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 36b7c95569..28daadc40b 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 f4f38ba947..e3871aead0 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 60c8036202..ea8d49bcf1 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 8b789fa48f..5672eeae55 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 f3f9a3af91..ab1a3e1d35 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 395400d29f..958e772322 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; - + } }