diff --git a/Makefile b/Makefile index 90a221d2a7..281b169c63 100644 --- a/Makefile +++ b/Makefile @@ -548,8 +548,8 @@ VPATH := $(VPATH):$(STDPERIPH_DIR)/src # Find out if ccache is installed on the system CCACHE := ccache -RESULT = $(shell which $(CCACHE)) -ifeq ($(RESULT),) +RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) ) +ifneq ($(RESULT),0) CCACHE := endif diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index c529f4132b..9ab7e8a0b0 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -632,7 +632,7 @@ static void writeInterframe(void) arraySubInt32(deltas, blackboxCurrent->axisPID_P, blackboxLast->axisPID_P, XYZ_AXIS_COUNT); blackboxWriteSignedVBArray(deltas, XYZ_AXIS_COUNT); - /* + /* * The PID I field changes very slowly, most of the time +-2, so use an encoding * that can pack all three fields into one byte in that situation. */ @@ -1140,6 +1140,7 @@ static bool blackboxWriteSysinfo() BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight"); BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName); BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime); + BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name); BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom); BLACKBOX_PRINT_HEADER_LINE("minthrottle:%d", masterConfig.escAndServoConfig.minthrottle); BLACKBOX_PRINT_HEADER_LINE("maxthrottle:%d", masterConfig.escAndServoConfig.maxthrottle); @@ -1218,6 +1219,8 @@ static bool blackboxWriteSysinfo() BLACKBOX_PRINT_HEADER_LINE("yaw_deadband:%d", masterConfig.rcControlsConfig.yaw_deadband); BLACKBOX_PRINT_HEADER_LINE("gyro_lpf:%d", masterConfig.gyro_lpf); BLACKBOX_PRINT_HEADER_LINE("gyro_lowpass_hz:%d", (int)(masterConfig.gyro_soft_lpf_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz:%d", (int)(masterConfig.gyro_soft_notch_hz * 100.0f)); + BLACKBOX_PRINT_HEADER_LINE("gyro_notch_q:%d", (int)(masterConfig.gyro_soft_notch_q * 10.0f)); BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz:%d", (int)(masterConfig.acc_lpf_hz * 100.0f)); BLACKBOX_PRINT_HEADER_LINE("acc_hardware:%d", masterConfig.acc_hardware); BLACKBOX_PRINT_HEADER_LINE("baro_hardware:%d", masterConfig.baro_hardware); @@ -1314,7 +1317,7 @@ static void blackboxCheckAndLogFlightMode() } } -/* +/* * Use the user's num/denom settings to decide if the P-frame of the given index should be logged, allowing the user to control * the portion of logged loop iterations. */ diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 7f9b1ec5bd..cd4f05d980 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -507,7 +507,7 @@ void blackboxWriteFloat(float value) /** * If there is data waiting to be written to the blackbox device, attempt to write (a portion of) that now. - * + * * Intended to be called regularly for the blackbox device to perform housekeeping. */ void blackboxDeviceFlush(void) diff --git a/src/main/common/filter.c b/src/main/common/filter.c index d059fe882f..90c3decdae 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -56,24 +56,39 @@ float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT) } /* sets up a biquad Filter */ -void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate) +void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate) +{ + biquadFilterInit(filter, filterFreq, refreshRate, BIQUAD_Q, FILTER_LPF); +} +void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType) { - const float sampleRate = 1 / ((float)refreshRate * 0.000001f); - // setup variables - const float omega = 2 * M_PI_FLOAT * filterCutFreq / sampleRate; + const float sampleRate = 1 / ((float)refreshRate * 0.000001f); + const float omega = 2 * M_PI_FLOAT * filterFreq / sampleRate; const float sn = sinf(omega); const float cs = cosf(omega); - //this is wrong, should be hyperbolic sine - //alpha = sn * sinf(M_LN2_FLOAT /2 * BIQUAD_BANDWIDTH * omega /sn); - const float alpha = sn / (2 * BIQUAD_Q); + const float alpha = sn / (2 * Q); - const float b0 = (1 - cs) / 2; - const float b1 = 1 - cs; - const float b2 = (1 - cs) / 2; - const float a0 = 1 + alpha; - const float a1 = -2 * cs; - const float a2 = 1 - alpha; + float b0, b1, b2, a0, a1, a2; + + switch (filterType) { + case FILTER_LPF: + b0 = (1 - cs) / 2; + b1 = 1 - cs; + b2 = (1 - cs) / 2; + a0 = 1 + alpha; + a1 = -2 * cs; + a2 = 1 - alpha; + break; + case FILTER_NOTCH: + b0 = 1; + b1 = -2 * cs; + b2 = 1; + a0 = 1 + alpha; + a1 = -2 * cs; + a2 = 1 - alpha; + break; + } // precompute the coefficients filter->b0 = b0 / a0; diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 66fcb53bb0..d97becc015 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -29,8 +29,13 @@ typedef struct biquadFilter_s { float d1, d2; } biquadFilter_t; +typedef enum { + FILTER_LPF, + FILTER_NOTCH +} filterType_e; -void biquadFilterInit(biquadFilter_t *filter, float filterCutFreq, uint32_t refreshRate); +void biquadFilterInitLPF(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate); +void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, filterType_e filterType); float biquadFilterApply(biquadFilter_t *filter, float input); void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT); diff --git a/src/main/common/maths.c b/src/main/common/maths.c index 888847e075..52990c6ac8 100644 --- a/src/main/common/maths.c +++ b/src/main/common/maths.c @@ -231,7 +231,7 @@ int32_t quickMedianFilter5(int32_t * v) QMF_SORT(p[0], p[1]); QMF_SORT(p[3], p[4]); QMF_SORT(p[0], p[3]); QMF_SORT(p[1], p[4]); QMF_SORT(p[1], p[2]); QMF_SORT(p[2], p[3]); - QMF_SORT(p[1], p[2]); + QMF_SORT(p[1], p[2]); return p[2]; } @@ -279,7 +279,7 @@ float quickMedianFilter5f(float * v) QMF_SORTF(p[0], p[1]); QMF_SORTF(p[3], p[4]); QMF_SORTF(p[0], p[3]); QMF_SORTF(p[1], p[4]); QMF_SORTF(p[1], p[2]); QMF_SORTF(p[2], p[3]); - QMF_SORTF(p[1], p[2]); + QMF_SORTF(p[1], p[2]); return p[2]; } diff --git a/src/main/common/printf.c b/src/main/common/printf.c index 7847fb3035..e11d49d151 100644 --- a/src/main/common/printf.c +++ b/src/main/common/printf.c @@ -56,7 +56,7 @@ typedef void (*putcf) (void *, char); static putcf stdout_putf; static void *stdout_putp; -// print bf, padded from left to at least n characters. +// print bf, padded from left to at least n characters. // padding is zero ('0') if z!=0, space (' ') otherwise static int putchw(void *putp, putcf putf, int n, char z, char *bf) { diff --git a/src/main/config/config.c b/src/main/config/config.c index 06ba7c9c09..0caa5c62e7 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -159,7 +159,7 @@ size_t custom_flash_memory_address = 0; #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) #else // use the last flash pages for storage -#ifndef CONFIG_START_FLASH_ADDRESS +#ifndef CONFIG_START_FLASH_ADDRESS #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) #endif #endif @@ -349,7 +349,7 @@ void resetSerialConfig(serialConfig_t *serialConfig) serialConfig->reboot_character = 'R'; } -static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) +static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; controlRateConfig->rcYawRate8 = 100; @@ -366,7 +366,7 @@ static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) } -void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) +void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) { rcControlsConfig->deadband = 0; rcControlsConfig->yaw_deadband = 0; @@ -374,7 +374,7 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) rcControlsConfig->alt_hold_fast_change = 1; } -void resetMixerConfig(mixerConfig_t *mixerConfig) +void resetMixerConfig(mixerConfig_t *mixerConfig) { mixerConfig->yaw_motor_direction = 1; #ifdef USE_SERVOS @@ -441,6 +441,7 @@ static void resetConf(void) featureSet(FEATURE_VBAT); #endif + masterConfig.version = EEPROM_CONF_VERSION; masterConfig.mixerMode = MIXER_QUADX; @@ -455,6 +456,8 @@ static void resetConf(void) masterConfig.gyro_sync_denom = 4; #endif masterConfig.gyro_soft_lpf_hz = 100; + masterConfig.gyro_soft_notch_hz = 0; + masterConfig.gyro_soft_notch_q = 5; masterConfig.pid_process_denom = 2; @@ -657,6 +660,7 @@ static void resetConf(void) targetConfiguration(); #endif + // copy first profile into remaining profile for (int i = 1; i < MAX_PROFILE_COUNT; i++) { memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t)); @@ -715,7 +719,7 @@ void activateConfig(void) ¤tProfile->pidProfile ); - gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz); + gyroUseConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz, masterConfig.gyro_soft_notch_hz, masterConfig.gyro_soft_notch_q); #ifdef TELEMETRY telemetryUseConfig(&masterConfig.telemetryConfig); diff --git a/src/main/config/config.h b/src/main/config/config.h index 5a46a78c33..b18febe8cd 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -24,6 +24,8 @@ #endif #define MAX_RATEPROFILES 3 #define ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS 1500 +#define MAX_NAME_LENGTH 16 + typedef enum { FEATURE_RX_PPM = 1 << 0, diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index c6f01b4029..5ce1d36833 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -56,9 +56,11 @@ typedef struct master_t { int8_t yaw_control_direction; // change control direction of yaw (inverted, normal) uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes. - uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. + uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen. uint8_t gyro_sync_denom; // Gyro sample divider - uint8_t gyro_soft_lpf_hz; // Biqyad gyro lpf hz + uint8_t gyro_soft_lpf_hz; // Biquad gyro lpf hz + uint16_t gyro_soft_notch_hz; // Biquad gyro notch hz + uint8_t gyro_soft_notch_q; // Biquad gyro notch quality uint16_t dcm_kp; // DCM filter proportional gain ( x 10000) uint16_t dcm_ki; // DCM filter integral gain ( x 10000) @@ -137,7 +139,7 @@ typedef struct master_t { profile_t profile[MAX_PROFILE_COUNT]; uint8_t current_profile_index; - + modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT]; adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT]; @@ -161,6 +163,9 @@ typedef struct master_t { uint8_t magic_ef; // magic number, should be 0xEF uint8_t chk; // XOR checksum + + char name[MAX_NAME_LENGTH+1]; + } master_t; extern master_t masterConfig; diff --git a/src/main/debug.h b/src/main/debug.h index 4f6250b758..19124266d0 100644 --- a/src/main/debug.h +++ b/src/main/debug.h @@ -50,5 +50,6 @@ typedef enum { DEBUG_MIXER, DEBUG_AIRMODE, DEBUG_PIDLOOP, + DEBUG_NOTCH, DEBUG_COUNT } debugType_e; diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 9a3cd57253..1c705ef137 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -252,7 +252,7 @@ void mpuIntExtiInit(void) EXTIEnable(mpuIntIO, true); #endif - mpuExtiInitDone = true; + mpuExtiInitDone = true; } static bool mpuReadRegisterI2C(uint8_t reg, uint8_t length, uint8_t* data) diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index 917c06f1a8..132c9e13a0 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -18,7 +18,7 @@ #pragma once #include "exti.h" - + // MPU6050 #define MPU_RA_WHO_AM_I 0x75 #define MPU_RA_WHO_AM_I_LEGACY 0x00 @@ -119,7 +119,7 @@ typedef bool (*mpuReadRegisterFunc)(uint8_t reg, uint8_t length, uint8_t* data); typedef bool (*mpuWriteRegisterFunc)(uint8_t reg, uint8_t data); -typedef void(*mpuResetFuncPtr)(void); +typedef void(*mpuResetFuncPtr)(void); typedef struct mpuConfiguration_s { uint8_t gyroReadXRegister; // Y and Z must registers follow this, 2 words each diff --git a/src/main/drivers/accgyro_mpu6050.c b/src/main/drivers/accgyro_mpu6050.c index 3cc3ac8f69..78e8b8e801 100644 --- a/src/main/drivers/accgyro_mpu6050.c +++ b/src/main/drivers/accgyro_mpu6050.c @@ -104,7 +104,7 @@ static void mpu6050GyroInit(uint8_t lpf) delay(100); ack = mpuConfiguration.write(MPU_RA_PWR_MGMT_1, 0x03); //PWR_MGMT_1 -- SLEEP 0; CYCLE 0; TEMP_DIS 0; CLKSEL 3 (PLL with Z Gyro reference) ack = mpuConfiguration.write(MPU_RA_SMPLRT_DIV, gyroMPU6xxxGetDividerDrops()); //SMPLRT_DIV -- SMPLRT_DIV = 0 Sample Rate = Gyroscope Output Rate / (1 + SMPLRT_DIV) - delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure + delay(15); //PLL Settling time when changing CLKSEL is max 10ms. Use 15ms to be sure ack = mpuConfiguration.write(MPU_RA_CONFIG, lpf); //CONFIG -- EXT_SYNC_SET 0 (disable input pin for data sync) ; default DLPF_CFG = 0 => ACC bandwidth = 260Hz GYRO bandwidth = 256Hz) ack = mpuConfiguration.write(MPU_RA_GYRO_CONFIG, INV_FSR_2000DPS << 3); //GYRO_CONFIG -- FS_SEL = 3: Full scale set to 2000 deg/sec diff --git a/src/main/drivers/accgyro_spi_mpu6000.c b/src/main/drivers/accgyro_spi_mpu6000.c index b483380912..dc21901e7a 100644 --- a/src/main/drivers/accgyro_spi_mpu6000.c +++ b/src/main/drivers/accgyro_spi_mpu6000.c @@ -158,7 +158,7 @@ bool mpu6000SpiDetect(void) uint8_t in; uint8_t attemptsRemaining = 5; -#ifdef MPU6000_CS_PIN +#ifdef MPU6000_CS_PIN mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN)); #endif IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0); @@ -253,7 +253,7 @@ static void mpu6000AccAndGyroInit(void) { delayMicroseconds(15); #endif - spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_FAST); delayMicroseconds(1); mpuSpi6000InitDone = true; diff --git a/src/main/drivers/accgyro_spi_mpu9250.c b/src/main/drivers/accgyro_spi_mpu9250.c index b5beca2946..0406e6023c 100644 --- a/src/main/drivers/accgyro_spi_mpu9250.c +++ b/src/main/drivers/accgyro_spi_mpu9250.c @@ -54,7 +54,7 @@ static IO_t mpuSpi9250CsPin = IO_NONE; #define DISABLE_MPU9250 IOHi(mpuSpi9250CsPin) #define ENABLE_MPU9250 IOLo(mpuSpi9250CsPin) -void mpu9250ResetGyro(void) +void mpu9250ResetGyro(void) { // Device Reset mpu9250WriteRegister(MPU_RA_PWR_MGMT_1, MPU9250_BIT_RESET); @@ -123,7 +123,7 @@ void mpu9250SpiAccInit(acc_t *acc) acc->acc_1G = 512 * 8; } -bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) +bool verifympu9250WriteRegister(uint8_t reg, uint8_t data) { uint8_t in; uint8_t attemptsRemaining = 20; @@ -176,7 +176,7 @@ static void mpu9250AccAndGyroInit(uint8_t lpf) { verifympu9250WriteRegister(MPU_RA_INT_ENABLE, 0x01); //this resets register MPU_RA_PWR_MGMT_1 and won't read back correctly. #endif - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); mpuSpi9250InitDone = true; //init done } @@ -208,7 +208,7 @@ bool mpu9250SpiDetect(void) } } while (attemptsRemaining--); - spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); + spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_FAST); return true; } diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 258c8acc8d..146ada62be 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -24,14 +24,14 @@ #define ADC_TAG_MAP_COUNT 16 #elif defined(STM32F3) #define ADC_TAG_MAP_COUNT 39 -#else +#else #define ADC_TAG_MAP_COUNT 10 -#endif +#endif typedef enum ADCDevice { ADCINVALID = -1, ADCDEV_1 = 0, -#if defined(STM32F3) +#if defined(STM32F3) ADCDEV_2, ADCDEV_MAX = ADCDEV_2, #elif defined(STM32F4) diff --git a/src/main/drivers/adc_stm32f10x.c b/src/main/drivers/adc_stm32f10x.c index 451c9296c6..3104bcd5e9 100644 --- a/src/main/drivers/adc_stm32f10x.c +++ b/src/main/drivers/adc_stm32f10x.c @@ -24,9 +24,6 @@ #include "build_config.h" #include "system.h" - -#include "sensors/sensors.h" // FIXME dependency into the main code - #include "sensor.h" #include "accgyro.h" #include "adc.h" @@ -38,13 +35,13 @@ #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 } }; ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; /* TODO -- ADC2 available on large 10x devices. @@ -54,7 +51,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) return ADCINVALID; } -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA0, ADC_Channel_0 }, // ADC12 { DEFIO_TAG_E__PA1, ADC_Channel_1 }, // ADC12 { DEFIO_TAG_E__PA2, ADC_Channel_2 }, // ADC12 @@ -64,7 +61,7 @@ const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA6, ADC_Channel_6 }, // ADC12 { DEFIO_TAG_E__PA7, ADC_Channel_7 }, // ADC12 { DEFIO_TAG_E__PB0, ADC_Channel_8 }, // ADC12 - { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 + { DEFIO_TAG_E__PB1, ADC_Channel_9 }, // ADC12 }; // Driver for STM32F103CB onboard ADC @@ -84,7 +81,6 @@ void adcInit(drv_adc_config_t *init) UNUSED(init); #endif - uint8_t i; uint8_t configuredAdcChannels = 0; memset(&adcConfig, 0, sizeof(adcConfig)); @@ -117,9 +113,9 @@ void adcInit(drv_adc_config_t *init) if (device == ADCINVALID) return; - adcDevice_t adc = adcHardware[device]; + const adcDevice_t adc = adcHardware[device]; - for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { + for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) continue; @@ -163,7 +159,7 @@ void adcInit(drv_adc_config_t *init) ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; - for (i = 0; i < ADC_CHANNEL_COUNT; i++) { + for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } diff --git a/src/main/drivers/adc_stm32f30x.c b/src/main/drivers/adc_stm32f30x.c index 6297c2bd16..f58a8086d6 100644 --- a/src/main/drivers/adc_stm32f30x.c +++ b/src/main/drivers/adc_stm32f30x.c @@ -21,7 +21,6 @@ #include "platform.h" #include "system.h" -#include "common/utils.h" #include "gpio.h" #include "sensor.h" @@ -32,16 +31,18 @@ #include "io.h" #include "rcc.h" +#include "common/utils.h" + #ifndef ADC_INSTANCE #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, - { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }, + { .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 } }; -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { { DEFIO_TAG_E__PA0, ADC_Channel_1 }, // ADC1 { DEFIO_TAG_E__PA1, ADC_Channel_2 }, // ADC1 { DEFIO_TAG_E__PA2, ADC_Channel_3 }, // ADC1 @@ -85,7 +86,7 @@ const adcTagMap_t adcTagMap[] = { ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; if (instance == ADC2) @@ -100,7 +101,6 @@ void adcInit(drv_adc_config_t *init) ADC_InitTypeDef ADC_InitStructure; DMA_InitTypeDef DMA_InitStructure; - uint8_t i; uint8_t adcChannelCount = 0; memset(&adcConfig, 0, sizeof(adcConfig)); @@ -133,9 +133,9 @@ void adcInit(drv_adc_config_t *init) if (device == ADCINVALID) return; - adcDevice_t adc = adcHardware[device]; + adcDevice_t adc = adcHardware[device]; - for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { + for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) continue; @@ -203,7 +203,7 @@ void adcInit(drv_adc_config_t *init) ADC_Init(adc.ADCx, &ADC_InitStructure); uint8_t rank = 1; - for (i = 0; i < ADC_CHANNEL_COUNT; i++) { + for (int i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].enabled) { continue; } diff --git a/src/main/drivers/adc_stm32f4xx.c b/src/main/drivers/adc_stm32f4xx.c index e1bb1ae617..968f05a67e 100644 --- a/src/main/drivers/adc_stm32f4xx.c +++ b/src/main/drivers/adc_stm32f4xx.c @@ -26,8 +26,6 @@ #include "io_impl.h" #include "rcc.h" -#include "sensors/sensors.h" // FIXME dependency into the main code - #include "sensor.h" #include "accgyro.h" @@ -38,13 +36,13 @@ #define ADC_INSTANCE ADC1 #endif -const adcDevice_t adcHardware[] = { - { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, - //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } +const adcDevice_t adcHardware[] = { + { .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 }, + //{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 } }; /* note these could be packed up for saving space */ -const adcTagMap_t adcTagMap[] = { +const adcTagMap_t adcTagMap[] = { /* { DEFIO_TAG_E__PF3, ADC_Channel_9 }, { DEFIO_TAG_E__PF4, ADC_Channel_14 }, @@ -75,7 +73,7 @@ const adcTagMap_t adcTagMap[] = { ADCDevice adcDeviceByInstance(ADC_TypeDef *instance) { - if (instance == ADC1) + if (instance == ADC1) return ADCDEV_1; /* if (instance == ADC2) // TODO add ADC2 and 3 @@ -128,7 +126,7 @@ void adcInit(drv_adc_config_t *init) if (device == ADCINVALID) return; - adcDevice_t adc = adcHardware[device]; + adcDevice_t adc = adcHardware[device]; for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) { if (!adcConfig[i].tag) diff --git a/src/main/drivers/barometer_bmp085.c b/src/main/drivers/barometer_bmp085.c index 4c3e779855..9b35646b6b 100644 --- a/src/main/drivers/barometer_bmp085.c +++ b/src/main/drivers/barometer_bmp085.c @@ -35,7 +35,7 @@ #ifdef BARO -#if defined(BARO_EOC_GPIO) +#if defined(BARO_EOC_GPIO) static IO_t eocIO; @@ -49,7 +49,7 @@ void bmp085_extiHandler(extiCallbackRec_t* cb) isConversionComplete = true; } -bool bmp085TestEOCConnected(const bmp085Config_t *config); +bool bmp085TestEOCConnected(const bmp085Config_t *config); # endif typedef struct { @@ -139,7 +139,7 @@ static IO_t xclrIO; #endif -void bmp085InitXclrIO(const bmp085Config_t *config) +void bmp085InitXclrIO(const bmp085Config_t *config) { if (!xclrIO && config && config->xclrIO) { xclrIO = IOGetByTag(config->xclrIO); @@ -184,7 +184,7 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro) delay(20); // datasheet says 10ms, we'll be careful and do 20. - ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ + ack = i2cRead(BARO_I2C_INSTANCE, BMP085_I2C_ADDR, BMP085_CHIP_ID__REG, 1, &data); /* read Chip Id */ if (ack) { bmp085.chip_id = BMP085_GET_BITSLICE(data, BMP085_CHIP_ID); bmp085.oversampling_setting = 3; diff --git a/src/main/drivers/barometer_bmp085.h b/src/main/drivers/barometer_bmp085.h index 328bffb134..ffe863d1ba 100644 --- a/src/main/drivers/barometer_bmp085.h +++ b/src/main/drivers/barometer_bmp085.h @@ -19,7 +19,7 @@ typedef struct bmp085Config_s { ioTag_t xclrIO; - ioTag_t eocIO; + ioTag_t eocIO; } bmp085Config_t; bool bmp085Detect(const bmp085Config_t *config, baro_t *baro); diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index bdfc75dfa9..86f7a66181 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -26,7 +26,7 @@ #ifndef I2C_DEVICE #define I2C_DEVICE I2CINVALID -#endif +#endif typedef enum I2CDevice { I2CINVALID = -1, diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 74a9f36559..7daea6fa95 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -47,35 +47,35 @@ static void i2cUnstick(IO_t scl, IO_t sda); #define IOCFG_I2C IOCFG_AF_OD #endif -#ifndef I2C1_SCL -#define I2C1_SCL PB8 +#ifndef I2C1_SCL +#define I2C1_SCL PB8 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB9 +#ifndef I2C1_SDA +#define I2C1_SDA PB9 #endif #else -#ifndef I2C1_SCL -#define I2C1_SCL PB6 +#ifndef I2C1_SCL +#define I2C1_SCL PB6 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB7 +#ifndef I2C1_SDA +#define I2C1_SDA PB7 #endif #endif -#ifndef I2C2_SCL -#define I2C2_SCL PB10 +#ifndef I2C2_SCL +#define I2C2_SCL PB10 #endif -#ifndef I2C2_SDA +#ifndef I2C2_SDA #define I2C2_SDA PB11 #endif #ifdef STM32F4 -#ifndef I2C3_SCL +#ifndef I2C3_SCL #define I2C3_SCL PA8 #endif -#ifndef I2C3_SDA -#define I2C3_SDA PB4 +#ifndef I2C3_SDA +#define I2C3_SDA PB4 #endif #endif @@ -93,7 +93,7 @@ static i2cState_t i2cState[] = { { false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 }, { false, false, 0, 0, 0, 0, 0, 0, 0 } -}; +}; void I2C1_ER_IRQHandler(void) { i2c_er_handler(I2CDEV_1); @@ -121,7 +121,7 @@ void I2C3_EV_IRQHandler(void) { } #endif -static bool i2cHandleHardwareFailure(I2CDevice device) +static bool i2cHandleHardwareFailure(I2CDevice device) { i2cErrorCount++; // reinit peripheral + clock out garbage @@ -129,7 +129,7 @@ static bool i2cHandleHardwareFailure(I2CDevice device) return false; } -bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) +bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data) { if (device == I2CINVALID) @@ -138,7 +138,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint32_t timeout = I2C_DEFAULT_TIMEOUT; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; i2cState_t *state; state = &(i2cState[device]); @@ -171,12 +171,12 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, return !(state->error); } -bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) +bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) { return i2cWriteBuffer(device, addr_, reg_, 1, &data); } -bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) +bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) { if (device == I2CINVALID) return false; @@ -369,7 +369,7 @@ void i2c_ev_handler(I2CDevice device) { } } -void i2cInit(I2CDevice device) +void i2cInit(I2CDevice device) { if (device == I2CINVALID) return; @@ -392,7 +392,7 @@ void i2cInit(I2CDevice device) I2C_ITConfig(i2c->dev, I2C_IT_EVT | I2C_IT_ERR, DISABLE); i2cUnstick(scl, sda); - + // Init pins #ifdef STM32F4 IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_I2C); diff --git a/src/main/drivers/bus_i2c_stm32f30x.c b/src/main/drivers/bus_i2c_stm32f30x.c index d645a70504..524df1bc86 100644 --- a/src/main/drivers/bus_i2c_stm32f30x.c +++ b/src/main/drivers/bus_i2c_stm32f30x.c @@ -39,18 +39,18 @@ #define I2C_SHORT_TIMEOUT ((uint32_t)0x1000) #define I2C_LONG_TIMEOUT ((uint32_t)(10 * I2C_SHORT_TIMEOUT)) -#define I2C_GPIO_AF GPIO_AF_4 +#define I2C_GPIO_AF GPIO_AF_4 -#ifndef I2C1_SCL -#define I2C1_SCL PB6 +#ifndef I2C1_SCL +#define I2C1_SCL PB6 #endif -#ifndef I2C1_SDA -#define I2C1_SDA PB7 +#ifndef I2C1_SDA +#define I2C1_SDA PB7 #endif -#ifndef I2C2_SCL -#define I2C2_SCL PF4 +#ifndef I2C2_SCL +#define I2C2_SCL PF4 #endif -#ifndef I2C2_SDA +#ifndef I2C2_SDA #define I2C2_SDA PA10 #endif @@ -82,7 +82,7 @@ void i2cInit(I2CDevice device) I2C_TypeDef *I2Cx; I2Cx = i2c->dev; - + IO_t scl = IOGetByTag(i2c->scl); IO_t sda = IOGetByTag(i2c->sda); @@ -108,7 +108,7 @@ void i2cInit(I2CDevice device) I2C_Init(I2Cx, &i2cInit); I2C_StretchClockCmd(I2Cx, ENABLE); - + I2C_Cmd(I2Cx, ENABLE); } @@ -122,7 +122,7 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data) addr_ <<= 1; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; @@ -188,7 +188,7 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t len, uint8_t* addr_ <<= 1; I2C_TypeDef *I2Cx; - I2Cx = i2cHardwareMap[device].dev; + I2Cx = i2cHardwareMap[device].dev; /* Test on BUSY Flag */ i2cTimeout = I2C_LONG_TIMEOUT; diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 005f7936b6..690f25b52e 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -36,7 +36,7 @@ #ifndef GPIO_AF_SPI3 #define GPIO_AF_SPI3 GPIO_AF_6 #endif -#endif +#endif #ifndef SPI1_SCK_PIN #define SPI1_NSS_PIN PA4 @@ -84,7 +84,7 @@ static spiDevice_t spiHardwareMap[] = { SPIDevice spiDeviceByInstance(SPI_TypeDef *instance) { - if (instance == SPI1) + if (instance == SPI1) return SPIDEV_1; if (instance == SPI2) diff --git a/src/main/drivers/bus_spi.h b/src/main/drivers/bus_spi.h index dbba94881c..5a6ea7dd37 100644 --- a/src/main/drivers/bus_spi.h +++ b/src/main/drivers/bus_spi.h @@ -31,8 +31,6 @@ #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_PP, GPIO_Speed_50MHz) -#else -#error "Unknown processor" #endif /* diff --git a/src/main/drivers/dma.h b/src/main/drivers/dma.h index 1665af5bd9..726a5a1807 100644 --- a/src/main/drivers/dma.h +++ b/src/main/drivers/dma.h @@ -65,7 +65,7 @@ typedef struct dmaChannelDescriptor_s { #define DMA_IT_TEIF ((uint32_t)0x00000008) #define DMA_IT_DMEIF ((uint32_t)0x00000004) #define DMA_IT_FEIF ((uint32_t)0x00000001) - + #else typedef enum { diff --git a/src/main/drivers/dma_stm32f4xx.c b/src/main/drivers/dma_stm32f4xx.c index a7dfd47045..ec6e7908d3 100644 --- a/src/main/drivers/dma_stm32f4xx.c +++ b/src/main/drivers/dma_stm32f4xx.c @@ -45,7 +45,6 @@ static dmaChannelDescriptor_t dmaDescriptors[] = { DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream5, 38, DMA2_Stream5_IRQn, RCC_AHB1Periph_DMA2), DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream6, 48, DMA2_Stream6_IRQn, RCC_AHB1Periph_DMA2), DEFINE_DMA_CHANNEL(DMA2, DMA2_Stream7, 54, DMA2_Stream7_IRQn, RCC_AHB1Periph_DMA2), - }; /* @@ -68,7 +67,6 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER) DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER) DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER) - void dmaInit(void) { // TODO: Do we need this? diff --git a/src/main/drivers/exti.c b/src/main/drivers/exti.c index cd97ba9b74..ce665bb077 100644 --- a/src/main/drivers/exti.c +++ b/src/main/drivers/exti.c @@ -24,22 +24,22 @@ static uint8_t extiGroupPriority[EXTI_IRQ_GROUPS]; #if defined(STM32F1) || defined(STM32F4) static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { - EXTI0_IRQn, - EXTI1_IRQn, - EXTI2_IRQn, - EXTI3_IRQn, + EXTI0_IRQn, + EXTI1_IRQn, + EXTI2_IRQn, + EXTI3_IRQn, EXTI4_IRQn, - EXTI9_5_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn }; #elif defined(STM32F3) static const uint8_t extiGroupIRQn[EXTI_IRQ_GROUPS] = { - EXTI0_IRQn, - EXTI1_IRQn, - EXTI2_TS_IRQn, - EXTI3_IRQn, + EXTI0_IRQn, + EXTI1_IRQn, + EXTI2_TS_IRQn, + EXTI3_IRQn, EXTI4_IRQn, - EXTI9_5_IRQn, + EXTI9_5_IRQn, EXTI15_10_IRQn }; #else diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index 806c777dab..29620fbe11 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -199,7 +199,7 @@ static bool m25p16_readIdentification() bool m25p16_init() { -#ifdef M25P16_CS_PIN +#ifdef M25P16_CS_PIN m25p16CsPin = IOGetByTag(IO_TAG(M25P16_CS_PIN)); #endif IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0); diff --git a/src/main/drivers/inverter.c b/src/main/drivers/inverter.c index fbbff6ffd4..967c87680a 100644 --- a/src/main/drivers/inverter.c +++ b/src/main/drivers/inverter.c @@ -20,7 +20,7 @@ #include "platform.h" -#ifdef INVERTER +#ifdef INVERTER #include "io.h" #include "io_impl.h" diff --git a/src/main/drivers/io.h b/src/main/drivers/io.h index 07c53a2032..af9deca810 100644 --- a/src/main/drivers/io.h +++ b/src/main/drivers/io.h @@ -52,7 +52,7 @@ typedef uint8_t ioConfig_t; // packed IO configuration #define IO_CONFIG(mode, speed, otype, pupd) ((mode) | ((speed) << 2) | ((otype) << 4) | ((pupd) << 5)) #define IOCFG_OUT_PP IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) // TODO -#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) +#define IOCFG_OUT_PP_25 IO_CONFIG(GPIO_Mode_OUT, GPIO_Speed_25MHz, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_OUT_OD IO_CONFIG(GPIO_Mode_OUT, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_NOPULL) #define IOCFG_AF_PP_PD IO_CONFIG(GPIO_Mode_AF, 0, GPIO_OType_PP, GPIO_PuPd_DOWN) diff --git a/src/main/drivers/io_impl.h b/src/main/drivers/io_impl.h index 1b3cca2bcf..0c880fd78d 100644 --- a/src/main/drivers/io_impl.h +++ b/src/main/drivers/io_impl.h @@ -12,7 +12,7 @@ typedef struct ioRec_s { GPIO_TypeDef *gpio; uint16_t pin; resourceOwner_t owner; - resourceType_t resource; + resourceType_t resource; uint8_t index; } ioRec_t; @@ -26,7 +26,7 @@ int IO_GPIO_PortSource(IO_t io); #if defined(STM32F3) || defined(STM32F4) int IO_EXTI_PortSourceGPIO(IO_t io); -int IO_EXTI_PinSource(IO_t io); +int IO_EXTI_PinSource(IO_t io); #endif GPIO_TypeDef* IO_GPIO(IO_t io); diff --git a/src/main/drivers/light_led.c b/src/main/drivers/light_led.c index 5fe73a1664..a6b2a6892e 100644 --- a/src/main/drivers/light_led.c +++ b/src/main/drivers/light_led.c @@ -27,12 +27,12 @@ static const IO_t leds[] = { DEFIO_IO(LED0), #else DEFIO_IO(NONE), -#endif +#endif #ifdef LED1 DEFIO_IO(LED1), #else DEFIO_IO(NONE), -#endif +#endif #ifdef LED2 DEFIO_IO(LED2), #else @@ -78,15 +78,14 @@ uint8_t ledPolarity = 0 #endif ; -uint8_t ledOffset = 0; +static uint8_t ledOffset = 0; void ledInit(bool alternative_led) { - uint32_t i; - #if defined(LED0_A) || defined(LED1_A) || defined(LED2_A) - if (alternative_led) + if (alternative_led) { ledOffset = LED_NUMBER; + } #else UNUSED(alternative_led); #endif @@ -95,7 +94,7 @@ void ledInit(bool alternative_led) LED1_OFF; LED2_OFF; - for (i = 0; i < LED_NUMBER; i++) { + for (int 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); @@ -114,6 +113,6 @@ void ledToggle(int led) void ledSet(int led, bool on) { - bool inverted = (1 << (led + ledOffset)) & ledPolarity; + const bool inverted = (1 << (led + ledOffset)) & ledPolarity; IOWrite(leds[led + ledOffset], on ? inverted : !inverted); } diff --git a/src/main/drivers/light_ws2811strip_stm32f4xx.c b/src/main/drivers/light_ws2811strip_stm32f4xx.c index 3a888bd21b..377954ce99 100644 --- a/src/main/drivers/light_ws2811strip_stm32f4xx.c +++ b/src/main/drivers/light_ws2811strip_stm32f4xx.c @@ -31,8 +31,8 @@ #ifdef LED_STRIP -#if !defined(WS2811_PIN) -#define WS2811_PIN PA0 +#if !defined(WS2811_PIN) +#define WS2811_PIN PA0 #define WS2811_TIMER TIM5 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER #define WS2811_DMA_STREAM DMA1_Stream2 diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c index 035d665f34..82f3f29af9 100644 --- a/src/main/drivers/max7456.c +++ b/src/main/drivers/max7456.c @@ -157,7 +157,7 @@ void max7456_dma_irq_handler(dmaChannelDescriptor_t* descriptor) { } #endif -void max7456_init(uint8_t video_system) +void max7456_init(uint8_t video_system) { uint8_t max_screen_rows; uint8_t srdata = 0; diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c index 13f01eac42..d6f41808cb 100755 --- a/src/main/drivers/pwm_mapping.c +++ b/src/main/drivers/pwm_mapping.c @@ -30,11 +30,6 @@ #include "pwm_rx.h" #include "pwm_mapping.h" -void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate); -void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); -void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse); -void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); - /* Configuration maps @@ -100,7 +95,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) int channelIndex = 0; memset(&pwmOutputConfiguration, 0, sizeof(pwmOutputConfiguration)); - + // this is pretty hacky shit, but it will do for now. array of 4 config maps, [ multiPWM multiPPM airPWM airPPM ] if (init->airplane) i = 2; // switch to air hardware config @@ -265,7 +260,7 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) if (init->useChannelForwarding && !init->airplane) { #if defined(NAZE) && defined(WS2811_TIMER) // if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14 - if (init->useLEDStrip) { + if (init->useLEDStrip) { if (timerIndex >= PWM13 && timerIndex <= PWM14) { type = MAP_TO_SERVO_OUTPUT; } @@ -313,14 +308,14 @@ pwmOutputConfiguration_t *pwmInit(drv_pwm_config_t *init) } #endif if (init->useFastPwm) { - pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->pwmProtocolType, init->motorPwmRate, init->idlePulse); - pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_ONESHOT|PWM_PF_OUTPUT_PROTOCOL_PWM ; + pwmFastPwmMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse, init->pwmProtocolType); + pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_OUTPUT_PROTOCOL_ONESHOT; } else if (init->pwmProtocolType == PWM_TYPE_BRUSHED) { pwmBrushedMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate); - pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_MOTOR_MODE_BRUSHED | PWM_PF_OUTPUT_PROTOCOL_PWM; + pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM | PWM_PF_MOTOR_MODE_BRUSHED; } else { pwmBrushlessMotorConfig(timerHardwarePtr, pwmOutputConfiguration.motorCount, init->motorPwmRate, init->idlePulse); - pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM ; + pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].flags = PWM_PF_MOTOR | PWM_PF_OUTPUT_PROTOCOL_PWM; } pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].index = pwmOutputConfiguration.motorCount; pwmOutputConfiguration.portConfigurations[pwmOutputConfiguration.outputCount].timerHardware = timerHardwarePtr; diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h index ffb5540995..5a3f402e97 100644 --- a/src/main/drivers/pwm_mapping.h +++ b/src/main/drivers/pwm_mapping.h @@ -30,24 +30,8 @@ #error Invalid motor/servo/port configuration #endif -#define PULSE_1MS (1000) // 1ms pulse width -#define MAX_INPUTS 8 #define PWM_TIMER_MHZ 1 -#if defined(STM32F40_41xxx) // must be multiples of timer clock -#define ONESHOT42_TIMER_MHZ 21 -#define ONESHOT125_TIMER_MHZ 12 -#define PWM_BRUSHED_TIMER_MHZ 21 -#define MULTISHOT_TIMER_MHZ 84 -#else -#define PWM_BRUSHED_TIMER_MHZ 24 -#define MULTISHOT_TIMER_MHZ 72 -#define ONESHOT42_TIMER_MHZ 24 -#define ONESHOT125_TIMER_MHZ 8 -#endif - -#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5) -#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f) typedef struct sonarIOConfig_s { ioTag_t triggerTag; @@ -133,7 +117,7 @@ enum { PWM13, PWM14, PWM15, - PWM16, + PWM16, PWM17, PWM18, PWM19, diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 056ee17faa..ecd0447a9a 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -17,21 +17,31 @@ #include #include - -#include #include #include "platform.h" #include "io.h" #include "timer.h" - -#include "flight/failsafe.h" // FIXME dependency into the main code from a driver - #include "pwm_mapping.h" - #include "pwm_output.h" +#if defined(STM32F40_41xxx) // must be multiples of timer clock +#define ONESHOT125_TIMER_MHZ 12 +#define ONESHOT42_TIMER_MHZ 21 +#define MULTISHOT_TIMER_MHZ 84 +#define PWM_BRUSHED_TIMER_MHZ 21 +#else +#define ONESHOT125_TIMER_MHZ 8 +#define ONESHOT42_TIMER_MHZ 24 +#define MULTISHOT_TIMER_MHZ 72 +#define PWM_BRUSHED_TIMER_MHZ 24 +#endif + +#define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5) +#define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f) + + typedef void (*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors typedef struct { @@ -52,6 +62,8 @@ static pwmOutputPort_t *servos[MAX_PWM_SERVOS]; static uint8_t allocatedOutputPortCount = 0; static bool pwmMotorsEnabled = true; + + static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t ouputPolarity) { TIM_OCInitTypeDef TIM_OCInitStructure; @@ -65,22 +77,22 @@ static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8 TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set; switch (channel) { - case TIM_Channel_1: - TIM_OC1Init(tim, &TIM_OCInitStructure); - TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable); - break; - case TIM_Channel_2: - TIM_OC2Init(tim, &TIM_OCInitStructure); - TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable); - break; - case TIM_Channel_3: - TIM_OC3Init(tim, &TIM_OCInitStructure); - TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable); - break; - case TIM_Channel_4: - TIM_OC4Init(tim, &TIM_OCInitStructure); - TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable); - break; + case TIM_Channel_1: + TIM_OC1Init(tim, &TIM_OCInitStructure); + TIM_OC1PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_2: + TIM_OC2Init(tim, &TIM_OCInitStructure); + TIM_OC2PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_3: + TIM_OC3Init(tim, &TIM_OCInitStructure); + TIM_OC3PreloadConfig(tim, TIM_OCPreload_Enable); + break; + case TIM_Channel_4: + TIM_OC4Init(tim, &TIM_OCInitStructure); + TIM_OC4PreloadConfig(tim, TIM_OCPreload_Enable); + break; } } @@ -90,7 +102,7 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 configTimeBase(timerHardware->tim, period, mhz); - IO_t io = IOGetByTag(timerHardware->tag); + const IO_t io = IOGetByTag(timerHardware->tag); IOInit(io, OWNER_MOTOR, RESOURCE_OUTPUT, allocatedOutputPortCount); IOConfigGPIO(io, IOCFG_AF_PP); @@ -102,24 +114,24 @@ static pwmOutputPort_t *pwmOutConfig(const timerHardware_t *timerHardware, uint8 TIM_Cmd(timerHardware->tim, ENABLE); switch (timerHardware->channel) { - case TIM_Channel_1: - p->ccr = &timerHardware->tim->CCR1; - break; - case TIM_Channel_2: - p->ccr = &timerHardware->tim->CCR2; - break; - case TIM_Channel_3: - p->ccr = &timerHardware->tim->CCR3; - break; - case TIM_Channel_4: - p->ccr = &timerHardware->tim->CCR4; - break; + case TIM_Channel_1: + p->ccr = &timerHardware->tim->CCR1; + break; + case TIM_Channel_2: + p->ccr = &timerHardware->tim->CCR2; + break; + case TIM_Channel_3: + p->ccr = &timerHardware->tim->CCR3; + break; + case TIM_Channel_4: + p->ccr = &timerHardware->tim->CCR4; + break; } p->period = period; p->tim = timerHardware->tim; *p->ccr = 0; - + return p; } @@ -133,16 +145,16 @@ static void pwmWriteStandard(uint8_t index, uint16_t value) *motors[index]->ccr = value; } -static void pwmWriteOneShot42(uint8_t index, uint16_t value) -{ - *motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f)); -} - static void pwmWriteOneShot125(uint8_t index, uint16_t value) { *motors[index]->ccr = lrintf((float)(value * ONESHOT125_TIMER_MHZ/8.0f)); } +static void pwmWriteOneShot42(uint8_t index, uint16_t value) +{ + *motors[index]->ccr = lrintf((float)(value * ONESHOT42_TIMER_MHZ/24.0f)); +} + static void pwmWriteMultiShot(uint8_t index, uint16_t value) { *motors[index]->ccr = lrintf(((float)(value-1000) * MULTISHOT_20US_MULT) + MULTISHOT_5US_PW); @@ -150,15 +162,14 @@ static void pwmWriteMultiShot(uint8_t index, uint16_t value) void pwmWriteMotor(uint8_t index, uint16_t value) { - if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) + if (motors[index] && index < MAX_MOTORS && pwmMotorsEnabled) { motors[index]->pwmWritePtr(index, value); + } } void pwmShutdownPulsesForAllMotors(uint8_t motorCount) { - uint8_t index; - - for(index = 0; index < motorCount; index++){ + for(int index = 0; index < motorCount; index++){ // Set the compare register to 0, which stops the output pulsing if the timer overflows *motors[index]->ccr = 0; } @@ -176,17 +187,14 @@ void pwmEnableMotors(void) void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) { - uint8_t index; TIM_TypeDef *lastTimerPtr = NULL; - for (index = 0; index < motorCount; index++) { - + for (int index = 0; index < motorCount; index++) { // Force the timer to overflow if it's the first motor to output, or if we change timers if (motors[index]->tim != lastTimerPtr) { lastTimerPtr = motors[index]->tim; timerForceOverflow(motors[index]->tim); } - // Set the compare register to 0, which stops the output pulsing if the timer overflows before the main loop completes again. // This compare register will be set to the output value on the next main loop. *motors[index]->ccr = 0; @@ -195,44 +203,46 @@ void pwmCompleteOneshotMotorUpdate(uint8_t motorCount) void pwmBrushedMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate) { - uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; + const uint32_t hz = PWM_BRUSHED_TIMER_MHZ * 1000000; motors[motorIndex] = pwmOutConfig(timerHardware, PWM_BRUSHED_TIMER_MHZ, hz / motorPwmRate, 0); motors[motorIndex]->pwmWritePtr = pwmWriteBrushed; } void pwmBrushlessMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse) { - uint32_t hz = PWM_TIMER_MHZ * 1000000; + const uint32_t hz = PWM_TIMER_MHZ * 1000000; motors[motorIndex] = pwmOutConfig(timerHardware, PWM_TIMER_MHZ, hz / motorPwmRate, idlePulse); motors[motorIndex]->pwmWritePtr = pwmWriteStandard; } -void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t fastPwmProtocolType, uint16_t motorPwmRate, uint16_t idlePulse) +void pwmFastPwmMotorConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType) { uint32_t timerMhzCounter; + pwmWriteFuncPtr pwmWritePtr; switch (fastPwmProtocolType) { - default: - case (PWM_TYPE_ONESHOT125): - timerMhzCounter = ONESHOT125_TIMER_MHZ; - break; - case (PWM_TYPE_ONESHOT42): - timerMhzCounter = ONESHOT42_TIMER_MHZ; - break; - case (PWM_TYPE_MULTISHOT): - timerMhzCounter = MULTISHOT_TIMER_MHZ; + default: + case (PWM_TYPE_ONESHOT125): + timerMhzCounter = ONESHOT125_TIMER_MHZ; + pwmWritePtr = pwmWriteOneShot125; + break; + case (PWM_TYPE_ONESHOT42): + timerMhzCounter = ONESHOT42_TIMER_MHZ; + pwmWritePtr = pwmWriteOneShot42; + break; + case (PWM_TYPE_MULTISHOT): + timerMhzCounter = MULTISHOT_TIMER_MHZ; + pwmWritePtr = pwmWriteMultiShot; + break; } if (motorPwmRate > 0) { - uint32_t hz = timerMhzCounter * 1000000; + const uint32_t hz = timerMhzCounter * 1000000; motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, hz / motorPwmRate, idlePulse); } else { motors[motorIndex] = pwmOutConfig(timerHardware, timerMhzCounter, 0xFFFF, 0); } - - motors[motorIndex]->pwmWritePtr = (fastPwmProtocolType == PWM_TYPE_MULTISHOT) ? pwmWriteMultiShot : - ((fastPwmProtocolType == PWM_TYPE_ONESHOT125) ? pwmWriteOneShot125 : - pwmWriteOneShot42); + motors[motorIndex]->pwmWritePtr = pwmWritePtr; } #ifdef USE_SERVOS @@ -243,7 +253,8 @@ void pwmServoConfig(const timerHardware_t *timerHardware, uint8_t servoIndex, ui void pwmWriteServo(uint8_t index, uint16_t value) { - if (servos[index] && index < MAX_SERVOS) + if (servos[index] && index < MAX_SERVOS) { *servos[index]->ccr = value; + } } #endif diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index c89e7fa802..b9bc62c68d 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -25,6 +25,12 @@ typedef enum { PWM_TYPE_BRUSHED } motorPwmProtocolTypes_e; +struct timerHardware_s; +void pwmBrushedMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate); +void pwmBrushlessMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse); +void pwmFastPwmMotorConfig(const struct timerHardware_s *timerHardware, uint8_t motorIndex, uint16_t motorPwmRate, uint16_t idlePulse, uint8_t fastPwmProtocolType); +void pwmServoConfig(const struct timerHardware_s *timerHardware, uint8_t servoIndex, uint16_t servoPwmRate, uint16_t servoCenterPulse); + void pwmWriteMotor(uint8_t index, uint16_t value); void pwmShutdownPulsesForAllMotors(uint8_t motorCount); void pwmCompleteOneshotMotorUpdate(uint8_t motorCount); diff --git a/src/main/drivers/resource.h b/src/main/drivers/resource.h index a177dab1da..f9430d2844 100644 --- a/src/main/drivers/resource.h +++ b/src/main/drivers/resource.h @@ -1,7 +1,7 @@ #pragma once -#define RESOURCE_INDEX(x) x + 1 +#define RESOURCE_INDEX(x) (x + 1) typedef enum { OWNER_FREE = 0, diff --git a/src/main/drivers/sdcard.c b/src/main/drivers/sdcard.c index d940ddc857..878d5eacf6 100644 --- a/src/main/drivers/sdcard.c +++ b/src/main/drivers/sdcard.c @@ -126,7 +126,7 @@ void sdcardInsertionDetectDeinit(void) #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0); - IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); + IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING); #endif } @@ -135,7 +135,7 @@ void sdcardInsertionDetectInit(void) #ifdef SDCARD_DETECT_PIN sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN)); IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0); - IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); + IOConfigGPIO(sdCardDetectPin, IOCFG_IPU); #endif } diff --git a/src/main/drivers/serial_uart_stm32f30x.c b/src/main/drivers/serial_uart_stm32f30x.c index 09b6663e86..852a60831e 100644 --- a/src/main/drivers/serial_uart_stm32f30x.c +++ b/src/main/drivers/serial_uart_stm32f30x.c @@ -114,8 +114,8 @@ static void handleUsartTxDma(dmaChannelDescriptor_t* descriptor) void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, uint8_t af, uint8_t index) { if (options & SERIAL_BIDIR) { - ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, - (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, + ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, + (options & SERIAL_INVERTED) ? GPIO_OType_PP : GPIO_OType_OD, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP ); diff --git a/src/main/drivers/serial_uart_stm32f4xx.c b/src/main/drivers/serial_uart_stm32f4xx.c index 97f087a510..f79a99ae6e 100644 --- a/src/main/drivers/serial_uart_stm32f4xx.c +++ b/src/main/drivers/serial_uart_stm32f4xx.c @@ -64,17 +64,17 @@ typedef struct uartDevice_s { //static uartPort_t uartPort[MAX_UARTS]; #ifdef USE_UART1 -static uartDevice_t uart1 = -{ +static uartDevice_t uart1 = +{ .DMAChannel = DMA_Channel_4, .txDMAStream = DMA2_Stream7, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA2_Stream5, #endif - .dev = USART1, - .rx = IO_TAG(UART1_RX_PIN), - .tx = IO_TAG(UART1_TX_PIN), - .af = GPIO_AF_USART1, + .dev = USART1, + .rx = IO_TAG(UART1_RX_PIN), + .tx = IO_TAG(UART1_TX_PIN), + .af = GPIO_AF_USART1, #ifdef UART1_AHB1_PERIPHERALS .rcc_ahb1 = UART1_AHB1_PERIPHERALS, #endif @@ -87,17 +87,17 @@ static uartDevice_t uart1 = #endif #ifdef USE_UART2 -static uartDevice_t uart2 = -{ +static uartDevice_t uart2 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART2_RX_DMA .rxDMAStream = DMA1_Stream5, #endif .txDMAStream = DMA1_Stream6, - .dev = USART2, - .rx = IO_TAG(UART2_RX_PIN), - .tx = IO_TAG(UART2_TX_PIN), - .af = GPIO_AF_USART2, + .dev = USART2, + .rx = IO_TAG(UART2_RX_PIN), + .tx = IO_TAG(UART2_TX_PIN), + .af = GPIO_AF_USART2, #ifdef UART2_AHB1_PERIPHERALS .rcc_ahb1 = UART2_AHB1_PERIPHERALS, #endif @@ -110,17 +110,17 @@ static uartDevice_t uart2 = #endif #ifdef USE_UART3 -static uartDevice_t uart3 = -{ +static uartDevice_t uart3 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART3_RX_DMA .rxDMAStream = DMA1_Stream1, #endif .txDMAStream = DMA1_Stream3, - .dev = USART3, - .rx = IO_TAG(UART3_RX_PIN), - .tx = IO_TAG(UART3_TX_PIN), - .af = GPIO_AF_USART3, + .dev = USART3, + .rx = IO_TAG(UART3_RX_PIN), + .tx = IO_TAG(UART3_TX_PIN), + .af = GPIO_AF_USART3, #ifdef UART3_AHB1_PERIPHERALS .rcc_ahb1 = UART3_AHB1_PERIPHERALS, #endif @@ -133,17 +133,17 @@ static uartDevice_t uart3 = #endif #ifdef USE_UART4 -static uartDevice_t uart4 = -{ +static uartDevice_t uart4 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream2, #endif .txDMAStream = DMA1_Stream4, - .dev = UART4, - .rx = IO_TAG(UART4_RX_PIN), - .tx = IO_TAG(UART4_TX_PIN), - .af = GPIO_AF_UART4, + .dev = UART4, + .rx = IO_TAG(UART4_RX_PIN), + .tx = IO_TAG(UART4_TX_PIN), + .af = GPIO_AF_UART4, #ifdef UART4_AHB1_PERIPHERALS .rcc_ahb1 = UART4_AHB1_PERIPHERALS, #endif @@ -156,17 +156,17 @@ static uartDevice_t uart4 = #endif #ifdef USE_UART5 -static uartDevice_t uart5 = -{ +static uartDevice_t uart5 = +{ .DMAChannel = DMA_Channel_4, #ifdef USE_UART1_RX_DMA .rxDMAStream = DMA1_Stream0, #endif .txDMAStream = DMA2_Stream7, - .dev = UART5, - .rx = IO_TAG(UART5_RX_PIN), - .tx = IO_TAG(UART5_TX_PIN), - .af = GPIO_AF_UART5, + .dev = UART5, + .rx = IO_TAG(UART5_RX_PIN), + .tx = IO_TAG(UART5_TX_PIN), + .af = GPIO_AF_UART5, #ifdef UART5_AHB1_PERIPHERALS .rcc_ahb1 = UART5_AHB1_PERIPHERALS, #endif @@ -179,17 +179,17 @@ static uartDevice_t uart5 = #endif #ifdef USE_UART6 -static uartDevice_t uart6 = -{ +static uartDevice_t uart6 = +{ .DMAChannel = DMA_Channel_5, #ifdef USE_UART6_RX_DMA .rxDMAStream = DMA2_Stream1, #endif .txDMAStream = DMA2_Stream6, - .dev = USART6, - .rx = IO_TAG(UART6_RX_PIN), - .tx = IO_TAG(UART6_TX_PIN), - .af = GPIO_AF_USART6, + .dev = USART6, + .rx = IO_TAG(UART6_RX_PIN), + .tx = IO_TAG(UART6_TX_PIN), + .af = GPIO_AF_USART6, #ifdef UART6_AHB1_PERIPHERALS .rcc_ahb1 = UART6_AHB1_PERIPHERALS, #endif @@ -344,7 +344,7 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af); } - if (mode & MODE_RX) { + if (mode & MODE_RX) { IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device)); IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af); } @@ -376,6 +376,7 @@ void USART1_IRQHandler(void) uartPort_t *s = &(uartHardwareMap[UARTDEV_1]->port); uartIrqHandler(s); } + #endif #ifdef USE_UART2 diff --git a/src/main/drivers/system_stm32f10x.c b/src/main/drivers/system_stm32f10x.c index f5eab63fac..3e33c545b8 100644 --- a/src/main/drivers/system_stm32f10x.c +++ b/src/main/drivers/system_stm32f10x.c @@ -36,7 +36,7 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC diff --git a/src/main/drivers/system_stm32f30x.c b/src/main/drivers/system_stm32f30x.c index e0aaad1bb0..fb30936968 100644 --- a/src/main/drivers/system_stm32f30x.c +++ b/src/main/drivers/system_stm32f30x.c @@ -34,7 +34,7 @@ void systemReset(void) SCB->AIRCR = AIRCR_VECTKEY_MASK | (uint32_t)0x04; } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { // 1FFFF000 -> 20000200 -> SP // 1FFFF004 -> 1FFFF021 -> PC diff --git a/src/main/drivers/system_stm32f4xx.c b/src/main/drivers/system_stm32f4xx.c index 8101974377..5c09ebdf6a 100644 --- a/src/main/drivers/system_stm32f4xx.c +++ b/src/main/drivers/system_stm32f4xx.c @@ -41,7 +41,7 @@ void systemReset(void) NVIC_SystemReset(); } -void systemResetToBootloader(void) +void systemResetToBootloader(void) { if (mpuConfiguration.reset) mpuConfiguration.reset(); diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c index a3b3624371..15e36cce3f 100755 --- a/src/main/drivers/timer.c +++ b/src/main/drivers/timer.c @@ -253,7 +253,7 @@ void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint8_t mhz) } #else TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / ((uint32_t)mhz * 1000000)) - 1; -#endif +#endif TIM_TimeBaseStructure.TIM_ClockDivision = 0; TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up; diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 26078d4517..e11f5a8974 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -87,7 +87,7 @@ typedef struct timerHardware_s { } timerHardware_t; enum { - TIMER_OUTPUT_ENABLED = 0x01, + TIMER_OUTPUT_ENABLED = 0x01, TIMER_OUTPUT_INVERTED = 0x02 }; diff --git a/src/main/drivers/timer_stm32f10x.c b/src/main/drivers/timer_stm32f10x.c index 09ef0efc8c..1a5085e63a 100644 --- a/src/main/drivers/timer_stm32f10x.c +++ b/src/main/drivers/timer_stm32f10x.c @@ -23,10 +23,10 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { { .TIMx = TIM8, .rcc = RCC_APB1(TIM8) }, { .TIMx = TIM9, .rcc = RCC_APB2(TIM9) }, { .TIMx = TIM10, .rcc = RCC_APB2(TIM10) }, - { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, + { .TIMx = TIM11, .rcc = RCC_APB2(TIM11) }, { .TIMx = TIM12, .rcc = RCC_APB1(TIM12) }, { .TIMx = TIM13, .rcc = RCC_APB1(TIM13) }, - { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, + { .TIMx = TIM14, .rcc = RCC_APB1(TIM14) }, #endif }; diff --git a/src/main/drivers/timer_stm32f30x.c b/src/main/drivers/timer_stm32f30x.c index 033aa316c4..04069b20c3 100644 --- a/src/main/drivers/timer_stm32f30x.c +++ b/src/main/drivers/timer_stm32f30x.c @@ -54,7 +54,7 @@ const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { */ #define CCMR_OFFSET ((uint16_t)0x0018) #define CCMR_OC13M_MASK ((uint32_t)0xFFFEFF8F) -#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) +#define CCMR_OC24M_MASK ((uint32_t)0xFEFF8FFF) void TIM_SelectOCxM_NoDisable(TIM_TypeDef* TIMx, uint16_t TIM_Channel, uint32_t TIM_OCMode) { diff --git a/src/main/drivers/usb_io.c b/src/main/drivers/usb_io.c index d8a7206109..8520ef8e54 100644 --- a/src/main/drivers/usb_io.c +++ b/src/main/drivers/usb_io.c @@ -66,7 +66,7 @@ bool usbCableIsInserted(void) void usbGenerateDisconnectPulse(void) { /* Pull down PA12 to create USB disconnect pulse */ - IO_t usbPin = IOGetByTag(IO_TAG(PA12)); + IO_t usbPin = IOGetByTag(IO_TAG(PA12)); IOConfigGPIO(usbPin, IOCFG_OUT_OD); IOHi(usbPin); diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index ee540da60e..93ffa83ecb 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -179,7 +179,7 @@ void rtc6705SetFreq(uint16_t freq) uint32_t val_a = ((((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) % RTC6705_SET_FDIV) / RTC6705_SET_NDIV; //Casts required to make sure correct math (large numbers) uint32_t val_n = (((uint64_t)freq*(uint64_t)RTC6705_SET_DIVMULT*(uint64_t)RTC6705_SET_R)/(uint64_t)RTC6705_SET_DIVMULT) / RTC6705_SET_FDIV; //Casts required to make sure correct math (large numbers) - + val_hex |= RTC6705_SET_WRITE; val_hex |= (val_a << 5); val_hex |= (val_n << 12); diff --git a/src/main/flight/mixer.c b/src/main/flight/mixer.c index b851fd355e..8db1443d0c 100755 --- a/src/main/flight/mixer.c +++ b/src/main/flight/mixer.c @@ -956,7 +956,7 @@ void filterServos(void) if (mixerConfig->servo_lowpass_enable) { for (servoIdx = 0; servoIdx < MAX_SUPPORTED_SERVOS; servoIdx++) { if (!servoFilterIsSet) { - biquadFilterInit(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime); + biquadFilterInitLPF(&servoFilter[servoIdx], mixerConfig->servo_lowpass_freq, targetPidLooptime); servoFilterIsSet = true; } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index b0dee87496..25ca7c40aa 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -71,12 +71,12 @@ static void pidInteger(const pidProfile_t *pidProfile, uint16_t max_angle_inclin pidControllerFuncPtr pid_controller = pidInteger; // which pid controller are we using -void setTargetPidLooptime(uint8_t pidProcessDenom) +void setTargetPidLooptime(uint8_t pidProcessDenom) { targetPidLooptime = gyro.targetLooptime * pidProcessDenom; } -uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) +uint16_t getDynamicKi(int axis, const pidProfile_t *pidProfile, int32_t angleRate) { uint16_t dynamicKi; uint16_t resetRate; diff --git a/src/main/io/gps.c b/src/main/io/gps.c index cf8e141aec..af963adcdc 100755 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -1069,7 +1069,7 @@ static void gpsHandlePassthrough(uint8_t data) #endif } - + void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort) { diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c index 68896a9a89..f354577f87 100644 --- a/src/main/io/rc_controls.c +++ b/src/main/io/rc_controls.c @@ -672,8 +672,8 @@ void processRcAdjustments(controlRateConfig_t *controlRateConfig, rxConfig_t *rx applyStepAdjustment(controlRateConfig, adjustmentFunction, delta); } else if (adjustmentState->config->mode == ADJUSTMENT_MODE_SELECT) { - uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); - uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; + uint16_t rangeWidth = ((2100 - 900) / adjustmentState->config->data.selectConfig.switchPositions); + uint8_t position = (constrain(rcData[channelIndex], 900, 2100 - 1) - 900) / rangeWidth; applySelectAdjustment(adjustmentFunction, position); } diff --git a/src/main/io/serial.c b/src/main/io/serial.c index 890e218280..15aae3e469 100644 --- a/src/main/io/serial.c +++ b/src/main/io/serial.c @@ -465,7 +465,7 @@ static void nopConsumer(uint8_t data) arbitrary serial passthrough "proxy". Optional callbacks can be given to allow for specialized data processing. */ -void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer +void serialPassthrough(serialPort_t *left, serialPort_t *right, serialConsumer *leftC, serialConsumer *rightC) { waitForSerialPortToFinishTransmitting(left); diff --git a/src/main/io/serial_4way_stk500v2.c b/src/main/io/serial_4way_stk500v2.c index 9c81c89317..1c32e2c6bb 100644 --- a/src/main/io/serial_4way_stk500v2.c +++ b/src/main/io/serial_4way_stk500v2.c @@ -16,7 +16,7 @@ * Author: 4712 * have a look at https://github.com/sim-/tgy/blob/master/boot.inc * for info about the stk500v2 implementation - */ + */ #include #include #include diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 283f905c09..4904764252 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -112,13 +112,14 @@ static void cliRxFail(char *cmdline); static void cliAdjustmentRange(char *cmdline); static void cliMotorMix(char *cmdline); static void cliDefaults(char *cmdline); -void cliDfu(char *cmdLine); +void cliDfu(char *cmdLine); static void cliDump(char *cmdLine); void cliDumpProfile(uint8_t profileIndex); void cliDumpRateProfile(uint8_t rateProfileIndex) ; static void cliExit(char *cmdline); static void cliFeature(char *cmdline); static void cliMotor(char *cmdline); +static void cliName(char *cmdline); static void cliPlaySound(char *cmdline); static void cliProfile(char *cmdline); static void cliRateProfile(char *cmdline); @@ -340,6 +341,7 @@ const clicmd_t cmdTable[] = { #ifdef VTX CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx), #endif + CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName), }; #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t)) @@ -451,6 +453,7 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = { "MIXER", "AIRMODE", "PIDLOOP", + "NOTCH", }; #ifdef OSD static const char * const lookupTableOsdType[] = { @@ -486,7 +489,7 @@ typedef enum { TABLE_GPS_SBAS_MODE, #endif #ifdef BLACKBOX - TABLE_BLACKBOX_DEVICE, + TABLE_BLACKBOX_DEVICE, #endif TABLE_CURRENT_SENSOR, TABLE_GIMBAL_MODE, @@ -696,6 +699,8 @@ const clivalue_t valueTable[] = { { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } }, { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } }, + { "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } }, + { "gyro_notch_q", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_notch_q, .config.minmax = { 1, 100 } }, { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } }, { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } }, { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } }, @@ -1941,7 +1946,7 @@ static void cliDump(char *cmdline) dumpMask = DUMP_PROFILE; // only } if (strcasecmp(cmdline, "rates") == 0) { - dumpMask = DUMP_RATES; + dumpMask = DUMP_RATES; } if (strcasecmp(cmdline, "all") == 0) { @@ -1953,6 +1958,8 @@ static void cliDump(char *cmdline) cliPrint("\r\n# version\r\n"); cliVersion(NULL); + cliPrint("\r\n# name\r\n"); + cliName(NULL); cliPrint("\r\n# dump master\r\n"); cliPrint("\r\n# mixer\r\n"); @@ -2494,6 +2501,18 @@ static void cliMotor(char *cmdline) cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]); } +static void cliName(char *cmdline) +{ + uint32_t len = strlen(cmdline); + if (len > 0) { + memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name)); + strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH)); + } + cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-"); + + return; +} + static void cliPlaySound(char *cmdline) { #if FLASH_SIZE <= 64 @@ -2681,7 +2700,7 @@ static void cliPrintVar(const clivalue_t *var, uint32_t full) break; } } -static void cliPrintVarRange(const clivalue_t *var) +static void cliPrintVarRange(const clivalue_t *var) { switch (var->type & VALUE_MODE_MASK) { case (MODE_DIRECT): { @@ -2693,7 +2712,7 @@ static void cliPrintVarRange(const clivalue_t *var) cliPrint("Allowed values:"); uint8_t i; for (i = 0; i < tableEntry->valueCount ; i++) { - if (i > 0) + if (i > 0) cliPrint(","); cliPrintf(" %s", tableEntry->values[i]); } @@ -2907,7 +2926,7 @@ static void cliStatus(char *cmdline) #ifdef USE_SDCARD cliSdInfo(NULL); -#endif +#endif } #ifndef SKIP_TASK_STATISTICS diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 80e4717fde..c21680f778 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -659,7 +659,7 @@ static uint32_t packFlightModeFlags(void) static bool processOutCommand(uint8_t cmdMSP) { uint32_t i; - + uint8_t len; #ifdef GPS uint8_t wp_no; int32_t lat = 0, lon = 0; @@ -750,6 +750,14 @@ static bool processOutCommand(uint8_t cmdMSP) serialize16(constrain(averageSystemLoadPercent, 0, 100)); break; + case MSP_NAME: + len = strlen(masterConfig.name); + headSerialReply(len); + for (uint8_t i=0; idataSize); i++) { + masterConfig.name[i] = read8(); + } + break; default: // we do not know how to handle the (valid) message, indicate error MSP $M! return false; diff --git a/src/main/io/serial_msp.h b/src/main/io/serial_msp.h index 1a63b2b20d..60d5a80d05 100644 --- a/src/main/io/serial_msp.h +++ b/src/main/io/serial_msp.h @@ -99,6 +99,10 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; #define MSP_BOARD_INFO 4 //out message #define MSP_BUILD_INFO 5 //out message +#define MSP_NAME 10 +#define MSP_SET_NAME 11 + + // // MSP commands for Cleanflight original features // @@ -147,6 +151,23 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; #define MSP_ARMING_CONFIG 61 //out message Returns auto_disarm_delay and disarm_kill_switch parameters #define MSP_SET_ARMING_CONFIG 62 //in message Sets auto_disarm_delay and disarm_kill_switch parameters +// +// Baseflight MSP commands (if enabled they exist in Cleanflight) +// +#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total) +#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP + +// FIXME - Provided for backwards compatibility with configurator code until configurator is updated. +// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead. +#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere +#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save + +#define MSP_REBOOT 68 //in message reboot settings + +// DEPRECATED - Use MSP_BUILD_INFO instead +#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion + + #define MSP_DATAFLASH_SUMMARY 70 //out message - get description of dataflash chip #define MSP_DATAFLASH_READ 71 //out message - get content of dataflash chip #define MSP_DATAFLASH_ERASE 72 //in message - erase dataflash chip @@ -177,22 +198,6 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; #define MSP_VTX_CONFIG 88 //in message Get vtx settings #define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings -// -// Baseflight MSP commands (if enabled they exist in Cleanflight) -// -#define MSP_RX_MAP 64 //out message get channel map (also returns number of channels total) -#define MSP_SET_RX_MAP 65 //in message set rx map, numchannels to set comes from MSP_RX_MAP - -// FIXME - Provided for backwards compatibility with configurator code until configurator is updated. -// DEPRECATED - DO NOT USE "MSP_BF_CONFIG" and MSP_SET_BF_CONFIG. In Cleanflight, isolated commands already exist and should be used instead. -#define MSP_BF_CONFIG 66 //out message baseflight-specific settings that aren't covered elsewhere -#define MSP_SET_BF_CONFIG 67 //in message baseflight-specific settings save - -#define MSP_REBOOT 68 //in message reboot settings - -// DEPRECATED - Use MSP_BUILD_INFO instead -#define MSP_BF_BUILD_INFO 69 //out message build date as well as some space for future expansion - // Betaflight Additional Commands #define MSP_PID_ADVANCED_CONFIG 90 #define MSP_SET_PID_ADVANCED_CONFIG 91 diff --git a/src/main/io/vtx.h b/src/main/io/vtx.h index 942a770547..fdd5e506f9 100644 --- a/src/main/io/vtx.h +++ b/src/main/io/vtx.h @@ -14,7 +14,7 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - + #pragma once #define VTX_BAND_MIN 1 diff --git a/src/main/main.c b/src/main/main.c index 8cf45ac7bb..0daf402768 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -313,7 +313,7 @@ void init(void) bool use_unsyncedPwm = masterConfig.use_unsyncedPwm; // Configurator feature abused for enabling Fast PWM - pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); + pwm_params.useFastPwm = (masterConfig.motor_pwm_protocol != PWM_TYPE_CONVENTIONAL && masterConfig.motor_pwm_protocol != PWM_TYPE_BRUSHED); pwm_params.pwmProtocolType = masterConfig.motor_pwm_protocol; pwm_params.motorPwmRate = masterConfig.motor_pwm_rate; pwm_params.idlePulse = masterConfig.escAndServoConfig.mincommand; diff --git a/src/main/rx/xbus.c b/src/main/rx/xbus.c index 0e68854897..bbf4848bb7 100644 --- a/src/main/rx/xbus.c +++ b/src/main/rx/xbus.c @@ -226,7 +226,7 @@ static void xBusUnpackRJ01Frame(void) uint8_t outerCrc = 0; uint8_t i = 0; - // When using the Align RJ01 receiver with + // When using the Align RJ01 receiver with // a MODE B setting in the radio (XG14 tested) // the MODE_B -frame is packed within some // at the moment unknown bytes before and after: @@ -234,7 +234,7 @@ static void xBusUnpackRJ01Frame(void) // Compared to a standard MODE B frame that only // contains the "middle" package. // Hence, at the moment, the unknown header and footer - // of the RJ01 MODEB packages are discarded. + // of the RJ01 MODEB packages are discarded. // However, the LAST byte (CRC_OUTER) is infact an 8-bit // CRC for the whole package, using the Dallas-One-Wire CRC // method. diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 5de9c3fce9..d8cc423c1a 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -190,7 +190,7 @@ void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) if (!accFilterInitialised) { if (accTargetLooptime) { /* Initialisation needs to happen once sample rate is known */ for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - biquadFilterInit(&accFilter[axis], accLpfCutHz, accTargetLooptime); + biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, accTargetLooptime); } accFilterInitialised = true; } diff --git a/src/main/sensors/battery.c b/src/main/sensors/battery.c index 59fa7ef9ae..53e7096480 100644 --- a/src/main/sensors/battery.c +++ b/src/main/sensors/battery.c @@ -70,7 +70,7 @@ static void updateBatteryVoltage(void) if (debugMode == DEBUG_BATTERY) debug[0] = vbatSample; if (!vbatFilterIsInitialised) { - biquadFilterInit(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update + biquadFilterInitLPF(&vbatFilter, VBATT_LPF_FREQ, 50000); //50HZ Update vbatFilterIsInitialised = true; } vbatSample = biquadFilterApply(&vbatFilter, vbatSample); @@ -91,7 +91,7 @@ void updateBattery(void) /* Actual battery state is calculated below, this is really BATTERY_PRESENT */ batteryState = BATTERY_OK; /* wait for VBatt to stabilise then we can calc number of cells - (using the filtered value takes a long time to ramp up) + (using the filtered value takes a long time to ramp up) We only do this on the ground so don't care if we do block, not worse than original code anyway*/ delay(VBATTERY_STABLE_DELAY); diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 4f425dc1d2..40a30ebb7c 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -27,12 +27,14 @@ #include "common/filter.h" #include "drivers/sensor.h" +#include "drivers/system.h" #include "drivers/accgyro.h" -#include "sensors/sensors.h" + #include "io/beeper.h" #include "io/statusindicator.h" -#include "sensors/boardalignment.h" +#include "sensors/sensors.h" +#include "sensors/boardalignment.h" #include "sensors/gyro.h" gyro_t gyro; // gyro access functions @@ -43,21 +45,27 @@ float gyroADCf[XYZ_AXIS_COUNT]; static int32_t gyroZero[XYZ_AXIS_COUNT] = { 0, 0, 0 }; static const gyroConfig_t *gyroConfig; -static biquadFilter_t gyroFilter[XYZ_AXIS_COUNT]; +static biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT]; +static biquadFilter_t gyroFilterNotch[XYZ_AXIS_COUNT]; +static uint16_t gyroSoftNotchHz; +static uint8_t gyroSoftNotchQ; static uint8_t gyroSoftLpfHz; static uint16_t calibratingG = 0; -void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz) +void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q) { gyroConfig = gyroConfigToUse; gyroSoftLpfHz = gyro_soft_lpf_hz; + gyroSoftNotchHz = gyro_soft_notch_hz; + gyroSoftNotchQ = gyro_soft_notch_q; } void gyroInit(void) { if (gyroSoftLpfHz && gyro.targetLooptime) { // Initialisation needs to happen once samplingrate is known for (int axis = 0; axis < 3; axis++) { - biquadFilterInit(&gyroFilter[axis], gyroSoftLpfHz, gyro.targetLooptime); + biquadFilterInit(&gyroFilterNotch[axis], gyroSoftNotchHz, gyro.targetLooptime, ((float) gyroSoftNotchQ) / 10, FILTER_NOTCH); + biquadFilterInitLPF(&gyroFilterLPF[axis], gyroSoftLpfHz, gyro.targetLooptime); } } } @@ -157,7 +165,17 @@ void gyroUpdate(void) if (gyroSoftLpfHz) { for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - gyroADCf[axis] = biquadFilterApply(&gyroFilter[axis], (float)gyroADC[axis]); + float sample = (float) gyroADC[axis]; + if (gyroSoftNotchHz) { + sample = biquadFilterApply(&gyroFilterNotch[axis], sample); + } + + if (debugMode == DEBUG_NOTCH && axis < 2){ + debug[axis*2 + 0] = gyroADC[axis]; + debug[axis*2 + 1] = lrintf(sample); + } + + gyroADCf[axis] = biquadFilterApply(&gyroFilterLPF[axis], sample);; gyroADC[axis] = lrintf(gyroADCf[axis]); } } else { diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 2239eb6816..4d2153fa0d 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -40,7 +40,7 @@ typedef struct gyroConfig_s { uint8_t gyroMovementCalibrationThreshold; // people keep forgetting that moving model while init results in wrong gyro offsets. and then they never reset gyro. so this is now on by default. } gyroConfig_t; -void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_lpf_hz); +void gyroUseConfig(const gyroConfig_t *gyroConfigToUse, uint8_t gyro_soft_lpf_hz, uint16_t gyro_soft_notch_hz, uint8_t gyro_soft_notch_q); void gyroSetCalibrationCycles(void); void gyroInit(void); void gyroUpdate(void); diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index eb206627b4..38d81a1f4f 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -89,7 +89,7 @@ const extiConfig_t *selectMPUIntExtiConfig(void) #if defined(MPU_INT_EXTI) static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; return &mpuIntExtiConfig; -#elif defined(USE_HARDWARE_REVISION_DETECTION) +#elif defined(USE_HARDWARE_REVISION_DETECTION) return selectMPUIntExtiConfigByHardwareRevision(); #else return NULL; @@ -118,9 +118,15 @@ static bool fakeGyroReadTemp(int16_t *tempData) return true; } + +static bool fakeGyroInitStatus(void) { + return true; +} + bool fakeGyroDetect(gyro_t *gyro) { gyro->init = fakeGyroInit; + gyro->intStatus = fakeGyroInitStatus; gyro->read = fakeGyroRead; gyro->temperature = fakeGyroReadTemp; gyro->scale = 1.0f / 16.4f; @@ -143,6 +149,7 @@ bool fakeAccDetect(acc_t *acc) { acc->init = fakeAccInit; acc->read = fakeAccRead; + acc->acc_1G = 512*8; acc->revisionCode = 0; return true; } @@ -584,10 +591,14 @@ void reconfigureAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig) } } -bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t accHardwareToUse, uint8_t magHardwareToUse, uint8_t baroHardwareToUse, int16_t magDeclinationFromConfig, uint8_t gyroLpf, uint8_t gyroSyncDenominator) +bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, + uint8_t accHardwareToUse, + uint8_t magHardwareToUse, + uint8_t baroHardwareToUse, + int16_t magDeclinationFromConfig, + uint8_t gyroLpf, + uint8_t gyroSyncDenominator) { - int16_t deg, min; - memset(&acc, 0, sizeof(acc)); memset(&gyro, 0, sizeof(gyro)); @@ -605,7 +616,6 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a detectAcc(accHardwareToUse); detectBaro(baroHardwareToUse); - // Now time to init things, acc first if (sensors(SENSOR_ACC)) { acc.acc_1G = 256; // set default @@ -623,9 +633,8 @@ bool sensorsAutodetect(sensorAlignmentConfig_t *sensorAlignmentConfig, uint8_t a // FIXME extract to a method to reduce dependencies, maybe move to sensors_compass.c if (sensors(SENSOR_MAG)) { // calculate magnetic declination - deg = magDeclinationFromConfig / 100; - min = magDeclinationFromConfig % 100; - + const int16_t deg = magDeclinationFromConfig / 100; + const int16_t min = magDeclinationFromConfig % 100; magneticDeclination = (deg + ((float)min * (1.0f / 60.0f))) * 10; // heading is in 0.1deg units } else { magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used. diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 3e60de5031..10bc3a49be 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -21,18 +21,16 @@ #define USE_CLI #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - -#define LED0 PB5 // Blue LED - PB5 +#define LED0 PB5 // Blue LED - PB5 -#define BEEPER PA0 - +#define BEEPER PA0 #define USABLE_TIMER_CHANNEL_COUNT 9 // MPU6050 interrupts #define USE_EXTI -#define MPU_INT_EXTI PA15 +#define MPU_INT_EXTI PA15 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready #define USE_MPU_DATA_READY_SIGNAL //#define ENSURE_MPU_DATA_READY_IS_LOW @@ -41,20 +39,18 @@ #define ACC #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW180_DEG +#define GYRO_MPU6050_ALIGN CW180_DEG #define USE_ACC_MPU6050 - -#define ACC_MPU6050_ALIGN CW180_DEG +#define ACC_MPU6050_ALIGN CW180_DEG #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG -#define MPU6000_CS_GPIO GPIOB -#define MPU6000_CS_PIN PB12 -#define MPU6000_SPI_INSTANCE SPI2 +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 //#define BARO //#define USE_BARO_MS5611 @@ -66,31 +62,30 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 -#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PB3 -#define UART2_RX_PIN PB4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 - -#define UART3_TX_PIN PB10 //(AF7) -#define UART3_RX_PIN PB11 //(AF7) +#define UART3_TX_PIN PB10 //(AF7) +#define UART3_RX_PIN PB11 //(AF7) #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) -#define I2C2_SCL PA9 -#define I2C2_SDA PA10 +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 #define USE_SPI #define USE_SPI_DEVICE_2 -#define M25P16_CS_PIN PB12 -#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 //#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG) -#define SENSORS_SET (SENSOR_ACC) +#define SENSORS_SET (SENSOR_ACC) #undef GPS #define DISPLAY @@ -99,10 +94,10 @@ #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA5 -//#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA5 +//#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #if 1 @@ -135,17 +130,17 @@ #define SPEKTRUM_BIND // USART2, PB4 -#define BIND_PIN PB4 +#define BIND_PIN PB4 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) // #define TARGET_IO_PORTF (BIT(0)|BIT(1)) // !!TODO - check the following line is correct -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h index 7e60ddc55f..9b23c614d1 100644 --- a/src/main/target/ALIENFLIGHTF3/hardware_revision.h +++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h @@ -15,7 +15,7 @@ * along with Cleanflight. If not, see . */ #pragma once - + #include "drivers/exti.h" typedef enum awf3HardwareRevision_t { diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index b05cdb33a4..8ce5876683 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -23,17 +23,17 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define USE_HARDWARE_REVISION_DETECTION -#define HW_PIN PB2 +#define HW_PIN PB2 // LED's V1 -#define LED0 PB4 // LED - PB4 -#define LED1 PB5 // LED - PB5 +#define LED0 PB4 +#define LED1 PB5 // LED's V2 -#define LED0_A PB8 // LED - PB8 -#define LED1_A PB9 // LED - PB9 +#define LED0_A PB8 +#define LED1_A PB9 -#define BEEPER PA5 // LED - PA5 +#define BEEPER PA5 #define USABLE_TIMER_CHANNEL_COUNT 11 @@ -48,15 +48,15 @@ #define USE_GYRO_MPU6050 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6050_ALIGN CW270_DEG -#define GYRO_MPU6500_ALIGN CW270_DEG +#define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6050_ALIGN CW270_DEG -#define ACC_MPU6500_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6500_ALIGN CW270_DEG // No baro support. //#define BARO @@ -65,29 +65,28 @@ // option to use MPU9150 or MPU9250 integrated AK89xx Mag #define MAG #define USE_MAG_AK8963 - -#define MAG_AK8963_ALIGN CW0_DEG_FLIP +#define MAG_AK8963_ALIGN CW0_DEG_FLIP #define USE_VCP #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 SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 // PB6 -#define UART1_RX_PIN PB7 // PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PA2 // PA2 -#define UART2_RX_PIN PA3 // PA3 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) -#define I2C2_SCL PA9 -#define I2C2_SDA PA10 +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 // SPI3 // PA15 38 SPI3_NSS @@ -98,22 +97,22 @@ #define USE_SPI #define USE_SPI_DEVICE_3 -#define MPU6500_CS_PIN PA15 -#define MPU6500_SPI_INSTANCE SPI3 +#define MPU6500_CS_PIN PA15 +#define MPU6500_SPI_INSTANCE SPI3 #define USE_ADC -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define VBAT_SCALE_DEFAULT 20 +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define VBAT_SCALE_DEFAULT 20 #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 #define HARDWARE_BIND_PLUG // Hardware bind plug at PB12 (Pin 25) -#define BINDPLUG_PIN PB12 +#define BINDPLUG_PIN PB12 #define BRUSHED_MOTORS #define DEFAULT_FEATURES FEATURE_MOTOR_STOP @@ -124,12 +123,11 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - assuming 303 in 64pin package, TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) ) diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index 909026c021..45a40fb0f1 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -23,39 +23,39 @@ #define USBD_PRODUCT_STRING "AlienFlight F4" -#define LED0 PC12 -#define LED1 PD2 +#define LED0 PC12 +#define LED1 PD2 -#define BEEPER PC13 +#define BEEPER PC13 -#define INVERTER PC15 -#define INVERTER_USART USART2 +#define INVERTER PC15 +#define INVERTER_USART USART2 // MPU interrupt //#define DEBUG_MPU_DATA_READY_INTERRUPT #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready -#define MPU_INT_EXTI PC14 +#define MPU_INT_EXTI PC14 #define USE_EXTI -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 #define ACC #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW270_DEG +#define ACC_MPU6500_ALIGN CW270_DEG #define GYRO #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG #define MAG #define USE_MAG_HMC5883 #define USE_MAG_AK8963 -#define MAG_HMC5883_ALIGN CW180_DEG -#define MAG_AK8963_ALIGN CW270_DEG +#define MAG_HMC5883_ALIGN CW180_DEG +#define MAG_AK8963_ALIGN CW270_DEG #define BARO #define USE_BARO_MS5611 @@ -65,14 +65,14 @@ //#define SDCARD_DETECT_INVERTED -#define SDCARD_DETECT_PIN PB10 -#define SDCARD_DETECT_EXTI_LINE EXTI_Line10 -#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10 -#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB -#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn +#define SDCARD_DETECT_PIN PB10 +#define SDCARD_DETECT_EXTI_LINE EXTI_Line10 +#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10 +#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB +#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn -#define SDCARD_SPI_INSTANCE SPI2 -#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN // SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: #define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz @@ -93,57 +93,55 @@ //#define USE_FLASHFS //#define USE_FLASH_M25P16 -#define USABLE_TIMER_CHANNEL_COUNT 13 +#define USABLE_TIMER_CHANNEL_COUNT 13 #define USE_VCP #define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define USE_UART2 -#define UART2_RX_PIN PA3 -#define UART2_TX_PIN PA2 //inverter +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 //inverter //#define USE_UART3 -//#define UART3_RX_PIN PB11 -//#define UART3_TX_PIN PB10 +//#define UART3_RX_PIN PB11 +//#define UART3_TX_PIN PB10 #define USE_UART4 -#define UART4_RX_PIN PC10 -#define UART4_TX_PIN PC11 +#define UART4_RX_PIN PC10 +#define UART4_TX_PIN PC11 //#define USE_UART5 -//#define UART5_RX_PIN PD2 -//#define UART5_TX_PIN PC12 +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 #define USE_SPI - #define USE_SPI_DEVICE_1 - #define USE_SPI_DEVICE_2 -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 #define USE_SPI_DEVICE_3 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) -//#define I2C_DEVICE_EXT (I2CDEV_2) -#define I2C1_SCL PB6 -#define I2C1_SDA PB7 +#define I2C_DEVICE (I2CDEV_1) +//#define I2C_DEVICE_EXT (I2CDEV_2) +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 #define USE_ADC //#define BOARD_HAS_VOLTAGE_DIVIDER -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC4 -#define EXTERNAL1_ADC_GPIO_PIN PC5 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC4 +#define EXTERNAL1_ADC_GPIO_PIN PC5 // LED strip configuration using RC5 pin. //#define LED_STRIP @@ -156,11 +154,11 @@ #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 #define HARDWARE_BIND_PLUG // Hardware bind plug at PB2 (Pin 28) -#define BINDPLUG_PIN PB2 +#define BINDPLUG_PIN PB2 #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT @@ -172,10 +170,10 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) -#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) diff --git a/src/main/target/BLUEJAYF4/target.c b/src/main/target/BLUEJAYF4/target.c index f005e5d1a0..b85e50f539 100644 --- a/src/main/target/BLUEJAYF4/target.c +++ b/src/main/target/BLUEJAYF4/target.c @@ -33,7 +33,7 @@ const uint16_t multiPPM[] = { }; const uint16_t multiPWM[] = { - PWM1 | (MAP_TO_PWM_INPUT << 8), + PWM1 | (MAP_TO_PWM_INPUT << 8), PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index e83499615a..34bdcf8aa7 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -20,40 +20,40 @@ #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define USBD_PRODUCT_STRING "BlueJayF4" +#define USBD_PRODUCT_STRING "BlueJayF4" #define BOARD_HAS_VOLTAGE_DIVIDER #define USE_EXTI -#define INVERTER PB15 -#define INVERTER_USART USART6 +#define LED0 PB6 +#define LED1 PB5 +#define LED2 PB4 -#define BEEPER PB7 +#define BEEPER PB7 #define BEEPER_INVERTED -#define LED0 PB6 -#define LED1 PB5 -#define LED2 PB4 +#define INVERTER PB15 +#define INVERTER_USART USART6 -#define MPU6500_CS_PIN PC4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PC4 +#define MPU6500_SPI_INSTANCE SPI1 #define ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG #define GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG //#define MAG //#define USE_MAG_AK8963 #define BARO #define USE_BARO_MS5611 -#define MS5611_I2C_INSTANCE I2CDEV_1 +#define MS5611_I2C_INSTANCE I2CDEV_1 #define USE_SDCARD @@ -76,8 +76,8 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -//#define M25P16_CS_PIN PB3 -//#define M25P16_SPI_INSTANCE SPI3 +//#define M25P16_CS_PIN PB3 +//#define M25P16_SPI_INSTANCE SPI3 //#define USE_FLASHFS //#define USE_FLASH_M25P16 @@ -96,22 +96,21 @@ //#define VBUS_SENSING_ENABLED #define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 #define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 #define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 @@ -134,15 +133,15 @@ #define SPI3_MOSI_PIN PC12 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) +#define I2C_DEVICE (I2CDEV_1) #define USE_I2C_PULLUP #define USE_ADC -#define VBAT_ADC_PIN PC3 +#define VBAT_ADC_PIN PC3 #define LED_STRIP // LED Strip can run off Pin 6 (PB1) of the ESC outputs. -#define WS2811_PIN PB1 +#define WS2811_PIN PB1 #define WS2811_TIMER TIM3 #define WS2811_TIMER_CHANNEL TIM_Channel_4 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER @@ -155,15 +154,15 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES FEATURE_BLACKBOX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9)) +#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 a1425bc538..cee25b2723 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -17,25 +17,25 @@ #define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D -#define LED0 PB3 // PB3 (LED) +#define LED0 PB3 -#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO -#define INVERTER_USART USART1 +#define INVERTER PB2 // PB2 (BOOT1) used as inverter select GPIO +#define INVERTER_USART USART1 -#define BEEPER PB15 // PB15 (Beeper) -#define BEEPER_OPT PB2 // PB15 (Beeper) +#define BEEPER PB15 +#define BEEPER_OPT PB2 #define USE_EXTI #define USE_MPU_DATA_READY_SIGNAL -#define MPU_INT_EXTI PA3 +#define MPU_INT_EXTI PA3 -#define MPU6000_CS_GPIO GPIOA -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_GPIO GPIOA +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 -#define M25P16_CS_GPIO GPIOB -#define M25P16_CS_PIN PB12 -#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_CS_GPIO GPIOB +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -72,18 +72,18 @@ #define USE_UART1 #define USE_UART3 #define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 4 +#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 TIM3 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 1 // PWM 2 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 2 // PWM 3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_SPI #define USE_SPI_DEVICE_1 @@ -93,15 +93,15 @@ #define I2C_DEVICE (I2CDEV_2) // Flex port - SCL/PB10, SDA/PB11 #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA0 -#define RSSI_ADC_PIN PB0 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA0 +#define RSSI_ADC_PIN PB0 #define LED_STRIP -#define WS2811_PIN PB4 -#define WS2811_TIMER TIM3 -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER +#define WS2811_PIN PB4 +#define WS2811_TIMER TIM3 +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER #define SPEKTRUM_BIND // USART3, PB11 (Flexport) @@ -111,12 +111,13 @@ #define DISPLAY #define SONAR -#define SONAR_ECHO_PIN PB0 -#define SONAR_TRIGGER_PIN PB5 +#define SONAR_ECHO_PIN PB0 +#define SONAR_TRIGGER_PIN PB5 #undef GPS #undef BARO +#undef MAG #ifdef CC3D_OPBL #define SKIP_CLI_COMMAND_HELP @@ -128,8 +129,8 @@ #define DEFAULT_RX_FEATURE FEATURE_RX_PPM // IO - from schematics -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC ( BIT(14) ) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC ( BIT(14) ) -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 52bea95ba2..84f7071c86 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -22,14 +22,14 @@ #ifndef STM32F3DISCOVERY #define STM32F3DISCOVERY -#endif - -#define LED0 PE8 // Blue LEDs - PE8/PE12 +#endif + +#define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_INVERTED -#define LED1 PE10 // Orange LEDs - PE10/PE14 +#define LED1 PE10 // Orange LEDs - PE10/PE14 #define LED1_INVERTED -#define BEEPER PE9 // Red LEDs - PE9/PE13 +#define BEEPER PE9 // Red LEDs - PE9/PE13 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 18 @@ -81,16 +81,14 @@ #define ACC #define USE_ACC_MPU6050 #define USE_ACC_LSM303DLHC - -#define ACC_MPU6050_ALIGN CW0_DEG +#define ACC_MPU6050_ALIGN CW0_DEG #define BARO #define USE_BARO_MS5611 #define MAG #define USE_MAG_AK8975 - -#define MAG_AK8975_ALIGN CW90_DEG_FLIP +#define MAG_AK8975_ALIGN CW90_DEG_FLIP #define USE_VCP #define USE_UART1 @@ -101,20 +99,19 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 // IO - assuming 303 in 64pin package, TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)|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)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#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)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h index 4b3c13d674..89e3478c13 100755 --- a/src/main/target/CJMCU/hardware_revision.h +++ b/src/main/target/CJMCU/hardware_revision.h @@ -17,7 +17,7 @@ #pragma once #include "drivers/exti.h" - + typedef enum cjmcuHardwareRevision_t { UNKNOWN = 0, REV_1, // Blue LED3 diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index d84e98eae1..4af75b2b2e 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -20,9 +20,9 @@ #define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU #define USE_HARDWARE_REVISION_DETECTION -#define LED0 PC14 // PC14 (LED) -#define LED1 PC13 // PC13 (LED) -#define LED2 PC15 // PC15 (LED) +#define LED0 PC14 +#define LED1 PC13 +#define LED2 PC15 #define ACC #define USE_ACC_MPU6050 @@ -38,7 +38,7 @@ #define USE_UART1 #define USE_UART2 -#define SERIAL_PORT_COUNT 2 +#define SERIAL_PORT_COUNT 2 #define USE_I2C #define I2C_DEVICE (I2CDEV_1) @@ -49,7 +49,7 @@ #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 #if (FLASH_SIZE > 64) @@ -64,8 +64,8 @@ #endif // IO - assuming all IOs on 48pin package TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 65ab62d5d6..f98d39eb36 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -18,17 +18,17 @@ #pragma once #define TARGET_BOARD_IDENTIFIER "CLBR" -#define BST_DEVICE_NAME "COLIBRI RACE" -#define BST_DEVICE_NAME_LENGTH 12 +#define BST_DEVICE_NAME "COLIBRI RACE" +#define BST_DEVICE_NAME_LENGTH 12 #define TARGET_CONFIG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - -#define LED0 PC15 -#define LED1 PC14 -#define LED2 PC13 -#define BEEPER PB13 +#define LED0 PC15 +#define LED1 PC14 +#define LED2 PC13 + +#define BEEPER PB13 #define BEEPER_INVERTED #define USE_EXTI @@ -53,17 +53,17 @@ #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#define ACC_MPU6000_ALIGN CW270_DEG #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW270_DEG +#define ACC_MPU6500_ALIGN CW270_DEG #define BARO #define USE_BARO_MS5611 @@ -80,34 +80,34 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PC4 -#define UART1_RX_PIN PC5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN PA14 -#define UART2_RX_PIN PA15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) -#define I2C2_SCL_PIN PA9 -#define I2C2_SDA_PIN PA10 +#define I2C2_SCL_PIN PA9 +#define I2C2_SDA_PIN PA10 #define USE_BST #define BST_DEVICE (BSTDEV_1) /* Configure the CRC peripheral to use the polynomial x8 + x7 + x6 + x4 + x2 + 1 */ -#define BST_CRC_POLYNOM 0xD5 +#define BST_CRC_POLYNOM 0xD5 #define USE_ADC -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP #define USE_COLIBTI_RACE_LED_DEFAULT_CONFIG @@ -122,7 +122,7 @@ // MPU6500 interrupt #define USE_EXTI -#define MPU_INT_EXTI PA5 +#define MPU_INT_EXTI PA5 //#define DEBUG_MPU_DATA_READY_INTERRUPT #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW @@ -135,11 +135,11 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - assuming 303 in 64pin package, TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) diff --git a/src/main/target/DOGE/target.c b/src/main/target/DOGE/target.c index c813ceecba..05b642f088 100644 --- a/src/main/target/DOGE/target.c +++ b/src/main/target/DOGE/target.c @@ -43,7 +43,7 @@ const uint16_t multiPWM[] = { PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), 0xFFFF }; diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index e4c2f76ba0..2399ede8d1 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -20,17 +20,15 @@ #define TARGET_BOARD_IDENTIFIER "DOGE" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - + // tqfp48 pin 34 -#define LED0 PA13 - +#define LED0 PA13 // tqfp48 pin 37 -#define LED1 PA14 - +#define LED1 PA14 // tqfp48 pin 38 -#define LED2 PA15 +#define LED2 PA15 -#define BEEPER PB2 +#define BEEPER PB2 #define BEEPER_INVERTED #define USE_SPI @@ -81,13 +79,13 @@ // #define USE_FAKE_GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW270_DEG // ?? +#define GYRO_MPU6500_ALIGN CW270_DEG // ?? #define ACC // #define USE_FAKE_ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW270_DEG // ?? +#define ACC_MPU6500_ALIGN CW270_DEG // ?? #define BARO #define USE_BARO_BMP280 @@ -100,20 +98,20 @@ #define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 -#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 // mpu_int definition in sensors/initialisation.c #define USE_EXTI @@ -135,19 +133,19 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // Use UART3 for speksat -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // !!TODO - check the TARGET_IO_PORTs are correct -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) diff --git a/src/main/target/EUSTM32F103RC/target.h b/src/main/target/EUSTM32F103RC/target.h index ee893670dd..87c531b109 100644 --- a/src/main/target/EUSTM32F103RC/target.h +++ b/src/main/target/EUSTM32F103RC/target.h @@ -19,21 +19,21 @@ #define TARGET_BOARD_IDENTIFIER "EUF1" -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) +#define LED0 PB3 +#define LED1 PB4 -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO #define INVERTER_USART USART2 #define USE_EXTI -#define MPU6000_CS_GPIO GPIOB -#define MPU6000_CS_PIN PB12 -#define MPU6000_SPI_INSTANCE SPI2 +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 #define MPU6500_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB -#define MPU6500_CS_GPIO GPIOB -#define MPU6500_CS_PIN PB12 -#define MPU6500_SPI_INSTANCE SPI2 +#define MPU6500_CS_GPIO GPIOB +#define MPU6500_CS_PIN PB12 +#define MPU6500_SPI_INSTANCE SPI2 #define GYRO #define USE_FAKE_GYRO @@ -44,7 +44,7 @@ #define USE_GYRO_SPI_MPU6000 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6050_ALIGN CW0_DEG +#define GYRO_MPU6050_ALIGN CW0_DEG #define ACC #define USE_FAKE_ACC @@ -55,7 +55,7 @@ //#define USE_ACC_SPI_MPU6000 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6050_ALIGN CW0_DEG +#define ACC_MPU6050_ALIGN CW0_DEG #define BARO #define USE_BARO_MS5611 @@ -66,7 +66,7 @@ #define USE_MAG_HMC5883 #define USE_MAG_AK8975 -#define MAG_AK8975_ALIGN CW180_DEG_FLIP +#define MAG_AK8975_ALIGN CW180_DEG_FLIP #define SONAR #define SONAR_TRIGGER_PIN PB0 @@ -80,12 +80,12 @@ #define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER TIM3 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 @@ -97,21 +97,20 @@ // #define SOFT_I2C_PB67 #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA4 -#define RSSI_ADC_PIN PA1 -#define EXTERNAL1_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 // IO - stm32f103RCT6 in 64pin package (TODO) -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/F4BY/target.c b/src/main/target/F4BY/target.c index e023d7e960..a8d80e823d 100644 --- a/src/main/target/F4BY/target.c +++ b/src/main/target/F4BY/target.c @@ -30,11 +30,11 @@ const uint16_t multiPWM[] = { PWM3 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), - PWM6 | (MAP_TO_PWM_INPUT << 8), - PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), @@ -69,11 +69,11 @@ const uint16_t airPWM[] = { PWM3 | (MAP_TO_PWM_INPUT << 8), PWM4 | (MAP_TO_PWM_INPUT << 8), PWM5 | (MAP_TO_PWM_INPUT << 8), - PWM6 | (MAP_TO_PWM_INPUT << 8), - PWM7 | (MAP_TO_PWM_INPUT << 8), + PWM6 | (MAP_TO_PWM_INPUT << 8), + PWM7 | (MAP_TO_PWM_INPUT << 8), PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8 - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1 PWM12 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2 PWM13 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3 @@ -101,7 +101,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM1, IO_TAG(PE11), TIM_Channel_2, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S6_OUT { TIM1, IO_TAG(PE13), TIM_Channel_3, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S7_OUT { TIM1, IO_TAG(PE14), TIM_Channel_4, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_TIM1}, // S8_OUT - + { TIM9, IO_TAG(PE6), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 0, IOCFG_AF_PP, GPIO_AF_TIM9 }, // sonar echo if needed }; diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index 127a33d4bb..8b4b846c40 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -20,46 +20,47 @@ #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define USBD_PRODUCT_STRING "Swift-Flyer F4BY" +#define USBD_PRODUCT_STRING "Swift-Flyer F4BY" -#define LED0 PE3 // Blue LED -#define LED1 PE2 // Red LED -#define LED2 PE1 // Blue LED -#define BEEPER PE5 +#define LED0 PE3 // Blue LED +#define LED1 PE2 // Red LED +#define LED2 PE1 // Blue LED -#define INVERTER PD3 -#define INVERTER_USART USART6 +#define BEEPER PE5 + +#define INVERTER PD3 +#define INVERTER_USART USART6 // MPU6000 interrupts #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PB0 +#define MPU_INT_EXTI PB0 #define USE_EXTI -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW90_DEG +#define ACC_MPU6000_ALIGN CW90_DEG #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG #define MAG #define USE_MAG_HMC5883 -#define MAG_HMC5883_ALIGN CW90_DEG +#define MAG_HMC5883_ALIGN CW90_DEG #define BARO #define USE_BARO_MS5611 #define USE_SDCARD -#define SDCARD_SPI_INSTANCE SPI2 -#define SDCARD_SPI_CS_PIN PE15 +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_PIN PE15 // SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: #define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz @@ -76,43 +77,41 @@ #define USABLE_TIMER_CHANNEL_COUNT 17 #define USE_VCP -#define VBUS_SENSING_PIN PA9 +#define VBUS_SENSING_PIN PA9 #define USE_UART1 -#define UART1_RX_PIN PB7 -#define UART1_TX_PIN PB6 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define USE_UART2 -#define UART2_RX_PIN PD6 -#define UART2_TX_PIN PD5 +#define UART2_RX_PIN PD6 +#define UART2_TX_PIN PD5 #define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 +#define UART3_RX_PIN PD9 +#define UART3_TX_PIN PD8 #define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 +#define UART4_RX_PIN PC11 +#define UART4_TX_PIN PC10 //#define USE_UART5 - error in DMA!!! -//#define UART5_RX_PIN PD2 -//#define UART5_TX_PIN PC12 +//#define UART5_RX_PIN PD2 +//#define UART5_TX_PIN PC12 #define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 - -#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6 +#define SERIAL_PORT_COUNT 6 //VCP, UART1, UART2, UART3, UART4, UART5, UART6 #define USE_SPI - #define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 -#define SPI1_NSS_PIN NONE +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 +#define SPI1_NSS_PIN NONE #define USE_SPI_DEVICE_2 #define SPI2_NSS_PIN NONE @@ -121,24 +120,23 @@ #define SPI2_MOSI_PIN PB15 #define USE_SPI_DEVICE_3 -#define SPI3_NSS_PIN PA15 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PB5 - +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 #define USE_I2C -#define I2C_DEVICE (I2CDEV_2) +#define I2C_DEVICE (I2CDEV_2) #define USE_I2C_PULLUP -#define I2C2_SCL PB10 -#define I2C2_SDA PB11 +#define I2C2_SCL PB10 +#define I2C2_SDA PB11 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define VBAT_ADC_PIN PC3 -#define CURRENT_METER_ADC_PIN PC2 -#define RSSI_ADC_PIN PC1 +#define USE_ADC +#define VBAT_ADC_PIN PC3 +#define CURRENT_METER_ADC_PIN PC2 +#define RSSI_ADC_PIN PC1 #define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL @@ -148,15 +146,15 @@ #define SPEKTRUM_BIND // UART6, PC7 -#define BIND_PIN PC7 +#define BIND_PIN PC7 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff -#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/FURYF3/target.c b/src/main/target/FURYF3/target.c index 21b05ab5d4..bf4ff7b20a 100644 --- a/src/main/target/FURYF3/target.c +++ b/src/main/target/FURYF3/target.c @@ -76,7 +76,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM4_IRQn, 1, IOCFG_AF_PP, GPIO_AF_2 }, // PWM5 - S2 { TIM17, IO_TAG(PB5), TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, IOCFG_AF_PP, GPIO_AF_10}, // PWM6 - S3 { TIM16, IO_TAG(PB4), TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, IOCFG_AF_PP, GPIO_AF_1 }, // PWM7 - S4 - + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM1_CC_IRQn, 1, IOCFG_AF_PP, GPIO_AF_6 }, // GPIO TIMER - LED_STRIP }; diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index e67a920cc6..82323ad058 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -21,13 +21,13 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define MPU_INT_EXTI PC4 +#define MPU_INT_EXTI PC4 #define USE_EXTI #define CONFIG_PREFER_ACC_ON - -#define LED0 PC14 -#define BEEPER PC15 +#define LED0 PC14 + +#define BEEPER PC15 #define BEEPER_INVERTED #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU INT, SDCardDetect @@ -36,26 +36,25 @@ #define ENSURE_MPU_DATA_READY_IS_LOW #define GYRO -#define ACC -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 - -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW90_DEG +#define GYRO_MPU6500_ALIGN CW90_DEG +#define ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW90_DEG +#define ACC_MPU6500_ALIGN CW90_DEG #define BARO #define USE_BARO_MS5611 @@ -113,31 +112,31 @@ #define USE_SOFTSERIAL1 #define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 1 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 2 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) +#define I2C_DEVICE (I2CDEV_1) // SDA (PB9/AF4), SCL (PB8/AF4) -#define I2C1_SCL_PIN PB8 -#define I2C1_SDA_PIN PB9 +#define I2C1_SCL_PIN PB8 +#define I2C1_SDA_PIN PB9 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PA0 -#define RSSI_ADC_PIN PA1 -#define CURRENT_METER_ADC_PIN PA2 +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PA0 +#define RSSI_ADC_PIN PA1 +#define CURRENT_METER_ADC_PIN PA2 #define LED_STRIP @@ -150,23 +149,23 @@ #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define DEFAULT_FEATURES FEATURE_BLACKBOX #define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTF (BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTF (BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index b9631d6124..c6263bcd47 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -20,44 +20,45 @@ #define TARGET_BOARD_IDENTIFIER "FYF4" #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define USBD_PRODUCT_STRING "FuryF4" +#define USBD_PRODUCT_STRING "FuryF4" -#define LED0 PB5 -#define LED1 PB4 -#define BEEPER PA8 +#define LED0 PB5 +#define LED1 PB4 + +#define BEEPER PA8 #define BEEPER_INVERTED #define INVERTER PC0 // PC0 used as inverter select GPIO #define INVERTER_USART USART1 -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG // MPU6000 interrupts #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC4 +#define MPU_INT_EXTI PC4 #define USE_EXTI #define BARO #define USE_BARO_MS5611 -#define MS5611_I2C_INSTANCE I2CDEV_1 +#define MS5611_I2C_INSTANCE I2CDEV_1 #define USE_SDCARD @@ -97,29 +98,29 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define M25P16_CS_PIN PB3 -#define M25P16_SPI_INSTANCE SPI3 +#define M25P16_CS_PIN PB3 +#define M25P16_SPI_INSTANCE SPI3 #define USABLE_TIMER_CHANNEL_COUNT 5 #define USE_VCP -#define VBUS_SENSING_PIN PC5 +#define VBUS_SENSING_PIN PC5 #define VBUS_SENSING_ENABLED #define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 +#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 #define USE_SPI @@ -138,16 +139,16 @@ #define SPI3_MOSI_PIN PC12 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA +#define I2C_DEVICE (I2CDEV_1) // PB6-SCL, PB7-SDA #define USE_I2C_PULLUP -#define I2C1_SCL PB6 -#define I2C1_SDA PB7 +#define I2C1_SCL PB6 +#define I2C1_SDA PB7 #define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define VBAT_ADC_PIN PC1 -#define RSSI_ADC_GPIO_PIN PC2 -#define CURRENT_METER_ADC_PIN PC3 +#define VBAT_ADC_PIN PC1 +#define RSSI_ADC_GPIO_PIN PC2 +#define CURRENT_METER_ADC_PIN PC3 #define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL @@ -157,14 +158,14 @@ #define SPEKTRUM_BIND // USART3 Rx, PB11 -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9)) diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 8e41030edf..8dbd6e55ba 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -21,7 +21,7 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 #define USABLE_TIMER_CHANNEL_COUNT 17 @@ -32,11 +32,11 @@ #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6050_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW270_DEG #define BARO #define USE_BARO_BMP085 @@ -49,17 +49,17 @@ #define USE_UART3 #define SERIAL_PORT_COUNT 3 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 @@ -67,16 +67,16 @@ #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE /* @@ -100,11 +100,10 @@ */ // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index de059f7b46..3c5f4cd5d7 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -23,51 +23,50 @@ #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR) -#define LED0 PB1 -#define BEEPER PB13 +#define LED0 PB1 + +#define BEEPER PB13 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 #define USE_EXTI -#define MPU_INT_EXTI PB2 +#define MPU_INT_EXTI PB2 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW180_DEG +#define GYRO_MPU6050_ALIGN CW180_DEG #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW180_DEG - +#define ACC_MPU6050_ALIGN CW180_DEG #define USE_VCP #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART2_TX_PIN PB3 -#define UART2_RX_PIN PB4 - -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_ADC -#define VBAT_SCALE_DEFAULT 160 -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PA0 -//#define CURRENT_METER_ADC_PIN PA5 -//#define RSSI_ADC_PIN PB2 +#define VBAT_SCALE_DEFAULT 160 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PA0 +//#define CURRENT_METER_ADC_PIN PA5 +//#define RSSI_ADC_PIN PB2 #define DEFAULT_FEATURES FEATURE_VBAT #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL @@ -75,12 +74,12 @@ #define SERIALRX_UART SERIAL_PORT_USART2 #define SPEKTRUM_BIND -#define BIND_PIN PB4 +#define BIND_PIN PB4 -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTF (BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTF (BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index ac7d2c06dd..ef5fc8547c 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -21,12 +21,12 @@ #define BOARD_HAS_VOLTAGE_DIVIDER #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - -#define LED0 PC15 -#define LED1 PC14 -#define LED2 PC13 -#define BEEPER PB13 +#define LED0 PC15 +#define LED1 PC14 +#define LED2 PC13 + +#define BEEPER PB13 #define BEEPER_INVERTED #define USE_SPI @@ -47,12 +47,12 @@ #define GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 -#define GYRO_MPU6500_ALIGN CW270_DEG +#define GYRO_MPU6500_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW270_DEG +#define ACC_MPU6500_ALIGN CW270_DEG #define USB_IO @@ -60,26 +60,26 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PC4 -#define UART1_RX_PIN PC5 +#define UART1_TX_PIN PC4 +#define UART1_RX_PIN PC5 -#define UART2_TX_PIN PA14 -#define UART2_RX_PIN PA15 +#define UART2_TX_PIN PA14 +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) #define USE_ADC -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP #define WS2811_PIN PA6 // TIM16_CH1 @@ -97,20 +97,20 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define SPEKTRUM_BIND // USART1, PC5 -#define BIND_PIN PC5 +#define BIND_PIN PC5 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - assuming 303 in 64pin package, TODO -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 958924fabe..1db54b9886 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -21,18 +21,18 @@ #define USE_CLI #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - -#define LED0 PB5 // Blue LEDs - PB5 -//#define LED1 PB9 // Green LEDs - PB9 -#define BEEPER PA0 +#define LED0 PB5 // Blue LEDs - PB5 +//#define LED1 PB9 // Green LEDs - PB9 + +#define BEEPER PA0 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 9 // MPU6050 interrupts #define USE_EXTI -#define MPU_INT_EXTI PA15 +#define MPU_INT_EXTI PA15 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready #define USE_MPU_DATA_READY_SIGNAL //#define ENSURE_MPU_DATA_READY_IS_LOW @@ -41,20 +41,20 @@ #define ACC #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW180_DEG +#define GYRO_MPU6050_ALIGN CW180_DEG #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW180_DEG +#define ACC_MPU6050_ALIGN CW180_DEG #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG -#define MPU6000_CS_GPIO GPIOB -#define MPU6000_CS_PIN PB12 -#define MPU6000_SPI_INSTANCE SPI2 +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 //#define BARO //#define USE_BARO_MS5611 @@ -66,42 +66,42 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 // PB6 -#define UART1_RX_PIN PB7 // PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PB3 // PB3 -#define UART2_RX_PIN PB4 // PB4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_I2C -#define I2C_DEVICE (I2CDEV_2) -#define I2C2_SCL PA9 -#define I2C2_SDA PA10 +#define I2C_DEVICE (I2CDEV_2) +#define I2C2_SCL PA9 +#define I2C2_SDA PA10 #define USE_SPI #define USE_SPI_DEVICE_2 -#define M25P16_CS_PIN PB12 -#define M25P16_SPI_INSTANCE SPI2 +#define M25P16_CS_PIN PB12 +#define M25P16_SPI_INSTANCE SPI2 -//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG) -#define SENSORS_SET (SENSOR_ACC) +//#define SENSORS_SET (SENSOR_ACC | SENSOR_BARO | SENSOR_GPS | SENSOR_MAG) +#define SENSORS_SET (SENSOR_ACC) #undef GPS #define DISPLAY #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA5 -//#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA5 +//#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #if 1 @@ -135,17 +135,17 @@ #define SPEKTRUM_BIND // USART2, PB4 -#define BIND_PIN PB4 +#define BIND_PIN PB4 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) // #define TARGET_IO_PORTF (BIT(0)|BIT(1)) // !!TODO - check the following line is correct -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index adca1659a7..390dc39f2a 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -22,19 +22,19 @@ #define BOARD_HAS_VOLTAGE_DIVIDER -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) +#define LED0 PB3 +#define LED1 PB4 -#define BEEPER PA12 // PA12 (Beeper) +#define BEEPER PA12 #ifdef AFROMINI #define BEEPER_INVERTED #endif -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_PIN PC14 +#define BARO_XCLR_PIN PC13 +#define BARO_EOC_PIN PC14 -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_USART USART2 #define USE_EXTI @@ -47,24 +47,22 @@ #define USE_SPI #define USE_SPI_DEVICE_2 -#define NAZE_SPI_INSTANCE SPI2 -#define NAZE_SPI_CS_GPIO GPIOB -#define NAZE_SPI_CS_PIN PB12 +#define NAZE_SPI_INSTANCE SPI2 +#define NAZE_SPI_CS_GPIO GPIOB +#define NAZE_SPI_CS_PIN PB12 #define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB // We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO -#define M25P16_CS_PIN NAZE_SPI_CS_PIN -#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE - -#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL -#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO -#define MPU6500_CS_PIN NAZE_SPI_CS_PIN -#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE +#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO +#define M25P16_CS_PIN NAZE_SPI_CS_PIN +#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE +#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL +#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO +#define MPU6500_CS_PIN NAZE_SPI_CS_PIN +#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE #define USE_FLASHFS - #define USE_FLASH_M25P16 #define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC @@ -75,17 +73,16 @@ //#define DEBUG_MAG_DATA_READY_INTERRUPT #define USE_MAG_DATA_READY_SIGNAL #define MAG_INT_EXTI PC14 - + #define GYRO #define USE_GYRO_MPU3050 #define USE_GYRO_MPU6050 #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 - -#define GYRO_MPU3050_ALIGN CW0_DEG -#define GYRO_MPU6050_ALIGN CW0_DEG -#define GYRO_MPU6500_ALIGN CW0_DEG +#define GYRO_MPU3050_ALIGN CW0_DEG +#define GYRO_MPU6050_ALIGN CW0_DEG +#define GYRO_MPU6500_ALIGN CW0_DEG #define ACC #define USE_ACC_ADXL345 @@ -95,11 +92,11 @@ #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_ADXL345_ALIGN CW270_DEG -#define ACC_MPU6050_ALIGN CW0_DEG -#define ACC_MMA8452_ALIGN CW90_DEG -#define ACC_BMA280_ALIGN CW0_DEG -#define ACC_MPU6500_ALIGN CW0_DEG +#define ACC_ADXL345_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW0_DEG +#define ACC_MMA8452_ALIGN CW90_DEG +#define ACC_BMA280_ALIGN CW0_DEG +#define ACC_MPU6500_ALIGN CW0_DEG #define BARO #define USE_BARO_MS5611 @@ -108,8 +105,7 @@ #define MAG #define USE_MAG_HMC5883 - -#define MAG_HMC5883_ALIGN CW180_DEG +#define MAG_HMC5883_ALIGN CW180_DEG #define SONAR #define SONAR_TRIGGER_PIN PB0 @@ -124,7 +120,7 @@ #define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 @@ -134,8 +130,8 @@ #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 // USART3 only on NAZE32_SP - Flex Port -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_I2C #define I2C_DEVICE (I2CDEV_2) @@ -145,23 +141,23 @@ // #define SOFT_I2C_PB67 #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA4 -#define RSSI_ADC_PIN PA1 -#define EXTERNAL1_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 #define LED_STRIP -#define WS2811_TIMER TIM3 -#define WS2811_PIN PA6 -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER +#define WS2811_TIMER TIM3 +#define WS2811_PIN PA6 +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER #undef GPS #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 #define USE_SERIAL_4WAY_BLHELI_INTERFACE @@ -186,8 +182,8 @@ #endif // ALIENFLIGHTF1 // IO - assuming all IOs on 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) ) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) ) -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/OLIMEXINO/target.h b/src/main/target/OLIMEXINO/target.h index c526310333..bb270cb4fc 100644 --- a/src/main/target/OLIMEXINO/target.h +++ b/src/main/target/OLIMEXINO/target.h @@ -23,12 +23,12 @@ //#define OLIMEXINO_UNCUT_LED2_E_JUMPER #ifdef OLIMEXINO_UNCUT_LED1_E_JUMPER -#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green +#define LED0 PA5 // D13, PA5/SPI1_SCK/ADC5 - "LED1" on silkscreen, Green #endif #ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER // "LED2" is using one of the PWM pins (CH2/PWM2), so we must not use PWM2 unless the jumper is cut. @See pwmInit() -#define LED1 PA1 // D3, PA1/UART2_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 @@ -59,14 +59,14 @@ #define USE_MAG_HMC5883 #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_UART1 #define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 #define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 @@ -79,17 +79,16 @@ #define I2C_DEVICE (I2CDEV_2) #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA4 -#define RSSI_ADC_PIN PA1 -#define EXTERNAL1_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 // IO - assuming all IOs on smt32f103rb LQFP64 package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index b9119c5fd3..87c5c286a9 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -21,9 +21,9 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 10 // 6 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. @@ -35,19 +35,19 @@ #define MPU_INT_EXTI PC13 #define USE_EXTI -#define MPU6000_SPI_INSTANCE SPI1 -#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW90_DEG +#define GYRO_MPU6000_ALIGN CW90_DEG #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW90_DEG +#define ACC_MPU6000_ALIGN CW90_DEG -#define BMP280_SPI_INSTANCE SPI1 -#define BMP280_CS_PIN PA13 +#define BMP280_SPI_INSTANCE SPI1 +#define BMP280_CS_PIN PA13 #define BARO #define USE_BARO_BMP280 @@ -60,13 +60,12 @@ //#define MAG_AK8975_ALIGN CW90_DEG_FLIP //#define SONAR -//#define SONAR_ECHO_PIN PB1 -//#define SONAR_TRIGGER_PIN PB0 +//#define SONAR_ECHO_PIN PB1 +//#define SONAR_TRIGGER_PIN PB0 #define USB_IO #define USB_CABLE_DETECTION - -#define USB_DETECT_PIN PB5 +#define USB_DETECT_PIN PB5 #define USE_VCP #define USE_UART1 @@ -74,14 +73,14 @@ #define USE_UART3 #define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 @@ -100,8 +99,8 @@ #define OSD // include the max7456 driver #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI1 -#define MAX7456_SPI_CS_PIN PB1 +#define MAX7456_SPI_INSTANCE SPI1 +#define MAX7456_SPI_CS_PIN PB1 //#define MAX7456_DMA_CHANNEL_TX DMA1_Channel3 //#define MAX7456_DMA_CHANNEL_RX DMA1_Channel2 //#define MAX7456_DMA_IRQ_HANDLER_ID DMA1_CH3_HANDLER @@ -169,27 +168,28 @@ #define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125) + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_CURRENT_METER | FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define BUTTONS -#define BUTTON_A_PORT GPIOB -#define BUTTON_A_PIN Pin_1 -#define BUTTON_B_PORT GPIOB -#define BUTTON_B_PIN Pin_0 +#define BUTTON_A_PORT GPIOB +#define BUTTON_A_PIN Pin_1 +#define BUTTON_B_PORT GPIOB +#define BUTTON_B_PIN Pin_0 #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define HARDWARE_BIND_PLUG -#define BINDPLUG_PIN PB0 +#define BINDPLUG_PIN PB0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) diff --git a/src/main/target/OMNIBUSF4/target.c b/src/main/target/OMNIBUSF4/target.c index 03f60516d4..7dd021055e 100644 --- a/src/main/target/OMNIBUSF4/target.c +++ b/src/main/target/OMNIBUSF4/target.c @@ -93,7 +93,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN - + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT @@ -101,5 +101,3 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM5, IO_TAG(PA1), TIM_Channel_2, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S5_OUT - GPIO_PartialRemap_TIM3 { TIM5, IO_TAG(PA0), TIM_Channel_1, TIM5_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM5 }, // S6_OUT }; - - diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 938af8f98b..111f6fc476 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -22,63 +22,63 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define LED0 PB9 -#define LED1 PB5 +#define LED0 PB9 +#define LED1 PB5 -#define BEEPER PA0 +#define BEEPER PA0 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 9 // MPU6000 interrupts #define USE_EXTI -#define MPU_INT_EXTI PA15 +#define MPU_INT_EXTI PA15 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready #define USE_MPU_DATA_READY_SIGNAL #define GYRO -#define ACC - #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW180_DEG -#define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG -#define MPU6000_CS_GPIO GPIOB -#define MPU6000_CS_PIN PB12 -#define MPU6000_SPI_INSTANCE SPI2 +#define ACC +#define USE_ACC_SPI_MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG + +#define MPU6000_CS_GPIO GPIOB +#define MPU6000_CS_PIN PB12 +#define MPU6000_SPI_INSTANCE SPI2 #define USE_VCP #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 // PB6 -#define UART1_RX_PIN PB7 // PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PB3 // PB3 -#define UART2_RX_PIN PB4 // PB4 +#define UART2_TX_PIN PB3 +#define UART2_RX_PIN PB4 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #define USE_SPI #define USE_SPI_DEVICE_2 -#define SENSORS_SET (SENSOR_ACC) +#define SENSORS_SET (SENSOR_ACC) #define TELEMETRY #define BLACKBOX #define SERIAL_RX #define USE_SERVOS -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define CURRENT_METER_ADC_PIN PA2 -#define VBAT_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define CURRENT_METER_ADC_PIN PA2 +#define VBAT_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #if 1 @@ -124,16 +124,17 @@ #define SPEKTRUM_BIND // USART3, PB11 -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -// #define TARGET_IO_PORTF (BIT(0)|BIT(1)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +// #define TARGET_IO_PORTF (BIT(0)|BIT(1)) // !!TODO - check the following line is correct -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/PORT103R/target.h b/src/main/target/PORT103R/target.h index 417f889c9f..66e83fa3d5 100644 --- a/src/main/target/PORT103R/target.h +++ b/src/main/target/PORT103R/target.h @@ -19,36 +19,36 @@ #define TARGET_BOARD_IDENTIFIER "103R" -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) -#define LED2 PD2 // PD2 (LED) - Labelled LED4 +#define LED0 PB3 +#define LED1 PB4 +#define LED2 PD2 // PD2 (LED) - Labelled LED4 -#define BEEPER PA12 // PA12 (Beeper) +#define BEEPER PA12 // PA12 (Beeper) -#define BARO_XCLR_GPIO GPIOC -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_GPIO GPIOC -#define BARO_EOC_PIN PC14 -#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC +#define BARO_XCLR_GPIO GPIOC +#define BARO_XCLR_PIN PC13 +#define BARO_EOC_GPIO GPIOC +#define BARO_EOC_PIN PC14 +#define BARO_APB2_PERIPHERALS RCC_APB2Periph_GPIOC -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_USART USART2 #define USE_SPI #define USE_SPI_DEVICE_2 -#define PORT103R_SPI_INSTANCE SPI2 -#define PORT103R_SPI_CS_PIN PB12 +#define PORT103R_SPI_INSTANCE SPI2 +#define PORT103R_SPI_CS_PIN PB12 // We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_PIN PORT103R_SPI_CS_PIN -#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define M25P16_CS_PIN PORT103R_SPI_CS_PIN +#define M25P16_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN -#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define MPU6000_CS_PIN PORT103R_SPI_CS_PIN +#define MPU6000_SPI_INSTANCE PORT103R_SPI_INSTANCE -#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN -#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE +#define MPU6500_CS_PIN PORT103R_SPI_CS_PIN +#define MPU6500_SPI_INSTANCE PORT103R_SPI_INSTANCE #define GYRO #define USE_FAKE_GYRO @@ -93,37 +93,35 @@ #define USE_UART2 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER TIM3 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #define USE_I2C -#define I2C_DEVICE (I2CDEV_2) +#define I2C_DEVICE (I2CDEV_2) // #define SOFT_I2C // enable to test software i2c // #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) // #define SOFT_I2C_PB67 #define USE_ADC -#define CURRENT_METER_ADC_PIN PB1 -#define VBAT_ADC_PIN PA4 -#define RSSI_ADC_PIN PA1 -#define EXTERNAL1_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PB1 +#define VBAT_ADC_PIN PA4 +#define RSSI_ADC_PIN PA1 +#define EXTERNAL1_ADC_PIN PA5 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f103RCT6 in 64pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) - +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(0)|BIT(1)|BIT(2)) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) - diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 03f60516d4..4e5aa61a12 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -93,7 +93,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { { TIM8, IO_TAG(PC7), TIM_Channel_2, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S4_IN { TIM8, IO_TAG(PC8), TIM_Channel_3, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S5_IN { TIM8, IO_TAG(PC9), TIM_Channel_4, TIM8_CC_IRQn, IOCFG_IPD, GPIO_Mode_AF, GPIO_AF_TIM8 }, // S6_IN - + { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S1_OUT { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM3_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM3 }, // S2_OUT { TIM9, IO_TAG(PA3), TIM_Channel_2, TIM1_BRK_TIM9_IRQn, IOCFG_AF_PP_PD, GPIO_Mode_AF, GPIO_AF_TIM9 }, // S3_OUT diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 05c58aa979..f566b07da7 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -21,40 +21,40 @@ #define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) -#define USBD_PRODUCT_STRING "Revolution" +#define USBD_PRODUCT_STRING "Revolution" #ifdef OPBL #define USBD_SERIALNUMBER_STRING "0x8020000" #endif -#define LED0 PB5 -#define LED1 PB4 -#define BEEPER PB4 -#define INVERTER PC0 // PC0 used as inverter select GPIO -#define INVERTER_USART USART1 +#define LED0 PB5 +#define LED1 PB4 +#define BEEPER PB4 +#define INVERTER PC0 // PC0 used as inverter select GPIO +#define INVERTER_USART USART1 -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 #define ACC #define USE_ACC_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG #define GYRO #define USE_GYRO_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#define ACC_MPU6000_ALIGN CW270_DEG // MPU6000 interrupts #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC4 +#define MPU_INT_EXTI PC4 #define USE_EXTI #define MAG #define USE_MAG_HMC5883 -#define MAG_HMC5883_ALIGN CW90_DEG +#define MAG_HMC5883_ALIGN CW90_DEG //#define USE_MAG_NAZA -//#define MAG_NAZA_ALIGN CW180_DEG_FLIP +//#define MAG_NAZA_ALIGN CW180_DEG_FLIP #define BARO #define USE_BARO_MS5611 @@ -63,8 +63,8 @@ //#define USE_PITOT_MS4525 //#define MS4525_BUS I2C_DEVICE_EXT -#define M25P16_CS_PIN PB3 -#define M25P16_SPI_INSTANCE SPI3 +#define M25P16_CS_PIN PB3 +#define M25P16_SPI_INSTANCE SPI3 #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -72,22 +72,22 @@ #define USABLE_TIMER_CHANNEL_COUNT 12 #define USE_VCP -#define VBUS_SENSING_PIN PC5 +#define VBUS_SENSING_PIN PC5 #define USE_UART1 #define UART1_RX_PIN PA10 #define UART1_TX_PIN PA9 -#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 +#define UART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2 #define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 #define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 +#define SERIAL_PORT_COUNT 4 //VCP, USART1, USART3, USART6 #define USE_SPI @@ -103,22 +103,22 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC -#define CURRENT_METER_ADC_PIN PC1 -#define VBAT_ADC_PIN PC2 -#define RSSI_ADC_GPIO_PIN PA0 +#define CURRENT_METER_ADC_PIN PC1 +#define VBAT_ADC_PIN PC2 +#define RSSI_ADC_GPIO_PIN PA0 + - #define SENSORS_SET (SENSOR_ACC) -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_ONESHOT125) #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/REVONANO/target.h b/src/main/target/REVONANO/target.h index 6e461c5eb2..a298c3ed9d 100644 --- a/src/main/target/REVONANO/target.h +++ b/src/main/target/REVONANO/target.h @@ -25,24 +25,26 @@ #define USBD_SERIALNUMBER_STRING "0x8010000" #endif -#define LED0 PC14 -#define LED1 PC13 -#define BEEPER PC13 -#define INVERTER PC15 -#define INVERTER_USART USART2 //Sbus on USART 2 of nano. +#define LED0 PC14 +#define LED1 PC13 -#define MPU9250_CS_PIN PB12 -#define MPU9250_SPI_INSTANCE SPI2 +#define BEEPER PC13 + +#define INVERTER PC15 +#define INVERTER_USART USART2 //Sbus on USART 2 of nano. + +#define MPU9250_CS_PIN PB12 +#define MPU9250_SPI_INSTANCE SPI2 #define ACC #define USE_ACC_MPU9250 #define USE_ACC_SPI_MPU9250 -#define ACC_MPU9250_ALIGN CW270_DEG +#define ACC_MPU9250_ALIGN CW270_DEG #define GYRO #define USE_GYRO_MPU9250 #define USE_GYRO_SPI_MPU9250 -#define GYRO_MPU9250_ALIGN CW270_DEG +#define GYRO_MPU9250_ALIGN CW270_DEG //#define MAG //#define USE_MAG_HMC5883 @@ -54,23 +56,23 @@ #define USE_MPU_DATA_READY_SIGNAL //#define ENSURE_MPU_DATA_READY_IS_LOW #define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PA15 +#define MPU_INT_EXTI PA15 #define USE_EXTI #define USABLE_TIMER_CHANNEL_COUNT 12 #define USE_VCP -#define VBUS_SENSING_PIN PA9 +#define VBUS_SENSING_PIN PA9 #define USE_UART1 -#define UART1_RX_PIN PB7 -#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 +#define UART1_TX_PIN PB6 #define USE_UART2 -#define UART2_RX_PIN PA3 -#define UART2_TX_PIN PA2 +#define UART2_RX_PIN PA3 +#define UART2_TX_PIN PA2 -#define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2 +#define SERIAL_PORT_COUNT 3 //VCP, USART1, USART2 #define USE_SPI //#define USE_SPI_DEVICE_1 @@ -81,9 +83,9 @@ #define I2C_DEVICE (I2CDEV_3) #define USE_ADC -#define CURRENT_METER_ADC_PIN PA7 -#define VBAT_ADC_PIN PA6 -#define RSSI_ADC_PIN PA5 +#define CURRENT_METER_ADC_PIN PA7 +#define VBAT_ADC_PIN PA6 +#define RSSI_ADC_PIN PA5 #define GPS #define BLACKBOX @@ -92,10 +94,9 @@ #define USE_SERVOS #define USE_CLI -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) ) diff --git a/src/main/target/RMDO/target.h b/src/main/target/RMDO/target.h index 14fd760c8e..fadbdb874b 100644 --- a/src/main/target/RMDO/target.h +++ b/src/main/target/RMDO/target.h @@ -21,9 +21,9 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 17 @@ -39,11 +39,11 @@ #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6050_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW270_DEG #define BARO #define USE_BARO_BMP280 @@ -52,34 +52,34 @@ #define USE_FLASH_M25P16 #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_UART1 #define USE_UART2 #define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 // PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER TIM3 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 @@ -88,12 +88,12 @@ #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP @@ -109,15 +109,15 @@ #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 06e9f3cfee..09a5678174 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -21,23 +21,23 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define USABLE_TIMER_CHANNEL_COUNT 10 #define USE_EXTI -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP +#define GYRO_MPU6050_ALIGN CW0_DEG_FLIP #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW0_DEG_FLIP +#define ACC_MPU6050_ALIGN CW0_DEG_FLIP #define USE_FLASHFS #define USE_FLASH_M25P16 @@ -49,22 +49,22 @@ #define USE_SOFTSERIAL1 // Telemetry #define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 //Not connected -#define UART2_RX_PIN PA15 +#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 PB10 +#define UART3_RX_PIN PB11 -#define SOFTSERIAL_1_TIMER TIM15 +#define SOFTSERIAL_1_TIMER TIM15 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 7 //Not connected #define SOFTSERIAL_1_TIMER_TX_HARDWARE 8 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 // PA4, 5, 6, 7 @@ -81,9 +81,9 @@ #define USE_ADC -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PB2 -#define VBAT_SCALE_DEFAULT 77 +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PB2 +#define VBAT_SCALE_DEFAULT 77 #define LED_STRIP @@ -103,17 +103,17 @@ #define SPEKTRUM_BIND // USART2, PA15 -#define BIND_PIN PA15 +#define BIND_PIN PA15 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) //#define TARGET_IO_PORTF (BIT(0)|BIT(1)) // !!TODO - check the following line is correct -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h index 42f2378c66..0b2ca5f969 100644 --- a/src/main/target/SIRINFPV/target.h +++ b/src/main/target/SIRINFPV/target.h @@ -19,14 +19,14 @@ #define TARGET_BOARD_IDENTIFIER "SIRF" -#define LED0 PB2 -#define BEEPER PA1 +#define LED0 PB2 +#define BEEPER PA1 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT #define USE_EXTI #define USE_MPU_DATA_READY_SIGNAL -#define MPU_INT_EXTI PA8 +#define MPU_INT_EXTI PA8 #define ENSURE_MPU_DATA_READY_IS_LOW #define GYRO @@ -40,18 +40,18 @@ #define USE_ACC_SPI_MPU6500 // MPU6000 -#define ACC_MPU6000_ALIGN CW180_DEG -#define GYRO_MPU6000_ALIGN CW180_DEG +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG -#define MPU6000_CS_PIN PA4 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 // MPU6500 -#define ACC_MPU6500_ALIGN CW90_DEG -#define GYRO_MPU6500_ALIGN CW90_DEG +#define ACC_MPU6500_ALIGN CW90_DEG +#define GYRO_MPU6500_ALIGN CW90_DEG -#define MPU6500_CS_PIN PA4 -#define MPU6500_SPI_INSTANCE SPI1 +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 #define USB_IO @@ -59,16 +59,16 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA2 // PA14 / SWCLK -#define UART2_RX_PIN PA3 // PA15 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 // PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) #undef USE_I2C @@ -93,17 +93,17 @@ #define SPI3_MOSI_PIN PB5 #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI3 -#define MAX7456_SPI_CS_PIN PA15 +#define MAX7456_SPI_INSTANCE SPI3 +#define MAX7456_SPI_CS_PIN PA15 #define MAX7456_DMA_CHANNEL_TX DMA2_Channel2 #define MAX7456_DMA_CHANNEL_RX DMA2_Channel1 #define MAX7456_DMA_IRQ_HANDLER_ID DMA2_CH1_HANDLER #define USE_RTC6705 -#define RTC6705_SPIDATA_PIN PC15 -#define RTC6705_SPILE_PIN PC14 -#define RTC6705_SPICLK_PIN PC13 +#define RTC6705_SPIDATA_PIN PC15 +#define RTC6705_SPILE_PIN PC14 +#define RTC6705_SPICLK_PIN PC13 #define USE_SDCARD #define USE_SDCARD_SPI2 @@ -124,32 +124,33 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PA0 +#define USE_ADC +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PA0 //#define USE_QUAD_MIXER_ONLY #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + #define OSD #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define USE_SERVOS -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_BLACKBOX | FEATURE_RX_SERIAL | FEATURE_OSD | FEATURE_VTX) #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 6 -#define USED_TIMERS (TIM_N(3) | TIM_N(4)) -#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) -#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB) +#define USED_TIMERS (TIM_N(3) | TIM_N(4)) +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB) diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index f82be07689..db0528e984 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -21,30 +21,28 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB4 // Blue (Rev 1 & 2) - PB4 -#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5 +#define LED0 PB4 // Blue (Rev 1 & 2) - PB4 +#define LED1 PB5 // Green (Rev 1) / Red (Rev 2) - PB5 -#define BEEPER PA1 +#define BEEPER PA1 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 11 // MPU6050 interrupts #define USE_EXTI -#define MPU_INT_EXTI PA15 +#define MPU_INT_EXTI PA15 #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready #define USE_MPU_DATA_READY_SIGNAL // MPU 9150 INT connected to PA15, pulled up to VCC by 10K Resistor, contains MPU6050 and AK8975 in single component. #define GYRO #define USE_GYRO_MPU6050 - -#define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6050_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 - -#define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW270_DEG #define BARO #define USE_BARO_MS5611 @@ -53,22 +51,22 @@ #define MAG #define USE_MAG_AK8975 -#define MAG_AK8975_ALIGN CW180_DEG_FLIP +#define MAG_AK8975_ALIGN CW180_DEG_FLIP #define USE_VCP #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 SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PB6 // PB6 -#define UART1_RX_PIN PB7 // PB7 +#define UART1_TX_PIN PB6 +#define UART1_RX_PIN PB7 -#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input. -#define UART2_RX_PIN PA3 // PA3 +#define UART2_TX_PIN PA2 // PA2 - Clashes with PWM6 input. +#define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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? @@ -76,11 +74,11 @@ #define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4) #define USE_ADC -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA7 +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA7 -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM #define LED_STRIP #if 1 @@ -115,21 +113,19 @@ #define SPEKTRUM_BIND // USART2, PA3 -#define BIND_PIN PA3 +#define BIND_PIN PA3 //#define SONAR -//#define SONAR_ECHO_PIN PB1 -//#define SONAR_TRIGGER_PIN PA2 +//#define SONAR_ECHO_PIN PB1 +//#define SONAR_TRIGGER_PIN PA2 // available IO pins (from schematics) //#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) //#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)) // !!TODO - check following lines are correct -#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) - - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define TARGET_IO_PORTA (BIT(1)|BIT(2)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(10)|BIT(11)|BIT(12)|BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTB (BIT(0)|BIT(1)|BIT(6)|BIT(10)|BIT(11)|BIT(14)|BIT(15)|BIT(3)|BIT(4)|BIT(5)|BIT(6)|BIT(7)|BIT(8)|BIT(9)|BIT(12)|BIT(13)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index 2380fd1008..c68e8b2b21 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -21,9 +21,9 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 17 @@ -37,11 +37,11 @@ #define GYRO #define USE_GYRO_MPU6050 -#define GYRO_MPU6050_ALIGN CW270_DEG +#define GYRO_MPU6050_ALIGN CW270_DEG #define ACC #define USE_ACC_MPU6050 -#define ACC_MPU6050_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW270_DEG #define BARO #define USE_BARO_MS5611 @@ -51,37 +51,37 @@ #define MAG #define USE_MAG_AK8975 #define USE_MAG_HMC5883 -#define MAG_HMC5883_ALIGN CW270_DEG +#define MAG_HMC5883_ALIGN CW270_DEG #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define MAG_INT_EXTI PC14 +#define MAG_INT_EXTI PC14 #define USE_FLASHFS #define USE_FLASH_M25P16 #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USE_UART1 #define USE_UART2 #define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 #define SOFTSERIAL_2_TIMER TIM3 @@ -97,12 +97,12 @@ #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP @@ -121,16 +121,15 @@ #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 0bae984252..9494f612c5 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -20,10 +20,10 @@ #define TARGET_BOARD_IDENTIFIER "SPEV" #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT - -#define LED0 PB8 -#define BEEPER PC15 +#define LED0 PB8 + +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 // PPM, 8 PWM, UART3 RX/TX, LED Strip @@ -31,7 +31,7 @@ #define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect #define USE_EXTI -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW @@ -47,8 +47,8 @@ #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 -#define ACC_MPU6500_ALIGN CW180_DEG -#define GYRO_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG +#define GYRO_MPU6500_ALIGN CW180_DEG #define BARO #define USE_BARO_BMP280 @@ -68,19 +68,19 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 4 +#define SERIAL_PORT_COUNT 4 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) @@ -117,13 +117,12 @@ #define MPU6500_CS_PIN PB9 #define MPU6500_SPI_INSTANCE SPI1 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP #define USE_LED_STRIP_ON_DMA1_CHANNEL2 @@ -149,21 +148,20 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h index d76558a9c2..799da79d47 100644 --- a/src/main/target/SPRACINGF3MINI/target.h +++ b/src/main/target/SPRACINGF3MINI/target.h @@ -24,9 +24,9 @@ // early prototype had slightly different pin mappings. //#define SPRACINGF3MINI_MKII_REVA -#define LED0 PB3 +#define LED0 PB3 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 12 // 8 Outputs; PPM; LED Strip; 2 additional PWM pins also on UART3 RX/TX pins. @@ -34,24 +34,22 @@ #define EXTI15_10_CALLBACK_HANDLER_COUNT 2 // MPU_INT, SDCardDetect #define USE_EXTI -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH - #define GYRO //#define USE_FAKE_GYRO #define USE_GYRO_MPU6500 +#define GYRO_MPU6500_ALIGN CW180_DEG #define ACC //#define USE_FAKE_ACC #define USE_ACC_MPU6500 - -#define ACC_MPU6500_ALIGN CW180_DEG -#define GYRO_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG #define BARO #define USE_BARO_BMP280 @@ -60,40 +58,39 @@ #define USE_MPU9250_MAG // Enables bypass configuration #define USE_MAG_AK8975 #define USE_MAG_HMC5883 // External - -#define MAG_AK8975_ALIGN CW90_DEG_FLIP +#define MAG_AK8975_ALIGN CW90_DEG_FLIP #define SONAR -#define SONAR_ECHO_PIN PB1 -#define SONAR_TRIGGER_PIN PB0 +#define SONAR_ECHO_PIN PB1 +#define SONAR_TRIGGER_PIN PB0 #define USB_IO #define USB_CABLE_DETECTION -#define USB_DETECT_PIN PB5 +#define USB_DETECT_PIN PB5 #define USE_VCP #define USE_UART1 #define USE_UART2 #define USE_UART3 #define USE_SOFTSERIAL1 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 10 // PA1 / PAD4 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 @@ -124,10 +121,8 @@ // Performance logging for SD card operations: // #define AFATFS_USE_INTROSPECTIVE_LOGGING -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER - - +#define USE_ADC #define ADC_INSTANCE ADC2 #define VBAT_ADC_PIN PA4 #define CURRENT_METER_ADC_PIN PA5 @@ -141,7 +136,6 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC2 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER - #define TRANSPONDER #define TRANSPONDER_GPIO GPIOA #define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA @@ -158,27 +152,29 @@ #define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES FEATURE_BLACKBOX + +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define BUTTONS -#define BUTTON_A_PORT GPIOB -#define BUTTON_A_PIN Pin_1 -#define BUTTON_B_PORT GPIOB -#define BUTTON_B_PIN Pin_0 +#define BUTTON_A_PORT GPIOB +#define BUTTON_A_PIN Pin_1 +#define BUTTON_B_PORT GPIOB +#define BUTTON_B_PIN Pin_0 #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define HARDWARE_BIND_PLUG -#define BINDPLUG_PIN PB0 +#define BINDPLUG_PIN PB0 #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 8ac7eca05f..b5e9ae0e0f 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -31,12 +31,12 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PE8 // Blue LEDs - PE8/PE12 +#define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_INVERTED -#define LED1 PE10 // Orange LEDs - PE10/PE14 +#define LED1 PE10 // Orange LEDs - PE10/PE14 #define LED1_INVERTED -#define BEEPER PE9 // Red LEDs - PE9/PE13 +#define BEEPER PE9 // Red LEDs - PE9/PE13 #define BEEPER_INVERTED #define USE_SPI @@ -50,9 +50,9 @@ //#define USE_SD_CARD // -//#define SD_DETECT_PIN PC14 -//#define SD_CS_PIN PB12 -//#define SD_SPI_INSTANCE SPI2 +//#define SD_DETECT_PIN PC14 +//#define SD_CS_PIN PB12 +//#define SD_SPI_INSTANCE SPI2 //#define USE_FLASHFS //#define USE_FLASH_M25P16 @@ -74,9 +74,9 @@ #define GYRO #define USE_GYRO_L3GD20 -#define L3GD20_SPI SPI1 -#define L3GD20_CS_PIN PE3 -#define GYRO_L3GD20_ALIGN CW270_DEG +#define L3GD20_SPI SPI1 +#define L3GD20_CS_PIN PE3 +#define GYRO_L3GD20_ALIGN CW270_DEG // Support the GY-91 MPU9250 dev board #define USE_GYRO_MPU6500 @@ -92,21 +92,21 @@ #define ACC_MPU6500_ALIGN CW270_DEG_FLIP //#define BARO -//#define BMP280_CS_PIN PB12 -//#define BMP280_SPI_INSTANCE SPI2 +//#define BMP280_CS_PIN PB12 +//#define BMP280_SPI_INSTANCE SPI2 //#define USE_BARO_BMP280 //#define USE_BARO_SPI_BMP280 #define OSD #define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI2 -#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN //#define USE_SDCARD //#define USE_SDCARD_SPI2 // -//#define SDCARD_SPI_INSTANCE SPI2 -//#define SDCARD_SPI_CS_PIN PB12 +//#define SDCARD_SPI_INSTANCE SPI2 +//#define SDCARD_SPI_CS_PIN PB12 //// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: //#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 //// Divide to under 25MHz for normal operation: @@ -125,7 +125,7 @@ #define USE_VCP #define USE_UART1 #define USE_UART2 -#define SERIAL_PORT_COUNT 3 +#define SERIAL_PORT_COUNT 3 // uart2 gpio for shared serial rx/ppm //#define UART2_TX_PIN GPIO_Pin_5 // PD5 @@ -139,11 +139,11 @@ #define I2C_DEVICE (I2CDEV_1) #define USE_ADC -#define ADC_INSTANCE ADC1 -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 +#define ADC_INSTANCE ADC1 +#define VBAT_ADC_PIN PC0 +#define CURRENT_METER_ADC_PIN PC1 +#define RSSI_ADC_PIN PC2 +#define EXTERNAL1_ADC_PIN PC3 #define LED_STRIP #define WS2811_PIN PB8 // TIM16_CH1 @@ -153,19 +153,18 @@ #define WS2811_DMA_TC_FLAG DMA1_FLAG_TC3 #define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER -#define LED_STRIP -#define LED_STRIP_TIMER TIM16 +#define LED_STRIP_TIMER TIM16 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - 303 in 100pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0x00ff +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD 0xffff +#define TARGET_IO_PORTE 0xffff +#define TARGET_IO_PORTF 0x00ff -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 4a38e233fb..024a3a6c28 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -22,33 +22,31 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE -#define LED0 PC14 -#define BEEPER PC15 +#define LED0 PC14 +#define BEEPER PC15 #define BEEPER_INVERTED #define USABLE_TIMER_CHANNEL_COUNT 17 - - #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define MPU6000_CS_PIN PA15 -#define MPU6000_SPI_INSTANCE SPI1 +#define MPU6000_CS_PIN PA15 +#define MPU6000_SPI_INSTANCE SPI1 #define GYRO #define USE_GYRO_SPI_MPU6000 -#define GYRO_MPU6000_ALIGN CW270_DEG +#define GYRO_MPU6000_ALIGN CW270_DEG #define ACC #define USE_ACC_SPI_MPU6000 -#define ACC_MPU6000_ALIGN CW270_DEG +#define ACC_MPU6000_ALIGN CW270_DEG // MPU6000 interrupts #define USE_MPU_DATA_READY_SIGNAL #define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready (mag disabled) -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_EXTI @@ -60,27 +58,27 @@ #define USE_UART3 #define USE_SOFTSERIAL1 #define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 +#define SERIAL_PORT_COUNT 5 -#define UART1_TX_PIN PA9 // PA9 -#define UART1_RX_PIN PA10 // PA10 +#define UART1_TX_PIN PA9 +#define UART1_RX_PIN PA10 -#define UART2_TX_PIN PA2 // PA14 / SWCLK -#define UART2_RX_PIN PA3 // PA15 +#define UART2_TX_PIN PA2 // PA14 / SWCLK +#define UART2_RX_PIN PA3 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#define UART3_TX_PIN PB10 // PB10 (AF7) +#define UART3_RX_PIN PB11 // PB11 (AF7) -#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER TIM3 #define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 #define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER TIM3 #define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 #define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 #define USE_I2C -#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 @@ -100,12 +98,12 @@ #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 #define LED_STRIP @@ -119,21 +117,20 @@ #define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES FEATURE_BLACKBOX +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES FEATURE_BLACKBOX #define SPEKTRUM_BIND // USART3, -#define BIND_PIN PB11 +#define BIND_PIN PB11 #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/ZCOREF3/target.h b/src/main/target/ZCOREF3/target.h index dc9f80cb23..c65abb7d92 100644 --- a/src/main/target/ZCOREF3/target.h +++ b/src/main/target/ZCOREF3/target.h @@ -21,32 +21,30 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT -#define LED0 PB8 +#define LED0 PB8 -#define BEEPER PC15 +#define BEEPER PC15 #define BEEPER_INVERTED #define EXTI15_10_CALLBACK_HANDLER_COUNT 1 #define USE_EXTI -#define MPU_INT_EXTI PC13 +#define MPU_INT_EXTI PC13 #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH - #define GYRO #define USE_GYRO_MPU6500 #define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW180_DEG #define ACC #define USE_ACC_MPU6500 #define USE_ACC_SPI_MPU6500 - -#define ACC_MPU6500_ALIGN CW180_DEG -#define GYRO_MPU6500_ALIGN CW180_DEG +#define ACC_MPU6500_ALIGN CW180_DEG #define BARO #define USE_BARO_BMP280 @@ -54,17 +52,17 @@ #define USE_UART1 #define USE_UART2 #define USE_UART3 -#define SERIAL_PORT_COUNT 3 +#define SERIAL_PORT_COUNT 3 -#define UART2_TX_PIN PA14 // PA14 / SWCLK -#define UART2_RX_PIN PA15 // PA15 +#define UART2_TX_PIN PA14 // PA14 / SWCLK +#define UART2_RX_PIN PA15 -#define UART3_TX_PIN PB10 // PB10 (AF7) -#define UART3_RX_PIN PB11 // PB11 (AF7) +#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 +#define I2C_DEVICE (I2CDEV_1) // PB6/SCL, PB7/SDA #define USE_SPI #define USE_SPI_DEVICE_1 // PB9,3,4,5 on AF5 SPI1 (MPU) @@ -74,7 +72,7 @@ #define SPI1_SCK_PIN PB3 #define SPI1_MISO_PIN PB4 #define SPI1_MOSI_PIN PB5 - + #define MPU6500_CS_PIN PB9 #define MPU6500_SPI_INSTANCE SPI1 @@ -84,25 +82,25 @@ #define M25P16_CS_PIN PB12 #define M25P16_SPI_INSTANCE SPI2 -#define USE_ADC #define BOARD_HAS_VOLTAGE_DIVIDER -#define ADC_INSTANCE ADC2 -#define VBAT_ADC_PIN PA4 -#define CURRENT_METER_ADC_PIN PA5 -#define RSSI_ADC_PIN PB2 +#define USE_ADC +#define ADC_INSTANCE ADC2 +#define VBAT_ADC_PIN PA4 +#define CURRENT_METER_ADC_PIN PA5 +#define RSSI_ADC_PIN PB2 -#define DEFAULT_RX_FEATURE FEATURE_RX_PPM -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM +#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_BLACKBOX | FEATURE_RSSI_ADC | FEATURE_CURRENT_METER | FEATURE_TELEMETRY) #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 17 // PPM, 8 PWM, UART3 RX/TX, LED Strip -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/common.h b/src/main/target/common.h index c9a9a0f1b3..65ab02c871 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -14,7 +14,7 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - + #pragma once #define I2C1_OVERCLOCK true diff --git a/src/main/target/system_stm32f30x.c b/src/main/target/system_stm32f30x.c index 09ba3fa47c..5d62e47aa3 100644 --- a/src/main/target/system_stm32f30x.c +++ b/src/main/target/system_stm32f30x.c @@ -9,17 +9,17 @@ * and is generated by the clock configuration tool * stm32f30x_Clock_Configuration_V1.0.0.xls * - * 1. This file provides two functions and one global variable to be called from + * 1. This file provides two functions and one global variable to be called from * user application: * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier * and Divider factors, AHB/APBx prescalers and Flash settings), - * depending on the configuration made in the clock xls tool. - * This function is called at startup just after reset and + * depending on the configuration made in the clock xls tool. + * This function is called at startup just after reset and * before branch to main program. This call is made inside * the "startup_stm32f30x.s" file. * * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used - * by the user application to setup the SysTick + * by the user application to setup the SysTick * timer or configure other parameters. * * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must @@ -31,7 +31,7 @@ * configure the system clock before to branch to main program. * * 3. If the system clock source selected by user fails to startup, the SystemInit() - * function will do nothing and HSI still used as system clock source. User can + * function will do nothing and HSI still used as system clock source. User can * add some code to deal with this issue inside the SetSysClock() function. * * 4. The default value of HSE crystal is set to 8MHz, refer to "HSE_VALUE" define @@ -79,8 +79,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. @@ -93,8 +93,8 @@ /** @addtogroup stm32f30x_system * @{ - */ - + */ + /** @addtogroup STM32F30x_System_Private_Includes * @{ */ @@ -113,13 +113,13 @@ uint32_t hse_value = HSE_VALUE; * @{ */ /*!< Uncomment the following line if you need to relocate your vector Table in - Internal SRAM. */ + Internal SRAM. */ /* #define VECT_TAB_SRAM */ -#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. - This value must be a multiple of 0x200. */ +#define VECT_TAB_OFFSET 0x0 /*!< Vector Table base offset field. + This value must be a multiple of 0x200. */ /** * @} - */ + */ /* Private macro -------------------------------------------------------------*/ @@ -151,7 +151,7 @@ void SetSysClock(void); /** * @brief Setup the microcontroller system - * Initialize the Embedded Flash Interface, the PLL and update the + * Initialize the Embedded Flash Interface, the PLL and update the * SystemFrequency variable. * @param None * @retval None @@ -184,19 +184,19 @@ void SystemInit(void) /* Reset USARTSW[1:0], I2CSW and TIMs bits */ RCC->CFGR3 &= (uint32_t)0xFF00FCCC; - + /* Disable all interrupts */ RCC->CIR = 0x00000000; - /* Configure the System clock source, PLL Multiplier and Divider factors, + /* Configure the System clock source, PLL Multiplier and Divider factors, AHB/APBx prescalers and Flash settings ----------------------------------*/ //SetSysClock(); // called from main() - + #ifdef VECT_TAB_SRAM SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM. */ #else SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH. */ -#endif +#endif } /** @@ -204,25 +204,25 @@ void SystemInit(void) * The SystemCoreClock variable contains the core clock (HCLK), it can * be used by the user application to setup the SysTick timer or configure * other parameters. - * + * * @note Each time the core clock (HCLK) changes, this function must be called * to update SystemCoreClock variable value. Otherwise, any configuration - * based on this variable will be incorrect. - * - * @note - The system frequency computed by this function is not the real - * frequency in the chip. It is calculated based on the predefined + * based on this variable will be incorrect. + * + * @note - The system frequency computed by this function is not the real + * frequency in the chip. It is calculated based on the predefined * constant and the selected clock source: * * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*) * * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**) * - * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) + * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**) * or HSI_VALUE(*) multiplied/divided by the PLL factors. - * + * * (*) HSI_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz) but the real value may vary depending on the variations - * in voltage and temperature. + * in voltage and temperature. * * (**) HSE_VALUE is a constant defined in stm32f30x.h file (default value * 8 MHz), user has to ensure that HSE_VALUE is same as the real @@ -231,7 +231,7 @@ void SystemInit(void) * * - The result of this function could be not correct when using fractional * value for HSE crystal. - * + * * @param None * @retval None */ @@ -241,7 +241,7 @@ void SystemCoreClockUpdate (void) /* Get SYSCLK source -------------------------------------------------------*/ tmp = RCC->CFGR & RCC_CFGR_SWS; - + switch (tmp) { case 0x00: /* HSI used as system clock */ @@ -255,7 +255,7 @@ void SystemCoreClockUpdate (void) pllmull = RCC->CFGR & RCC_CFGR_PLLMULL; pllsource = RCC->CFGR & RCC_CFGR_PLLSRC; pllmull = ( pllmull >> 18) + 2; - + if (pllsource == 0x00) { /* HSI oscillator clock divided by 2 selected as PLL clock entry */ @@ -265,8 +265,8 @@ void SystemCoreClockUpdate (void) { prediv1factor = (RCC->CFGR2 & RCC_CFGR2_PREDIV1) + 1; /* HSE oscillator clock selected as PREDIV1 clock entry */ - SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; - } + SystemCoreClock = (HSE_VALUE / prediv1factor) * pllmull; + } break; default: /* HSI used as system clock */ SystemCoreClock = HSI_VALUE; @@ -276,7 +276,7 @@ void SystemCoreClockUpdate (void) /* Get HCLK prescaler */ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)]; /* HCLK clock frequency */ - SystemCoreClock >>= tmp; + SystemCoreClock >>= tmp; } /** @@ -298,7 +298,7 @@ void SetSysClock(void) /* SYSCLK, HCLK, PCLK2 and PCLK1 configuration -----------*/ /* Enable HSE */ RCC->CR |= ((uint32_t)RCC_CR_HSEON); - + /* Wait till HSE is ready and if Time out is reached exit */ do { @@ -319,13 +319,13 @@ void SetSysClock(void) { /* Enable Prefetch Buffer and set Flash Latency */ FLASH->ACR = FLASH_ACR_PRFTBE | (uint32_t)FLASH_ACR_LATENCY_1; - + /* HCLK = SYSCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_HPRE_DIV1; - + /* PCLK2 = HCLK / 1 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE2_DIV1; - + /* PCLK1 = HCLK / 2 */ RCC->CFGR |= (uint32_t)RCC_CFGR_PPRE1_DIV2; diff --git a/src/main/target/system_stm32f30x.h b/src/main/target/system_stm32f30x.h index 4f999d3058..b213ad0b1e 100644 --- a/src/main/target/system_stm32f30x.h +++ b/src/main/target/system_stm32f30x.h @@ -4,7 +4,7 @@ * @author MCD Application Team * @version V1.1.1 * @date 28-March-2014 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. + * @brief CMSIS Cortex-M4 Device System Source File for STM32F30x devices. ****************************************************************************** * @attention * @@ -16,8 +16,8 @@ * * http://www.st.com/software_license_agreement_liberty_v2 * - * Unless required by applicable law or agreed to in writing, software - * distributed under the License is distributed on an "AS IS" BASIS, + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. * See the License for the specific language governing permissions and * limitations under the License. @@ -31,8 +31,8 @@ /** @addtogroup stm32f30x_system * @{ - */ - + */ + /** * @brief Define to prevent recursive inclusion */ @@ -41,7 +41,7 @@ #ifdef __cplusplus extern "C" { -#endif +#endif /* Exported types ------------------------------------------------------------*/ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */ @@ -52,7 +52,7 @@ extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Cloc /** @addtogroup STM32F30x_System_Exported_Functions * @{ */ - + extern void SystemInit(void); extern void SystemCoreClockUpdate(void); @@ -69,8 +69,8 @@ extern void SystemCoreClockUpdate(void); /** * @} */ - + /** * @} - */ + */ /************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/target/system_stm32f4xx.h b/src/main/target/system_stm32f4xx.h index e266366801..45c811bb06 100644 --- a/src/main/target/system_stm32f4xx.h +++ b/src/main/target/system_stm32f4xx.h @@ -4,8 +4,8 @@ * @author MCD Application Team * @version V1.6.1 * @date 21-October-2015 - * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. - ****************************************************************************** + * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices. + ****************************************************************************** * @attention * *

© COPYRIGHT 2015 STMicroelectronics

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

© COPYRIGHT 2011 STMicroelectronics

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

© COPYRIGHT 2011 STMicroelectronics

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

© COPYRIGHT 2011 STMicroelectronics

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

© COPYRIGHT 2011 STMicroelectronics

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