diff --git a/src/main/flight/mixer_tricopter.c b/src/main/flight/mixer_tricopter.c
index 3700ff4953c..2de57d93f52 100644
--- a/src/main/flight/mixer_tricopter.c
+++ b/src/main/flight/mixer_tricopter.c
@@ -619,7 +619,7 @@ static void tailTuneModeServoSetup(struct servoSetup_t *pSS, servoParam_t *pServ
*pSS->cal.avg.pCalibConfig = pSS->cal.avg.sum / pSS->cal.avg.numOf;
pSS->cal.done = true;
} else {
- pSS->cal.avg.sum += tailServo.ADC;
+ pSS->cal.avg.sum += tailServo.ADCRaw;
pSS->cal.avg.numOf++;
}
}
@@ -628,7 +628,7 @@ static void tailTuneModeServoSetup(struct servoSetup_t *pSS, servoParam_t *pServ
switch (pSS->cal.subState) {
case SS_C_MIN:
// Wait for the servo to reach min position
- if (tailServo.ADC < (gpTriMixerConfig->tri_servo_min_adc + 10)) {
+ if (tailServo.ADCRaw < (gpTriMixerConfig->tri_servo_min_adc + 10)) {
if (!pSS->cal.waitingServoToStop) {
pSS->cal.avg.sum += GetCurrentDelay_ms(pSS->cal.timestamp_ms);
pSS->cal.avg.numOf++;
@@ -656,7 +656,7 @@ static void tailTuneModeServoSetup(struct servoSetup_t *pSS, servoParam_t *pServ
break;
case SS_C_MAX:
// Wait for the servo to reach max position
- if (tailServo.ADC > (gpTriMixerConfig->tri_servo_max_adc - 10)) {
+ if (tailServo.ADCRaw > (gpTriMixerConfig->tri_servo_max_adc - 10)) {
if (!pSS->cal.waitingServoToStop) {
pSS->cal.avg.sum += GetCurrentDelay_ms(pSS->cal.timestamp_ms);
pSS->cal.avg.numOf++;
@@ -687,9 +687,9 @@ static void updateServoAngle(float dT)
} else {
static pt1Filter_t feedbackFilter;
// Read new servo feedback signal sample and run it through filter
- const uint16_t ADC = pt1FilterApply4(&feedbackFilter, adcGetChannel(tailServo.ADCChannel), 70, dT);
- tailServo.angle = feedbackServoStep(gpTriMixerConfig, ADC);
- tailServo.ADC = ADC;
+ const uint16_t ADCRaw = pt1FilterApply4(&feedbackFilter, adcGetChannel(tailServo.ADCChannel), 70, dT);
+ tailServo.angle = feedbackServoStep(gpTriMixerConfig, ADCRaw);
+ tailServo.ADCRaw = ADCRaw;
}
}
diff --git a/src/main/flight/mixer_tricopter.h b/src/main/flight/mixer_tricopter.h
index 79d4a55fff1..af8b5b3bbf9 100644
--- a/src/main/flight/mixer_tricopter.h
+++ b/src/main/flight/mixer_tricopter.h
@@ -166,7 +166,7 @@ typedef struct tailServo_s {
uint16_t angleAtMin;
uint16_t angleAtMax;
uint16_t angle; //!< Current measured angle
- uint16_t ADC;
+ uint16_t ADCRaw;
_Bool saturated;
uint8_t saturationRange; //!< Servo angle range around setpoint where servo is not saturated (one direction)
} tailServo_t;
diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h
index b7f3a1a01cf..99ec380cefd 100755
--- a/src/main/target/BETAFLIGHTF3/target.h
+++ b/src/main/target/BETAFLIGHTF3/target.h
@@ -60,8 +60,8 @@
#define SERIAL_PORT_COUNT 6
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
+//#define USE_ESCSERIAL
+//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
diff --git a/src/main/target/CC3D/CC3D_OPBL.mk b/src/main/target/CC3D/CC3D_OPBL.mk
deleted file mode 100644
index e69de29bb2d..00000000000
diff --git a/src/main/target/CJMCU/hardware_revision.c b/src/main/target/CJMCU/hardware_revision.c
deleted file mode 100755
index 20f63e256d1..00000000000
--- a/src/main/target/CJMCU/hardware_revision.c
+++ /dev/null
@@ -1,53 +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
-#include
-
-#include "platform.h"
-
-#include "build/build_config.h"
-
-#include "drivers/system.h"
-#include "drivers/bus_spi.h"
-#include "drivers/sensor.h"
-#include "drivers/accgyro.h"
-#include "drivers/accgyro_spi_mpu6500.h"
-#include "drivers/exti.h"
-
-#include "hardware_revision.h"
-
-uint8_t hardwareRevision = UNKNOWN;
-
-void detectHardwareRevision(void)
-{
- if (GPIOC->IDR & GPIO_Pin_15) {
- hardwareRevision = REV_2;
- } else {
- hardwareRevision = REV_1;
- }
-}
-
-void updateHardwareRevision(void)
-{
-}
-
-const extiConfig_t *selectMPUIntExtiConfigByHardwareRevision(void)
-{
- return NULL;
-}
diff --git a/src/main/target/CJMCU/hardware_revision.h b/src/main/target/CJMCU/hardware_revision.h
deleted file mode 100755
index ed6413d8cfa..00000000000
--- a/src/main/target/CJMCU/hardware_revision.h
+++ /dev/null
@@ -1,33 +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 .
- */
-#pragma once
-
- typedef enum cjmcuHardwareRevision_t {
- UNKNOWN = 0,
- REV_1, // Blue LED3
- REV_2 // Green LED3
-} cjmcuHardwareRevision_e;
-
-extern uint8_t hardwareRevision;
-
-void updateHardwareRevision(void);
-void detectHardwareRevision(void);
-
-void spiBusInit(void);
-
-struct extiConfig_s;
-const struct extiConfig_s *selectMPUIntExtiConfigByHardwareRevision(void);
diff --git a/src/main/target/CJMCU/initialisation.c b/src/main/target/CJMCU/initialisation.c
deleted file mode 100644
index 884ea03350d..00000000000
--- a/src/main/target/CJMCU/initialisation.c
+++ /dev/null
@@ -1,36 +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
-
-#include "platform.h"
-#include "drivers/bus_i2c.h"
-#include "drivers/bus_spi.h"
-#include "io/serial.h"
-
-void targetBusInit(void)
-{
- #if defined(USE_SPI) && defined(USE_SPI_DEVICE_1)
- spiInit(SPIDEV_1);
- #endif
-
- if (!doesConfigurationUsePort(SERIAL_PORT_USART3)) {
- serialRemovePort(SERIAL_PORT_USART3);
- i2cInit(I2C_DEVICE);
- }
-}
\ No newline at end of file
diff --git a/src/main/target/CJMCU/target.c b/src/main/target/CJMCU/target.c
deleted file mode 100644
index 2478c668d4f..00000000000
--- a/src/main/target/CJMCU/target.c
+++ /dev/null
@@ -1,41 +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
-#include "drivers/io.h"
-
-#include "drivers/timer.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM, 0 }, // PWM1 - RC1
- { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0 }, // PWM2 - RC2
- { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0 }, // PWM3 - RC3
- { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0 }, // PWM4 - RC4
- { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM, 0 }, // PWM5 - RC5
- { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0 }, // PWM6 - RC6
- { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0 }, // PWM7 - RC7
- { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0 }, // PWM8 - RC8
- { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1 }, // PWM9 - OUT1
- { TIM1, IO_TAG(PA11),TIM_Channel_4, TIM_USE_MOTOR, 1 }, // PWM10 - OUT2
- { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 0 }, // PWM11 - OUT3
- { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 0 }, // PWM12 - OUT4
- { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 0 }, // PWM13 - OUT5
- { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 0 } // PWM14 - OUT6
-};
-
diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h
deleted file mode 100644
index cd10384e3c1..00000000000
--- a/src/main/target/CJMCU/target.h
+++ /dev/null
@@ -1,136 +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 .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "CJM1" // CJMCU
-#define USE_HARDWARE_REVISION_DETECTION
-#define TARGET_BUS_INIT
-
-#define LED0 PC14
-#define LED1 PC13
-#define LED2 PC15
-
-#undef BEEPER
-
-#define GYRO
-#define USE_GYRO_MPU6050
-
-#define ACC
-#define USE_ACC_MPU6050
-
-//#define MAG
-//#define USE_MAG_HMC5883
-
-#define BRUSHED_MOTORS
-
-#define USE_UART1
-#define USE_UART2
-
-#define SERIAL_PORT_COUNT 2
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1)
-
-// #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_SPI
-#define USE_SPI_DEVICE_1
-
-#define USE_RX_NRF24
-#ifdef USE_RX_NRF24
-
-#define USE_RX_SPI
-#define RX_SPI_INSTANCE SPI1
-
-// Nordic Semiconductor uses 'CSN', STM uses 'NSS'
-#define RX_CE_PIN PA4
-#define RX_NSS_PIN PA11
-#define RX_SCK_PIN PA5
-#define RX_MISO_PIN PA6
-#define RX_MOSI_PIN PA7
-#define RX_IRQ_PIN PA8
-// CJMCU has NSS on PA11, rather than the standard PA4
-#define SPI1_NSS_PIN RX_NSS_PIN
-#define SPI1_SCK_PIN RX_SCK_PIN
-#define SPI1_MISO_PIN RX_MISO_PIN
-#define SPI1_MOSI_PIN RX_MOSI_PIN
-
-#define USE_RX_NRF24
-#define USE_RX_CX10
-#define USE_RX_H8_3D
-#define USE_RX_INAV
-#define USE_RX_SYMA
-#define USE_RX_V202
-//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_SYMA_X5
-//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_SYMA_X5C
-//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_INAV
-#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_H8_3D
-//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_CX10A
-//#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_V202_1M
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_SPI
-//#define TELEMETRY
-//#define TELEMETRY_LTM
-//#define TELEMETRY_NRF24_LTM
-#ifdef USE_PWM
-#undef USE_PWM
-#endif
-
-#ifdef USE_PPM
-#undef USE_PPM
-#endif
-
-#ifdef SERIAL_RX
-#undef SERIAL_RX
-#endif
-//#undef SKIP_TASK_STATISTICS
-
-#else
-
-#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
-#define USE_RX_MSP
-#define SPEKTRUM_BIND
-#define BIND_PIN PA3 // UART2, PA3
-
-#endif //USE_RX_NRF24
-
-#define BRUSHED_MOTORS
-#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
-#define SKIP_SERIAL_PASSTHROUGH
-#undef USE_CLI
-
-// Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers.
-#define USE_QUAD_MIXER_ONLY
-#undef USE_SERVOS
-
-#if (FLASH_SIZE <= 64)
-#undef BLACKBOX
-#endif
-
-// Number of available PWM outputs
-//#define MAX_PWM_OUTPUT_PORTS 4
-
-// 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 USABLE_TIMER_CHANNEL_COUNT 14
-#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4))
diff --git a/src/main/target/CJMCU/target.mk b/src/main/target/CJMCU/target.mk
deleted file mode 100644
index 8da31647cf6..00000000000
--- a/src/main/target/CJMCU/target.mk
+++ /dev/null
@@ -1,12 +0,0 @@
-F1_TARGETS += $(TARGET)
-FLASH_SIZE = 64
-
-TARGET_SRC = \
- drivers/accgyro_mpu.c \
- drivers/accgyro_mpu6050.c \
- drivers/compass_hmc5883l.c \
- blackbox/blackbox.c \
- blackbox/blackbox_io.c \
- telemetry/telemetry.c \
- telemetry/ltm.c
-
diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h
index a89f8970b80..303a15a0b1b 100644
--- a/src/main/target/FURYF3/target.h
+++ b/src/main/target/FURYF3/target.h
@@ -119,8 +119,8 @@
#define SERIAL_PORT_COUNT 6
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
+//#define USE_ESCSERIAL
+//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
@@ -149,9 +149,9 @@
#define LED_STRIP
-#define SONAR
-#define SONAR_ECHO_PIN PB1
-#define SONAR_TRIGGER_PIN PB0
+//#define SONAR
+//#define SONAR_ECHO_PIN PB1
+//#define SONAR_TRIGGER_PIN PB0
#define DEFAULT_FEATURES FEATURE_BLACKBOX
#define DEFAULT_RX_FEATURE FEATURE_RX_PPM
diff --git a/src/main/target/MICROSCISKY/target.c b/src/main/target/MICROSCISKY/target.c
deleted file mode 100644
index fd9678c7997..00000000000
--- a/src/main/target/MICROSCISKY/target.c
+++ /dev/null
@@ -1,41 +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
-#include "drivers/io.h"
-
-#include "drivers/timer.h"
-#include "drivers/dma.h"
-
-const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
- { TIM2, IO_TAG(PA0), TIM_Channel_1, TIM_USE_PWM | TIM_USE_PPM, 0, NULL, 0 }, // PWM1 - RC1
- { TIM2, IO_TAG(PA1), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM2 - RC2
- { TIM2, IO_TAG(PA2), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM3 - RC3
- { TIM2, IO_TAG(PA3), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM4 - RC4
- { TIM3, IO_TAG(PA6), TIM_Channel_1, TIM_USE_PWM | TIM_USE_LED, 0, DMA1_Channel6, DMA1_CH6_HANDLER }, // PWM5 - RC5
- { TIM3, IO_TAG(PA7), TIM_Channel_2, TIM_USE_PWM, 0, NULL, 0 }, // PWM6 - RC6
- { TIM3, IO_TAG(PB0), TIM_Channel_3, TIM_USE_PWM, 0, NULL, 0 }, // PWM7 - RC7
- { TIM3, IO_TAG(PB1), TIM_Channel_4, TIM_USE_PWM, 0, NULL, 0 }, // PWM8 - RC8
- { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM9 - OUT1
- { TIM1, IO_TAG(PA11), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM10 - OUT2
- { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM11 - OUT3
- { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM12 - OUT4
- { TIM4, IO_TAG(PB8), TIM_Channel_3, TIM_USE_MOTOR, 1, NULL, 0 }, // PWM13 - OUT5
- { TIM4, IO_TAG(PB9), TIM_Channel_4, TIM_USE_MOTOR, 1, NULL, 0 } // PWM14 - OUT6
-};
diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h
deleted file mode 100644
index 8b6cc28d90c..00000000000
--- a/src/main/target/MICROSCISKY/target.h
+++ /dev/null
@@ -1,96 +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 .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY
-
-#define LED0 PB3
-#define LED1 PB4
-
-#define BEEPER PA12
-
-#define BARO_XCLR_PIN PC13
-#define BARO_EOC_PIN PC14
-
-#define INVERTER_PIN_USART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO
-
-#define USE_EXTI
-#define MAG_INT_EXTI PC14
-//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define USE_MPU_DATA_READY_SIGNAL
-//#define DEBUG_MAG_DATA_READY_INTERRUPT
-#define USE_MAG_DATA_READY_SIGNAL
-
-// SPI2
-// PB15 28 SPI2_MOSI
-// PB14 27 SPI2_MISO
-// PB13 26 SPI2_SCK
-// PB12 25 SPI2_NSS
-
-#define USE_SPI
-#define USE_SPI_DEVICE_2
-
-#define GYRO
-#define USE_GYRO_MPU6050
-#define GYRO_MPU6050_ALIGN CW0_DEG
-
-#define ACC
-#define USE_ACC_MPU6050
-#define ACC_MPU6050_ALIGN CW0_DEG
-
-#define BARO
-#define USE_BARO_MS5611
-#define USE_BARO_BMP085
-#define USE_BARO_BMP280
-
-#define MAG
-#define USE_MAG_HMC5883
-#define MAG_HMC5883_ALIGN CW180_DEG
-
-#define USE_UART1
-#define USE_UART2
-#define SERIAL_PORT_COUNT 2
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_2)
-
-#define LED_STRIP
-
-#define SPEKTRUM_BIND
-// USART2, PA3
-#define BIND_PIN PA3
-
-#define BRUSHED_MOTORS
-#define DEFAULT_FEATURES FEATURE_MOTOR_STOP
-#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
-#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM1024
-#define SERIALRX_UART SERIAL_PORT_USART2
-#define RX_CHANNELS_TAER
-
-#undef GPS
-#undef USE_SERVOS
-#define USE_QUAD_MIXER_ONLY
-
-
-// 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 USABLE_TIMER_CHANNEL_COUNT 14
-#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) )
diff --git a/src/main/target/MICROSCISKY/target.mk b/src/main/target/MICROSCISKY/target.mk
deleted file mode 100644
index 88034cc60a5..00000000000
--- a/src/main/target/MICROSCISKY/target.mk
+++ /dev/null
@@ -1,10 +0,0 @@
-F1_TARGETS += $(TARGET)
-FEATURES = HIGHEND
-
-TARGET_SRC = \
- drivers/accgyro_mpu.c \
- drivers/accgyro_mpu6050.c \
- drivers/barometer_bmp085.c \
- drivers/barometer_bmp280.c \
- drivers/barometer_ms5611.c \
- drivers/compass_hmc5883l.c
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index e4817bf3833..74ed7b02fc1 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -147,7 +147,7 @@
#define RSSI_ADC_PIN PA1
#define EXTERNAL1_ADC_PIN PA7
-#define LED_STRIP
+//#define LED_STRIP
#undef GPS
diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h
index 179b91af7b0..cdc4991f88b 100755
--- a/src/main/target/SPRACINGF3EVO/target.h
+++ b/src/main/target/SPRACINGF3EVO/target.h
@@ -143,7 +143,7 @@
#define LED_STRIP
-#define TRANSPONDER
+//#define TRANSPONDER
#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT
diff --git a/src/main/target/SPRACINGF3MINI/target.h b/src/main/target/SPRACINGF3MINI/target.h
index cc82da505ab..ad1991a8c39 100644
--- a/src/main/target/SPRACINGF3MINI/target.h
+++ b/src/main/target/SPRACINGF3MINI/target.h
@@ -101,8 +101,8 @@
#define SERIAL_PORT_COUNT 6
#endif
-#define USE_ESCSERIAL
-#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
+//#define USE_ESCSERIAL
+//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
#define UART1_TX_PIN PA9
#define UART1_RX_PIN PA10
diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h
index e2fa0d48cc9..a875315d0ce 100644
--- a/src/main/target/STM32F3DISCOVERY/target.h
+++ b/src/main/target/STM32F3DISCOVERY/target.h
@@ -179,9 +179,9 @@
#define SPEKTRUM_BIND
#define BIND_PIN PA3 // USART2, PA3
-#define SONAR
-#define SONAR_TRIGGER_PIN PB0
-#define SONAR_ECHO_PIN PB1
+//#define SONAR
+//#define SONAR_TRIGGER_PIN PB0
+//#define SONAR_ECHO_PIN PB1
#define USE_SERIAL_4WAY_BLHELI_INTERFACE