From 8e9be424cecbbc51b20d026c1710ece9a1287ae5 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 19 Feb 2017 17:28:29 +1100 Subject: [PATCH 1/3] Removed more target specific conditionals from the main codebase --- src/main/drivers/accgyro_mma845x.c | 10 ++--- src/main/drivers/compass_hmc5883l.c | 21 ++++----- src/main/drivers/compass_hmc5883l.h | 6 +-- src/main/drivers/vtx_rtc6705.c | 2 +- src/main/fc/config.c | 55 +++++------------------ src/main/sensors/acceleration.c | 9 ---- src/main/sensors/barometer.c | 6 --- src/main/sensors/compass.c | 29 +----------- src/main/sensors/compass.h | 4 +- src/main/target/CC3D/config.c | 42 +++++++++++++++++ src/main/target/CC3D/target.h | 1 + src/main/target/CHEBUZZF3/config.c | 31 +++++++++++++ src/main/target/COLIBRI_RACE/config.c | 13 ++++++ src/main/target/COLIBRI_RACE/i2c_bst.c | 4 -- src/main/target/COLIBRI_RACE/target.h | 1 + src/main/target/NAZE/config.c | 20 +++++++++ src/main/target/NAZE/target.h | 13 ++---- src/main/target/STM32F3DISCOVERY/config.c | 32 +++++++++++++ 18 files changed, 177 insertions(+), 122 deletions(-) create mode 100644 src/main/target/CC3D/config.c create mode 100644 src/main/target/CHEBUZZF3/config.c create mode 100644 src/main/target/STM32F3DISCOVERY/config.c diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 96fed71c3b..d61e4b666c 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -83,12 +83,10 @@ static uint8_t device_id; static inline void mma8451ConfigureInterrupt(void) { -#ifdef NAZE - // PA5 - ACC_INT2 output on NAZE rev3/4 hardware - // NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board - // OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code. - IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU_EXTI, 0); - IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? +#ifdef MMA8451_INT_PIN + IOInit(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), OWNER_MPU_EXTI, 0); + // TODO - maybe pullup / pulldown ? + IOConfigGPIO(IOGetByTag(IO_TAG(MMA8451_INT_PIN)), IOCFG_IN_FLOATING); #endif i2cWrite(MPU_I2C_INSTANCE, MMA8452_ADDRESS, MMA8452_CTRL_REG3, MMA8452_CTRL_REG3_IPOL); // Interrupt polarity (active HIGH) diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index ff0cd12d22..cfb160f031 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -119,11 +119,9 @@ static float magGain[3] = { 1.0f, 1.0f, 1.0f }; -static const hmc5883Config_t *hmc5883Config = NULL; - #ifdef USE_MAG_DATA_READY_SIGNAL -static IO_t intIO; +static IO_t hmc5883InterruptIO; static extiCallbackRec_t hmc5883_extiCallbackRec; static void hmc5883_extiHandler(extiCallbackRec_t* cb) @@ -150,20 +148,19 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void) { #ifdef USE_MAG_DATA_READY_SIGNAL - if (!(hmc5883Config->intTag)) { + if (!(hmc5883InterruptIO)) { return; } - intIO = IOGetByTag(hmc5883Config->intTag); #ifdef ENSURE_MAG_DATA_READY_IS_HIGH - uint8_t status = IORead(intIO); + uint8_t status = IORead(hmc5883InterruptIO); if (!status) { return; } #endif EXTIHandlerInit(&hmc5883_extiCallbackRec, hmc5883_extiHandler); - EXTIConfig(intIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising); - EXTIEnable(intIO, true); + EXTIConfig(hmc5883InterruptIO, &hmc5883_extiCallbackRec, NVIC_PRIO_MAG_INT_EXTI, EXTI_Trigger_Rising); + EXTIEnable(hmc5883InterruptIO, true); #endif } @@ -257,9 +254,13 @@ static bool hmc5883lInit(void) return true; } -bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse) +bool hmc5883lDetect(magDev_t* mag, ioTag_t interruptTag) { - hmc5883Config = hmc5883ConfigToUse; +#ifdef USE_MAG_DATA_READY_SIGNAL + hmc5883InterruptIO = IOGetByTag(interruptTag); +#else + UNUSED(interruptTag); +#endif uint8_t sig = 0; bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig); diff --git a/src/main/drivers/compass_hmc5883l.h b/src/main/drivers/compass_hmc5883l.h index 9028143afc..0be30a9dc0 100644 --- a/src/main/drivers/compass_hmc5883l.h +++ b/src/main/drivers/compass_hmc5883l.h @@ -19,8 +19,4 @@ #include "io_types.h" -typedef struct hmc5883Config_s { - ioTag_t intTag; -} hmc5883Config_t; - -bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse); +bool hmc5883lDetect(magDev_t* mag, ioTag_t interruptTag); diff --git a/src/main/drivers/vtx_rtc6705.c b/src/main/drivers/vtx_rtc6705.c index 36e6be4d54..59aa7c2f7d 100644 --- a/src/main/drivers/vtx_rtc6705.c +++ b/src/main/drivers/vtx_rtc6705.c @@ -87,7 +87,7 @@ #define DISABLE_RTC6705 GPIO_SetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN) #define ENABLE_RTC6705 GPIO_ResetBits(RTC6705_CS_GPIO, RTC6705_CS_PIN) -#if defined(SPRACINGF3NEO) +#ifdef RTC6705_POWER_PIN static IO_t vtxPowerPin = IO_NONE; #endif diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 3b0d7485b9..4068606c86 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -117,6 +117,16 @@ static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims) accelerometerTrims->values.yaw = 0; } +static void resetCompassConfig(compassConfig_t* compassConfig) +{ + compassConfig->mag_align = ALIGN_DEFAULT; +#ifdef MAG_INT_EXTI + compassConfig->interruptTag = IO_TAG(MAG_INT_EXTI); +#else + compassConfig->interruptTag = IO_TAG_NONE; +#endif +} + static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) { controlRateConfig->rcRate8 = 100; @@ -642,7 +652,8 @@ void createDefaultConfig(master_t *config) config->gyroConfig.gyro_align = ALIGN_DEFAULT; config->accelerometerConfig.acc_align = ALIGN_DEFAULT; - config->compassConfig.mag_align = ALIGN_DEFAULT; + + resetCompassConfig(&config->compassConfig); config->boardAlignment.rollDegrees = 0; config->boardAlignment.pitchDegrees = 0; @@ -954,12 +965,6 @@ void validateAndFixConfig(void) featureClear(FEATURE_CURRENT_METER); } #endif - -#if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY) - // led strip needs the same ports - featureClear(FEATURE_LED_STRIP); -#endif - // software serial needs free PWM ports featureClear(FEATURE_SOFTSERIAL); } @@ -979,42 +984,6 @@ void validateAndFixConfig(void) } #endif -#if defined(NAZE) && defined(SONAR) - if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) { - featureClear(FEATURE_CURRENT_METER); - } -#endif - -#if defined(OLIMEXINO) && defined(SONAR) - if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) { - featureClear(FEATURE_CURRENT_METER); - } -#endif - -#if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3) - if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) { - featureClear(FEATURE_DASHBOARD); - } -#endif - -#if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO) - // shared pin - if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) { - featureClear(FEATURE_SONAR); - featureClear(FEATURE_SOFTSERIAL); - featureClear(FEATURE_RSSI_ADC); - } -#endif - -#if defined(COLIBRI_RACE) - serialConfig()->portConfigs[0].functionMask = FUNCTION_MSP; - if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) { - featureClear(FEATURE_RX_PARALLEL_PWM); - featureClear(FEATURE_RX_MSP); - featureSet(FEATURE_RX_PPM); - } -#endif - useRxConfig(&masterConfig.rxConfig); serialConfig_t *serialConfig = &masterConfig.serialConfig; diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index f9af837dc8..c664aa2b5f 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -98,11 +98,7 @@ retry: #ifdef USE_ACC_ADXL345 acc_params.useFifo = false; acc_params.dataRate = 800; // unused currently -#ifdef NAZE - if (hardwareRevision < NAZE32_REV5 && adxl345Detect(&acc_params, dev)) { -#else if (adxl345Detect(&acc_params, dev)) { -#endif #ifdef ACC_ADXL345_ALIGN dev->accAlign = ACC_ADXL345_ALIGN; #endif @@ -135,12 +131,7 @@ retry: ; // fallthrough case ACC_MMA8452: // MMA8452 #ifdef USE_ACC_MMA8452 -#ifdef NAZE - // Not supported with this frequency - if (hardwareRevision < NAZE32_REV5 && mma8452Detect(dev)) { -#else if (mma8452Detect(dev)) { -#endif #ifdef ACC_MMA8452_ALIGN dev->accAlign = ACC_MMA8452_ALIGN; #endif diff --git a/src/main/sensors/barometer.c b/src/main/sensors/barometer.c index 4b25477dc5..d5a130df4e 100644 --- a/src/main/sensors/barometer.c +++ b/src/main/sensors/barometer.c @@ -71,12 +71,6 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse) bmp085Config = &defaultBMP085Config; #endif -#ifdef NAZE - if (hardwareRevision == NAZE32) { - bmp085Disable(bmp085Config); - } -#endif - #endif switch (baroHardware) { diff --git a/src/main/sensors/compass.c b/src/main/sensors/compass.c index 2c012a944e..33393463cc 100644 --- a/src/main/sensors/compass.c +++ b/src/main/sensors/compass.c @@ -56,33 +56,6 @@ bool compassDetect(magDev_t *dev, magSensor_e magHardwareToUse) { magSensor_e magHardware; -#ifdef USE_MAG_HMC5883 - const hmc5883Config_t *hmc5883Config = 0; - -#ifdef NAZE // TODO remove this target specific define - static const hmc5883Config_t nazeHmc5883Config_v1_v4 = { - .intTag = IO_TAG(PB12) /* perhaps disabled? */ - }; - static const hmc5883Config_t nazeHmc5883Config_v5 = { - .intTag = IO_TAG(MAG_INT_EXTI) - }; - if (hardwareRevision < NAZE32_REV5) { - hmc5883Config = &nazeHmc5883Config_v1_v4; - } else { - hmc5883Config = &nazeHmc5883Config_v5; - } -#endif - -#ifdef MAG_INT_EXTI - static const hmc5883Config_t extiHmc5883Config = { - .intTag = IO_TAG(MAG_INT_EXTI) - }; - - hmc5883Config = &extiHmc5883Config; -#endif - -#endif - retry: dev->magAlign = ALIGN_DEFAULT; @@ -93,7 +66,7 @@ retry: case MAG_HMC5883: #ifdef USE_MAG_HMC5883 - if (hmc5883lDetect(dev, hmc5883Config)) { + if (hmc5883lDetect(dev, compassConfig()->interruptTag)) { #ifdef MAG_HMC5883_ALIGN dev->magAlign = MAG_HMC5883_ALIGN; #endif diff --git a/src/main/sensors/compass.h b/src/main/sensors/compass.h index 7f4002fc64..6194743330 100644 --- a/src/main/sensors/compass.h +++ b/src/main/sensors/compass.h @@ -18,10 +18,11 @@ #pragma once #include "config/parameter_group.h" + +#include "drivers/io.h" #include "drivers/sensor.h" #include "sensors/sensors.h" - // Type of magnetometer used/detected typedef enum { MAG_DEFAULT = 0, @@ -43,6 +44,7 @@ typedef struct compassConfig_s { // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero. sensor_align_e mag_align; // mag alignment uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device + ioTag_t interruptTag; flightDynamicsTrims_t magZero; } compassConfig_t; diff --git a/src/main/target/CC3D/config.c b/src/main/target/CC3D/config.c new file mode 100644 index 0000000000..5e35e33729 --- /dev/null +++ b/src/main/target/CC3D/config.c @@ -0,0 +1,42 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "config/config_master.h" +#include "config/feature.h" +#include "sensors/battery.h" + +void targetValidateConfiguration(master_t *config) +{ + UNUSED(config); + +#if defined(DISPLAY) && defined(USE_UART3) + if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) { + featureClear(FEATURE_DASHBOARD); + } +#endif + +#if defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO) + // shared pin + if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) { + featureClear(FEATURE_SONAR); + featureClear(FEATURE_SOFTSERIAL); + featureClear(FEATURE_RSSI_ADC); + } +#endif +} \ No newline at end of file diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 9871d0cf46..2eea75aafe 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -16,6 +16,7 @@ */ #define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D +#define TARGET_VALIDATECONFIG #define LED0 PB3 diff --git a/src/main/target/CHEBUZZF3/config.c b/src/main/target/CHEBUZZF3/config.c new file mode 100644 index 0000000000..a5b03052f3 --- /dev/null +++ b/src/main/target/CHEBUZZF3/config.c @@ -0,0 +1,31 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include + +#include "config/config_master.h" +#include "config/feature.h" + +void targetValidateConfiguration(master_t *config) +{ + UNUSED(config); + + if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { + // led strip needs the same ports + featureClear(FEATURE_LED_STRIP); + } +} diff --git a/src/main/target/COLIBRI_RACE/config.c b/src/main/target/COLIBRI_RACE/config.c index 826bd10adf..389d5f4edb 100644 --- a/src/main/target/COLIBRI_RACE/config.c +++ b/src/main/target/COLIBRI_RACE/config.c @@ -21,6 +21,7 @@ #include #include "common/maths.h" +#include "common/utils.h" #include "config/config_master.h" #include "config/feature.h" @@ -99,3 +100,15 @@ void targetConfiguration(master_t *config) targetApplyDefaultLedStripConfig(config->ledStripConfig.ledConfigs); } + +void targetValidateConfiguration(master_t *config) +{ + UNUSED(config); + + serialConfig()->portConfigs[0].functionMask = FUNCTION_MSP; + if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) { + featureClear(FEATURE_RX_PARALLEL_PWM); + featureClear(FEATURE_RX_MSP); + featureSet(FEATURE_RX_PPM); + } +} \ No newline at end of file diff --git a/src/main/target/COLIBRI_RACE/i2c_bst.c b/src/main/target/COLIBRI_RACE/i2c_bst.c index 3d84971bc5..b6070664c2 100644 --- a/src/main/target/COLIBRI_RACE/i2c_bst.c +++ b/src/main/target/COLIBRI_RACE/i2c_bst.c @@ -70,10 +70,6 @@ #include "config/config_master.h" #include "config/feature.h" -#ifdef NAZE -#include "hardware_revision.h" -#endif - #include "bus_bst.h" #include "i2c_bst.h" diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index 7fe59629f3..f3bcaa73a3 100755 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -21,6 +21,7 @@ #define BST_DEVICE_NAME "COLIBRI RACE" #define BST_DEVICE_NAME_LENGTH 12 #define TARGET_CONFIG +#define TARGET_VALIDATECONFIG #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index 3319fa9cf1..a3e1220136 100755 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -96,5 +96,25 @@ void targetConfiguration(master_t *config) config->flashConfig.csTag = IO_TAG_NONE; } #endif + +#ifdef MAG_INT_EXTI + if (hardwareRevision < NAZE32_REV5) { + config->compassConfig.interruptTag = IO_TAG(PB12); + } +#endif } +void targetValidateConfiguration(master_t *config) +{ + UNUSED(config); + +#if defined(SONAR) + if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) { + featureClear(FEATURE_CURRENT_METER); + } +#endif + + if (hardwareRevision < NAZE32_REV5 && config->accelerometerConfig.acc_hardware == ACC_ADXL345) { + config->accelerometerConfig.acc_hardware = ACC_NONE; + } +} \ No newline at end of file diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 315faf2fe5..fae72941b0 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -18,6 +18,7 @@ #pragma once #define TARGET_CONFIG +#define TARGET_VALIDATECONFIG #define USE_HARDWARE_REVISION_DETECTION #define TARGET_BUS_INIT @@ -49,16 +50,10 @@ #define USE_EXTI #define MAG_INT_EXTI PC14 #define MPU_INT_EXTI PC13 -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL -//#define DEBUG_MAG_DATA_READY_INTERRUPT -#define USE_MAG_DATA_READY_SIGNAL +#define MMA8451_INT_PIN PA5 -// SPI2 -// PB15 28 SPI2_MOSI -// PB14 27 SPI2_MISO -// PB13 26 SPI2_SCK -// PB12 25 SPI2_NSS +#define USE_MPU_DATA_READY_SIGNAL +#define USE_MAG_DATA_READY_SIGNAL #define USE_SPI #define USE_SPI_DEVICE_2 diff --git a/src/main/target/STM32F3DISCOVERY/config.c b/src/main/target/STM32F3DISCOVERY/config.c new file mode 100644 index 0000000000..61e9bbcab1 --- /dev/null +++ b/src/main/target/STM32F3DISCOVERY/config.c @@ -0,0 +1,32 @@ +/* + * This file is part of Cleanflight. + * + * Cleanflight is free software: you can redistribute it and/or modify + * it under the terms of the GNU General Public License as published by + * the Free Software Foundation, either version 3 of the License, or + * (at your option) any later version. + * + * Cleanflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Cleanflight. If not, see . + */ + +#include +#include + +#include "config/config_master.h" +#include "config/feature.h" + +void targetValidateConfiguration(master_t *config) +{ + UNUSED(config); + + if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { + // led strip needs the same ports + featureClear(FEATURE_LED_STRIP); + } +} \ No newline at end of file From d8e8fbf2713e0d41b744ff5e91d8f5fcf33f49a1 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 19 Feb 2017 17:57:34 +1100 Subject: [PATCH 2/3] Whitespace cleanup --- src/main/target/NAZE/config.c | 2 +- src/main/target/NAZE/target.h | 2 +- src/main/target/STM32F3DISCOVERY/config.c | 5 ++--- 3 files changed, 4 insertions(+), 5 deletions(-) diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index a3e1220136..542f7f6c5c 100755 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -117,4 +117,4 @@ void targetValidateConfiguration(master_t *config) if (hardwareRevision < NAZE32_REV5 && config->accelerometerConfig.acc_hardware == ACC_ADXL345) { config->accelerometerConfig.acc_hardware = ACC_NONE; } -} \ No newline at end of file +} diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index fae72941b0..e44b813f3e 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -50,7 +50,7 @@ #define USE_EXTI #define MAG_INT_EXTI PC14 #define MPU_INT_EXTI PC13 -#define MMA8451_INT_PIN PA5 +#define MMA8451_INT_PIN PA5 #define USE_MPU_DATA_READY_SIGNAL #define USE_MAG_DATA_READY_SIGNAL diff --git a/src/main/target/STM32F3DISCOVERY/config.c b/src/main/target/STM32F3DISCOVERY/config.c index 61e9bbcab1..167086b363 100644 --- a/src/main/target/STM32F3DISCOVERY/config.c +++ b/src/main/target/STM32F3DISCOVERY/config.c @@ -15,7 +15,6 @@ * along with Cleanflight. If not, see . */ -#include #include #include "config/config_master.h" @@ -23,10 +22,10 @@ void targetValidateConfiguration(master_t *config) { - UNUSED(config); + UNUSED(config); if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { // led strip needs the same ports featureClear(FEATURE_LED_STRIP); } -} \ No newline at end of file +} From 4c3e4962595a5649433818dbe1e5f9364f0ddef3 Mon Sep 17 00:00:00 2001 From: blckmn Date: Sun, 19 Feb 2017 19:12:58 +1100 Subject: [PATCH 3/3] Removing unnecessary target config - resource management takes care of it --- src/main/target/CC3D/config.c | 42 ----------------------- src/main/target/CC3D/target.h | 1 - src/main/target/CHEBUZZF3/config.c | 31 ----------------- src/main/target/NAZE/config.c | 6 ---- src/main/target/STM32F3DISCOVERY/config.c | 31 ----------------- 5 files changed, 111 deletions(-) delete mode 100644 src/main/target/CC3D/config.c delete mode 100644 src/main/target/CHEBUZZF3/config.c delete mode 100644 src/main/target/STM32F3DISCOVERY/config.c diff --git a/src/main/target/CC3D/config.c b/src/main/target/CC3D/config.c deleted file mode 100644 index 5e35e33729..0000000000 --- a/src/main/target/CC3D/config.c +++ /dev/null @@ -1,42 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include - -#include "config/config_master.h" -#include "config/feature.h" -#include "sensors/battery.h" - -void targetValidateConfiguration(master_t *config) -{ - UNUSED(config); - -#if defined(DISPLAY) && defined(USE_UART3) - if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) { - featureClear(FEATURE_DASHBOARD); - } -#endif - -#if defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO) - // shared pin - if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) { - featureClear(FEATURE_SONAR); - featureClear(FEATURE_SOFTSERIAL); - featureClear(FEATURE_RSSI_ADC); - } -#endif -} \ No newline at end of file diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index 2eea75aafe..9871d0cf46 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -16,7 +16,6 @@ */ #define TARGET_BOARD_IDENTIFIER "CC3D" // CopterControl 3D -#define TARGET_VALIDATECONFIG #define LED0 PB3 diff --git a/src/main/target/CHEBUZZF3/config.c b/src/main/target/CHEBUZZF3/config.c deleted file mode 100644 index a5b03052f3..0000000000 --- a/src/main/target/CHEBUZZF3/config.c +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include - -#include "config/config_master.h" -#include "config/feature.h" - -void targetValidateConfiguration(master_t *config) -{ - UNUSED(config); - - if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { - // led strip needs the same ports - featureClear(FEATURE_LED_STRIP); - } -} diff --git a/src/main/target/NAZE/config.c b/src/main/target/NAZE/config.c index 542f7f6c5c..54305b67f1 100755 --- a/src/main/target/NAZE/config.c +++ b/src/main/target/NAZE/config.c @@ -108,12 +108,6 @@ void targetValidateConfiguration(master_t *config) { UNUSED(config); -#if defined(SONAR) - if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) { - featureClear(FEATURE_CURRENT_METER); - } -#endif - if (hardwareRevision < NAZE32_REV5 && config->accelerometerConfig.acc_hardware == ACC_ADXL345) { config->accelerometerConfig.acc_hardware = ACC_NONE; } diff --git a/src/main/target/STM32F3DISCOVERY/config.c b/src/main/target/STM32F3DISCOVERY/config.c deleted file mode 100644 index 167086b363..0000000000 --- a/src/main/target/STM32F3DISCOVERY/config.c +++ /dev/null @@ -1,31 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include - -#include "config/config_master.h" -#include "config/feature.h" - -void targetValidateConfiguration(master_t *config) -{ - UNUSED(config); - - if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) { - // led strip needs the same ports - featureClear(FEATURE_LED_STRIP); - } -}