From ee582df432a4d4495eb90fdebaa2c8d7ef95db5f Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Thu, 13 Apr 2017 23:11:18 +0200 Subject: [PATCH 1/4] Adding various PikoBLX based FuriousFPV targets --- Makefile | 8 +++ src/main/target/PIKOBLX/ACROWHOOPFR.mk | 3 + src/main/target/PIKOBLX/ACROWHOOPSP.mk | 3 + src/main/target/PIKOBLX/KOMBINI.mk | 3 + src/main/target/PIKOBLX/KOMBINID.mk | 3 + src/main/target/PIKOBLX/NUKE.mk | 2 + src/main/target/PIKOBLX/RACEWHOOP.mk | 3 + src/main/target/PIKOBLX/RADIANCE.mk | 2 + src/main/target/PIKOBLX/RADIANCED.mk | 2 + src/main/target/PIKOBLX/config.c | 82 ++++++++++++++++++++++++++ src/main/target/PIKOBLX/target.c | 17 +++++- src/main/target/PIKOBLX/target.h | 76 +++++++++++++++++------- 12 files changed, 179 insertions(+), 25 deletions(-) create mode 100644 src/main/target/PIKOBLX/ACROWHOOPFR.mk create mode 100644 src/main/target/PIKOBLX/ACROWHOOPSP.mk create mode 100644 src/main/target/PIKOBLX/KOMBINI.mk create mode 100644 src/main/target/PIKOBLX/KOMBINID.mk create mode 100644 src/main/target/PIKOBLX/NUKE.mk create mode 100644 src/main/target/PIKOBLX/RACEWHOOP.mk create mode 100644 src/main/target/PIKOBLX/RADIANCE.mk create mode 100644 src/main/target/PIKOBLX/RADIANCED.mk create mode 100644 src/main/target/PIKOBLX/config.c diff --git a/Makefile b/Makefile index f5fbf41408..8a16c2d71a 100644 --- a/Makefile +++ b/Makefile @@ -98,6 +98,8 @@ VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) GROUP_1_TARGETS := \ + ACROWHOOPFR \ + ACROWHOOPSP \ AFROMINI \ AIORACERF3 \ AIR32 \ @@ -141,6 +143,8 @@ GROUP_3_TARGETS := \ KAKUTEF4 \ KISSCC \ KIWIF4 \ + KOMBINI \ + KOMBINID \ LUX_RACE \ LUXV2_RACE \ MICROSCISKY \ @@ -148,6 +152,7 @@ GROUP_3_TARGETS := \ MULTIFLITEPICO \ NAZE \ NERO \ + NUKE \ NUCLEOF7 \ OMNIBUS \ OMNIBUSF4 \ @@ -157,6 +162,9 @@ GROUP_3_TARGETS := \ PODIUMF4 \ GROUP_4_TARGETS := \ + RACEWHOOP \ + RADIANCE \ + RADIANCED \ RCEXPLORERF3 \ REVO \ REVO_OPBL \ diff --git a/src/main/target/PIKOBLX/ACROWHOOPFR.mk b/src/main/target/PIKOBLX/ACROWHOOPFR.mk new file mode 100644 index 0000000000..75f2df026e --- /dev/null +++ b/src/main/target/PIKOBLX/ACROWHOOPFR.mk @@ -0,0 +1,3 @@ +# ACROWHOOPFR is a variant of PIKOBLX +# small brushed FC with FrSky receiver onboard +# designed for inductrix and similar copters diff --git a/src/main/target/PIKOBLX/ACROWHOOPSP.mk b/src/main/target/PIKOBLX/ACROWHOOPSP.mk new file mode 100644 index 0000000000..fbd54f2d9f --- /dev/null +++ b/src/main/target/PIKOBLX/ACROWHOOPSP.mk @@ -0,0 +1,3 @@ +# ACROWHOOPSP is a variant of PIKOBLX +# small brushed FC with Spektrum receiver onboard +# designed for inductrix and similar copters diff --git a/src/main/target/PIKOBLX/KOMBINI.mk b/src/main/target/PIKOBLX/KOMBINI.mk new file mode 100644 index 0000000000..1107387a1e --- /dev/null +++ b/src/main/target/PIKOBLX/KOMBINI.mk @@ -0,0 +1,3 @@ +# KOMBINI is a variant of PIKOBLX +# FC with integrated PDB and current sensor +# 12V and 5V BEC onboard diff --git a/src/main/target/PIKOBLX/KOMBINID.mk b/src/main/target/PIKOBLX/KOMBINID.mk new file mode 100644 index 0000000000..9244af15bf --- /dev/null +++ b/src/main/target/PIKOBLX/KOMBINID.mk @@ -0,0 +1,3 @@ +# KOMBINID is a variant of PIKOBLX (DSHOT ready version) +# FC with integrated PDB and current sensor +# 12V and 5V BEC onboard diff --git a/src/main/target/PIKOBLX/NUKE.mk b/src/main/target/PIKOBLX/NUKE.mk new file mode 100644 index 0000000000..3f06589379 --- /dev/null +++ b/src/main/target/PIKOBLX/NUKE.mk @@ -0,0 +1,2 @@ +# NUKE is a variant of PIKOBLX +# very small brushed FC, (16mmx16mm) hole spacing diff --git a/src/main/target/PIKOBLX/RACEWHOOP.mk b/src/main/target/PIKOBLX/RACEWHOOP.mk new file mode 100644 index 0000000000..7a46ba683e --- /dev/null +++ b/src/main/target/PIKOBLX/RACEWHOOP.mk @@ -0,0 +1,3 @@ +# RACEWHOOP is a variant of PIKOBLX +# small FC with current sensor +# designed for vers small brushless copters (e.g. MOSKITO70) diff --git a/src/main/target/PIKOBLX/RADIANCE.mk b/src/main/target/PIKOBLX/RADIANCE.mk new file mode 100644 index 0000000000..ef6e760f96 --- /dev/null +++ b/src/main/target/PIKOBLX/RADIANCE.mk @@ -0,0 +1,2 @@ +# RADIANCE is a variant of PIKOBLX +# similar to Kombini, but without PDB and current sensor diff --git a/src/main/target/PIKOBLX/RADIANCED.mk b/src/main/target/PIKOBLX/RADIANCED.mk new file mode 100644 index 0000000000..616187aa8e --- /dev/null +++ b/src/main/target/PIKOBLX/RADIANCED.mk @@ -0,0 +1,2 @@ +# RADIANCED is a variant of PIKOBLX (DSHOT ready version) +# similar to Kombini, but without PDB and current sensor diff --git a/src/main/target/PIKOBLX/config.c b/src/main/target/PIKOBLX/config.c new file mode 100644 index 0000000000..ff2723e832 --- /dev/null +++ b/src/main/target/PIKOBLX/config.c @@ -0,0 +1,82 @@ +/* + * 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 + +#ifdef TARGET_CONFIG +#include "common/axis.h" + +#include "config/feature.h" + +#include "fc/config.h" +#include "fc/controlrate_profile.h" + +#include "flight/mixer.h" +#include "flight/pid.h" + +#include "rx/rx.h" + +#include "io/serial.h" + +#include "telemetry/telemetry.h" + +#include "sensors/battery.h" + +#ifdef BRUSHED_MOTORS_PWM_RATE +#undef BRUSHED_MOTORS_PWM_RATE +#endif + +#define BRUSHED_MOTORS_PWM_RATE 32000 // 32kHz + +void targetConfiguration(void) +{ +#if defined(NUKE) || defined(ACROWHOOPFR) || defined(ACROWHOOPSP) + motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; + motorConfigMutable()->minthrottle = 1049; + +#if defined(ACROWHOOPFR) + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; + rxConfigMutable()->sbus_inversion = 0; + featureSet(FEATURE_TELEMETRY); +#elif defined(ACROWHOOPSP) + rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; + rxConfigMutable()->spektrum_sat_bind = 5; + rxConfigMutable()->spektrum_sat_bind_autoreset = 1; +#endif + + pidProfilesMutable(0)->pid[PID_ROLL].P = 80; + pidProfilesMutable(0)->pid[PID_ROLL].I = 37; + pidProfilesMutable(0)->pid[PID_ROLL].D = 35; + pidProfilesMutable(0)->pid[PID_PITCH].P = 100; + pidProfilesMutable(0)->pid[PID_PITCH].I = 37; + pidProfilesMutable(0)->pid[PID_PITCH].D = 35; + pidProfilesMutable(0)->pid[PID_YAW].P = 180; + pidProfilesMutable(0)->pid[PID_YAW].D = 45; + + controlRateProfilesMutable(0)->rcRate8 = 100; + controlRateProfilesMutable(0)->rcYawRate8 = 100; + controlRateProfilesMutable(0)->rcExpo8 = 15; + controlRateProfilesMutable(0)->rcYawExpo8 = 15; + controlRateProfilesMutable(0)->rates[PID_ROLL] = 80; + controlRateProfilesMutable(0)->rates[PID_PITCH] = 80; + controlRateProfilesMutable(0)->rates[PID_YAW] = 80; +#endif +} +#endif diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/PIKOBLX/target.c index d830ba78cf..5cffca9223 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/PIKOBLX/target.c @@ -25,15 +25,26 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { +#if defined(RADIANCED) || defined(KOMBINID) || defined(RACEWHOOP) + DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, 1), // PWM1 - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N + DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 + DEF_TIM(TIM3, CH2, PA4, TIM_USE_PPM, 0), // PPM - PA4 + DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8 +#else DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, 1), // PWM1 - PA4 - *TIM3_CH2 DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 1), // PWM4 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, 1), // PWM5 - PA1 - *TIM2_CH2, TIM15_CH1N DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1), // PWM6 - PA2 - *TIM2_CH3, !TIM15_CH1 - DEF_TIM(TIM15, CH2, PA3, TIM_USE_MOTOR, 1), // PWM7 - PA3 - *TIM15_CH2, TIM2_CH4 - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 1), // PWM8 - PA8 - *TIM1_CH1, TIM4_ETR DEF_TIM(TIM17, CH1, PA7, TIM_USE_PPM, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 - DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), // PPM - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + DEF_TIM(TIM16, CH1, PB8, TIM_USE_LED, 0), + DEF_TIM(TIM1, CH1, PA8, TIM_USE_TRANSPONDER, 1 ), // TRANSPONDER - PA8 +#endif }; diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/PIKOBLX/target.h index 35555c41aa..c5d74b1f46 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/PIKOBLX/target.h @@ -17,10 +17,39 @@ #pragma once -#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV Piko BLX +#if defined(RADIANCED) +#define TARGET_BOARD_IDENTIFIER "RADD" // Furious FPV RADIANCE DSHOT +#elif defined(RADIANCE) +#define TARGET_BOARD_IDENTIFIER "RADI" // Furious FPV RADIANCE V1 +#elif defined(KOMBINID) +#define TARGET_BOARD_IDENTIFIER "KOMD" // Furious FPV KOMBINI DSHOT +#elif defined(KOMBINI) +#define TARGET_BOARD_IDENTIFIER "KOMB" // Furious FPV KOMBINI V1 +#elif defined(RACEWHOOP) +#define TARGET_BOARD_IDENTIFIER "RWHO" // Furious FPV RACEWHOOP +#elif defined(ACROWHOOPFR) +#define TARGET_BOARD_IDENTIFIER "AWHF" // Furious FPV ACROWHOOP FRSKY +#elif defined(ACROWHOOPSP) +#define TARGET_BOARD_IDENTIFIER "AWHS" // Furious FPV ACROWHOOP SPEKTRUM +#elif defined(NUKE) +#define TARGET_BOARD_IDENTIFIER "NUKE" // Furious FPV NUKE +#else +#define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV PIKOBLX +#endif #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT +#define TARGET_CONFIG + +#if defined(ACROWHOOPFR) || defined(ACROWHOOPSP) || defined(NUKE) +#define BRUSHED_MOTORS +#define RX_CHANNELS_TAER +#endif + +#if defined(RACEWHOOP) +#define RX_CHANNELS_TAER +#endif + #define LED0 PB9 #define LED1 PB5 @@ -63,45 +92,48 @@ #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 +#define UART3_RX_PIN PB11 #define USE_SPI #define USE_SPI_DEVICE_2 -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define USE_ADC +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC #define ADC_INSTANCE ADC2 #define CURRENT_METER_ADC_PIN PB2 #define VBAT_ADC_PIN PA5 + +#if defined(KOMBINI) || defined(KOMBINID) #define CURRENT_METER_SCALE_DEFAULT 125 +#elif defined(RACEWHOOP) +#define CURRENT_METER_SCALE_DEFAULT 1000 +#endif -#define TRANSPONDER -#define TRANSPONDER_GPIO GPIOA -#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define TRANSPONDER_GPIO_AF GPIO_AF_6 -#define TRANSPONDER_PIN GPIO_Pin_8 -#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 -#define TRANSPONDER_TIMER TIM1 -#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 -#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 -#define TRANSPONDER_IRQ DMA1_Channel2_IRQn -#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 -#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 +#if defined(RADIANCE) || defined(RADIANCED) +#define SPEKTRUM_BIND_PIN UART2_RX_PIN +#else #define SPEKTRUM_BIND_PIN UART3_RX_PIN +#endif +#if !(defined(NUKE) || defined(ACROWHOPFR) || defined(ACROWHOPSP) || defined(RACEWHOOP)) +#define TRANSPONDER +#endif + +#if !defined(BRUSHED_MOTORS) #define USE_SERIAL_4WAY_BLHELI_INTERFACE +#endif // 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)) -// !!TODO - check the following line is correct -#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) - -#define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) +#define USABLE_TIMER_CHANNEL_COUNT 9 +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(16) | TIM_N(17)) From 6050bd46009d067a71e400eb58abb82da8cb0210 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Sat, 27 May 2017 14:11:44 +0200 Subject: [PATCH 2/4] Rename FuriousFPV targets (prefix all with FF_) --- Makefile | 18 ++++++------ .../FF_ACROWHOOPFR.mk} | 0 .../FF_ACROWHOOPSP.mk} | 0 .../KOMBINI.mk => FF_PIKOBLX/FF_KOMBINI.mk} | 0 .../KOMBINID.mk => FF_PIKOBLX/FF_KOMBINID.mk} | 0 .../NUKE.mk => FF_PIKOBLX/FF_NUKE.mk} | 0 .../FF_RACEWHOOP.mk} | 0 .../RADIANCE.mk => FF_PIKOBLX/FF_RADIANCE.mk} | 0 .../FF_RADIANCED.mk} | 0 .../target/{PIKOBLX => FF_PIKOBLX}/config.c | 6 ++-- .../target/{PIKOBLX => FF_PIKOBLX}/target.c | 2 +- .../target/{PIKOBLX => FF_PIKOBLX}/target.h | 28 +++++++++---------- .../target/{PIKOBLX => FF_PIKOBLX}/target.mk | 0 13 files changed, 27 insertions(+), 27 deletions(-) rename src/main/target/{PIKOBLX/ACROWHOOPFR.mk => FF_PIKOBLX/FF_ACROWHOOPFR.mk} (100%) rename src/main/target/{PIKOBLX/ACROWHOOPSP.mk => FF_PIKOBLX/FF_ACROWHOOPSP.mk} (100%) rename src/main/target/{PIKOBLX/KOMBINI.mk => FF_PIKOBLX/FF_KOMBINI.mk} (100%) rename src/main/target/{PIKOBLX/KOMBINID.mk => FF_PIKOBLX/FF_KOMBINID.mk} (100%) rename src/main/target/{PIKOBLX/NUKE.mk => FF_PIKOBLX/FF_NUKE.mk} (100%) rename src/main/target/{PIKOBLX/RACEWHOOP.mk => FF_PIKOBLX/FF_RACEWHOOP.mk} (100%) rename src/main/target/{PIKOBLX/RADIANCE.mk => FF_PIKOBLX/FF_RADIANCE.mk} (100%) rename src/main/target/{PIKOBLX/RADIANCED.mk => FF_PIKOBLX/FF_RADIANCED.mk} (100%) rename src/main/target/{PIKOBLX => FF_PIKOBLX}/config.c (94%) rename src/main/target/{PIKOBLX => FF_PIKOBLX}/target.c (97%) rename src/main/target/{PIKOBLX => FF_PIKOBLX}/target.h (86%) rename src/main/target/{PIKOBLX => FF_PIKOBLX}/target.mk (100%) diff --git a/Makefile b/Makefile index 8a16c2d71a..eaf4a52153 100644 --- a/Makefile +++ b/Makefile @@ -98,8 +98,6 @@ VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) GROUP_1_TARGETS := \ - ACROWHOOPFR \ - ACROWHOOPSP \ AFROMINI \ AIORACERF3 \ AIR32 \ @@ -130,8 +128,17 @@ GROUP_2_TARGETS := \ F4BY \ FISHDRONEF4 \ FLIP32F3OSD \ + FF_ACROWHOOPFR \ + FF_ACROWHOOPSP \ FF_FORTINIF4 \ + FF_KOMBINI \ + FF_KOMBINID \ + FF_NUKE \ + FF_PIKOBLX \ FF_PIKOF4 \ + FF_RACEWHOOP \ + FF_RADIANCE \ + FF_RADIANCED \ FURYF3 \ FURYF4 \ FURYF7 \ @@ -143,8 +150,6 @@ GROUP_3_TARGETS := \ KAKUTEF4 \ KISSCC \ KIWIF4 \ - KOMBINI \ - KOMBINID \ LUX_RACE \ LUXV2_RACE \ MICROSCISKY \ @@ -152,19 +157,14 @@ GROUP_3_TARGETS := \ MULTIFLITEPICO \ NAZE \ NERO \ - NUKE \ NUCLEOF7 \ OMNIBUS \ OMNIBUSF4 \ OMNIBUSF4SD \ - PIKOBLX \ PLUMF4 \ PODIUMF4 \ GROUP_4_TARGETS := \ - RACEWHOOP \ - RADIANCE \ - RADIANCED \ RCEXPLORERF3 \ REVO \ REVO_OPBL \ diff --git a/src/main/target/PIKOBLX/ACROWHOOPFR.mk b/src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk similarity index 100% rename from src/main/target/PIKOBLX/ACROWHOOPFR.mk rename to src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk diff --git a/src/main/target/PIKOBLX/ACROWHOOPSP.mk b/src/main/target/FF_PIKOBLX/FF_ACROWHOOPSP.mk similarity index 100% rename from src/main/target/PIKOBLX/ACROWHOOPSP.mk rename to src/main/target/FF_PIKOBLX/FF_ACROWHOOPSP.mk diff --git a/src/main/target/PIKOBLX/KOMBINI.mk b/src/main/target/FF_PIKOBLX/FF_KOMBINI.mk similarity index 100% rename from src/main/target/PIKOBLX/KOMBINI.mk rename to src/main/target/FF_PIKOBLX/FF_KOMBINI.mk diff --git a/src/main/target/PIKOBLX/KOMBINID.mk b/src/main/target/FF_PIKOBLX/FF_KOMBINID.mk similarity index 100% rename from src/main/target/PIKOBLX/KOMBINID.mk rename to src/main/target/FF_PIKOBLX/FF_KOMBINID.mk diff --git a/src/main/target/PIKOBLX/NUKE.mk b/src/main/target/FF_PIKOBLX/FF_NUKE.mk similarity index 100% rename from src/main/target/PIKOBLX/NUKE.mk rename to src/main/target/FF_PIKOBLX/FF_NUKE.mk diff --git a/src/main/target/PIKOBLX/RACEWHOOP.mk b/src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk similarity index 100% rename from src/main/target/PIKOBLX/RACEWHOOP.mk rename to src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk diff --git a/src/main/target/PIKOBLX/RADIANCE.mk b/src/main/target/FF_PIKOBLX/FF_RADIANCE.mk similarity index 100% rename from src/main/target/PIKOBLX/RADIANCE.mk rename to src/main/target/FF_PIKOBLX/FF_RADIANCE.mk diff --git a/src/main/target/PIKOBLX/RADIANCED.mk b/src/main/target/FF_PIKOBLX/FF_RADIANCED.mk similarity index 100% rename from src/main/target/PIKOBLX/RADIANCED.mk rename to src/main/target/FF_PIKOBLX/FF_RADIANCED.mk diff --git a/src/main/target/PIKOBLX/config.c b/src/main/target/FF_PIKOBLX/config.c similarity index 94% rename from src/main/target/PIKOBLX/config.c rename to src/main/target/FF_PIKOBLX/config.c index ff2723e832..247f66ec33 100644 --- a/src/main/target/PIKOBLX/config.c +++ b/src/main/target/FF_PIKOBLX/config.c @@ -47,15 +47,15 @@ void targetConfiguration(void) { -#if defined(NUKE) || defined(ACROWHOOPFR) || defined(ACROWHOOPSP) +#if defined(FF_NUKE) || defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfigMutable()->minthrottle = 1049; -#if defined(ACROWHOOPFR) +#if defined(FF_ACROWHOOPFR) serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; rxConfigMutable()->sbus_inversion = 0; featureSet(FEATURE_TELEMETRY); -#elif defined(ACROWHOOPSP) +#elif defined(FF_ACROWHOOPSP) rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfigMutable()->spektrum_sat_bind = 5; rxConfigMutable()->spektrum_sat_bind_autoreset = 1; diff --git a/src/main/target/PIKOBLX/target.c b/src/main/target/FF_PIKOBLX/target.c similarity index 97% rename from src/main/target/PIKOBLX/target.c rename to src/main/target/FF_PIKOBLX/target.c index 5cffca9223..8db259922b 100644 --- a/src/main/target/PIKOBLX/target.c +++ b/src/main/target/FF_PIKOBLX/target.c @@ -25,7 +25,7 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { -#if defined(RADIANCED) || defined(KOMBINID) || defined(RACEWHOOP) +#if defined(FF_RADIANCED) || defined(FF_KOMBINID) || defined(FF_RACEWHOOP) DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, 1), // PWM1 - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h similarity index 86% rename from src/main/target/PIKOBLX/target.h rename to src/main/target/FF_PIKOBLX/target.h index c5d74b1f46..2fcfeb7121 100644 --- a/src/main/target/PIKOBLX/target.h +++ b/src/main/target/FF_PIKOBLX/target.h @@ -17,21 +17,21 @@ #pragma once -#if defined(RADIANCED) +#if defined(FF_RADIANCED) #define TARGET_BOARD_IDENTIFIER "RADD" // Furious FPV RADIANCE DSHOT -#elif defined(RADIANCE) +#elif defined(FF_RADIANCE) #define TARGET_BOARD_IDENTIFIER "RADI" // Furious FPV RADIANCE V1 -#elif defined(KOMBINID) +#elif defined(FF_KOMBINID) #define TARGET_BOARD_IDENTIFIER "KOMD" // Furious FPV KOMBINI DSHOT -#elif defined(KOMBINI) +#elif defined(FF_KOMBINI) #define TARGET_BOARD_IDENTIFIER "KOMB" // Furious FPV KOMBINI V1 -#elif defined(RACEWHOOP) +#elif defined(FF_RACEWHOOP) #define TARGET_BOARD_IDENTIFIER "RWHO" // Furious FPV RACEWHOOP -#elif defined(ACROWHOOPFR) +#elif defined(FF_ACROWHOOPFR) #define TARGET_BOARD_IDENTIFIER "AWHF" // Furious FPV ACROWHOOP FRSKY -#elif defined(ACROWHOOPSP) +#elif defined(FF_ACROWHOOPSP) #define TARGET_BOARD_IDENTIFIER "AWHS" // Furious FPV ACROWHOOP SPEKTRUM -#elif defined(NUKE) +#elif defined(FF_NUKE) #define TARGET_BOARD_IDENTIFIER "NUKE" // Furious FPV NUKE #else #define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV PIKOBLX @@ -41,12 +41,12 @@ #define TARGET_CONFIG -#if defined(ACROWHOOPFR) || defined(ACROWHOOPSP) || defined(NUKE) +#if defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) || defined(FF_NUKE) #define BRUSHED_MOTORS #define RX_CHANNELS_TAER #endif -#if defined(RACEWHOOP) +#if defined(FF_RACEWHOOP) #define RX_CHANNELS_TAER #endif @@ -105,9 +105,9 @@ #define VBAT_ADC_PIN PA5 -#if defined(KOMBINI) || defined(KOMBINID) +#if defined(FF_KOMBINI) || defined(FF_KOMBINID) #define CURRENT_METER_SCALE_DEFAULT 125 -#elif defined(RACEWHOOP) +#elif defined(FF_RACEWHOOP) #define CURRENT_METER_SCALE_DEFAULT 1000 #endif @@ -115,13 +115,13 @@ #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART3 -#if defined(RADIANCE) || defined(RADIANCED) +#if defined(FF_RADIANCE) || defined(FF_RADIANCED) #define SPEKTRUM_BIND_PIN UART2_RX_PIN #else #define SPEKTRUM_BIND_PIN UART3_RX_PIN #endif -#if !(defined(NUKE) || defined(ACROWHOPFR) || defined(ACROWHOPSP) || defined(RACEWHOOP)) +#if !(defined(FF_NUKE) || defined(FF_ACROWHOPFR) || defined(FF_ACROWHOPSP) || defined(FF_RACEWHOOP)) #define TRANSPONDER #endif diff --git a/src/main/target/PIKOBLX/target.mk b/src/main/target/FF_PIKOBLX/target.mk similarity index 100% rename from src/main/target/PIKOBLX/target.mk rename to src/main/target/FF_PIKOBLX/target.mk From b333e5cfd864dd6b4a3398e14e9c8241751e9d75 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Sat, 27 May 2017 14:39:56 +0200 Subject: [PATCH 3/4] First run to reduce number of targets --- src/main/target/FF_PIKOBLX/config.c | 52 +++++++++++++++-------------- src/main/target/FF_PIKOBLX/target.h | 13 ++------ 2 files changed, 29 insertions(+), 36 deletions(-) diff --git a/src/main/target/FF_PIKOBLX/config.c b/src/main/target/FF_PIKOBLX/config.c index 247f66ec33..7cc94523a4 100644 --- a/src/main/target/FF_PIKOBLX/config.c +++ b/src/main/target/FF_PIKOBLX/config.c @@ -25,6 +25,8 @@ #include "config/feature.h" +#include "drivers/pwm_esc_detect.h" + #include "fc/config.h" #include "fc/controlrate_profile.h" @@ -47,36 +49,36 @@ void targetConfiguration(void) { -#if defined(FF_NUKE) || defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) - motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - motorConfigMutable()->minthrottle = 1049; + if (hardwareMotorType == MOTOR_BRUSHED) { + motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; + motorConfigMutable()->minthrottle = 1049; #if defined(FF_ACROWHOOPFR) - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; - rxConfigMutable()->sbus_inversion = 0; - featureSet(FEATURE_TELEMETRY); + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; + rxConfigMutable()->sbus_inversion = 0; + featureSet(FEATURE_TELEMETRY); #elif defined(FF_ACROWHOOPSP) - rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; - rxConfigMutable()->spektrum_sat_bind = 5; - rxConfigMutable()->spektrum_sat_bind_autoreset = 1; + rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; + rxConfigMutable()->spektrum_sat_bind = 5; + rxConfigMutable()->spektrum_sat_bind_autoreset = 1; #endif - pidProfilesMutable(0)->pid[PID_ROLL].P = 80; - pidProfilesMutable(0)->pid[PID_ROLL].I = 37; - pidProfilesMutable(0)->pid[PID_ROLL].D = 35; - pidProfilesMutable(0)->pid[PID_PITCH].P = 100; - pidProfilesMutable(0)->pid[PID_PITCH].I = 37; - pidProfilesMutable(0)->pid[PID_PITCH].D = 35; - pidProfilesMutable(0)->pid[PID_YAW].P = 180; - pidProfilesMutable(0)->pid[PID_YAW].D = 45; + pidProfilesMutable(0)->pid[PID_ROLL].P = 80; + pidProfilesMutable(0)->pid[PID_ROLL].I = 37; + pidProfilesMutable(0)->pid[PID_ROLL].D = 35; + pidProfilesMutable(0)->pid[PID_PITCH].P = 100; + pidProfilesMutable(0)->pid[PID_PITCH].I = 37; + pidProfilesMutable(0)->pid[PID_PITCH].D = 35; + pidProfilesMutable(0)->pid[PID_YAW].P = 180; + pidProfilesMutable(0)->pid[PID_YAW].D = 45; - controlRateProfilesMutable(0)->rcRate8 = 100; - controlRateProfilesMutable(0)->rcYawRate8 = 100; - controlRateProfilesMutable(0)->rcExpo8 = 15; - controlRateProfilesMutable(0)->rcYawExpo8 = 15; - controlRateProfilesMutable(0)->rates[PID_ROLL] = 80; - controlRateProfilesMutable(0)->rates[PID_PITCH] = 80; - controlRateProfilesMutable(0)->rates[PID_YAW] = 80; -#endif + controlRateProfilesMutable(0)->rcRate8 = 100; + controlRateProfilesMutable(0)->rcYawRate8 = 100; + controlRateProfilesMutable(0)->rcExpo8 = 15; + controlRateProfilesMutable(0)->rcYawExpo8 = 15; + controlRateProfilesMutable(0)->rates[PID_ROLL] = 80; + controlRateProfilesMutable(0)->rates[PID_PITCH] = 80; + controlRateProfilesMutable(0)->rates[PID_YAW] = 80; + } } #endif diff --git a/src/main/target/FF_PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h index 2fcfeb7121..7bea4508ea 100644 --- a/src/main/target/FF_PIKOBLX/target.h +++ b/src/main/target/FF_PIKOBLX/target.h @@ -40,13 +40,9 @@ #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT #define TARGET_CONFIG +#define BRUSHED_ESC_AUTODETECT -#if defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) || defined(FF_NUKE) -#define BRUSHED_MOTORS -#define RX_CHANNELS_TAER -#endif - -#if defined(FF_RACEWHOOP) +#if defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) || defined(FF_NUKE) || defined(FF_RACEWHOOP) #define RX_CHANNELS_TAER #endif @@ -121,13 +117,8 @@ #define SPEKTRUM_BIND_PIN UART3_RX_PIN #endif -#if !(defined(FF_NUKE) || defined(FF_ACROWHOPFR) || defined(FF_ACROWHOPSP) || defined(FF_RACEWHOOP)) #define TRANSPONDER -#endif - -#if !defined(BRUSHED_MOTORS) #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#endif // IO - stm32f303cc in 48pin package #define TARGET_IO_PORTA 0xffff From 337d9823a34c307bc5b964c2241719ebadc05a28 Mon Sep 17 00:00:00 2001 From: Michael Jakob Date: Sat, 27 May 2017 18:58:31 +0200 Subject: [PATCH 4/4] Final reduction of targets --- Makefile | 5 ---- src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk | 3 --- src/main/target/FF_PIKOBLX/FF_KOMBINI.mk | 2 +- src/main/target/FF_PIKOBLX/FF_KOMBINID.mk | 3 --- src/main/target/FF_PIKOBLX/FF_NUKE.mk | 2 -- src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk | 3 --- src/main/target/FF_PIKOBLX/FF_RADIANCE.mk | 2 +- src/main/target/FF_PIKOBLX/FF_RADIANCED.mk | 2 -- src/main/target/FF_PIKOBLX/config.c | 13 +++++----- src/main/target/FF_PIKOBLX/target.c | 2 +- src/main/target/FF_PIKOBLX/target.h | 26 ++++---------------- 11 files changed, 15 insertions(+), 48 deletions(-) delete mode 100644 src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk delete mode 100644 src/main/target/FF_PIKOBLX/FF_KOMBINID.mk delete mode 100644 src/main/target/FF_PIKOBLX/FF_NUKE.mk delete mode 100644 src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk delete mode 100644 src/main/target/FF_PIKOBLX/FF_RADIANCED.mk diff --git a/Makefile b/Makefile index eaf4a52153..f7bf4b89b7 100644 --- a/Makefile +++ b/Makefile @@ -128,17 +128,12 @@ GROUP_2_TARGETS := \ F4BY \ FISHDRONEF4 \ FLIP32F3OSD \ - FF_ACROWHOOPFR \ FF_ACROWHOOPSP \ FF_FORTINIF4 \ FF_KOMBINI \ - FF_KOMBINID \ - FF_NUKE \ FF_PIKOBLX \ FF_PIKOF4 \ - FF_RACEWHOOP \ FF_RADIANCE \ - FF_RADIANCED \ FURYF3 \ FURYF4 \ FURYF7 \ diff --git a/src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk b/src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk deleted file mode 100644 index 75f2df026e..0000000000 --- a/src/main/target/FF_PIKOBLX/FF_ACROWHOOPFR.mk +++ /dev/null @@ -1,3 +0,0 @@ -# ACROWHOOPFR is a variant of PIKOBLX -# small brushed FC with FrSky receiver onboard -# designed for inductrix and similar copters diff --git a/src/main/target/FF_PIKOBLX/FF_KOMBINI.mk b/src/main/target/FF_PIKOBLX/FF_KOMBINI.mk index 1107387a1e..9244af15bf 100644 --- a/src/main/target/FF_PIKOBLX/FF_KOMBINI.mk +++ b/src/main/target/FF_PIKOBLX/FF_KOMBINI.mk @@ -1,3 +1,3 @@ -# KOMBINI is a variant of PIKOBLX +# KOMBINID is a variant of PIKOBLX (DSHOT ready version) # FC with integrated PDB and current sensor # 12V and 5V BEC onboard diff --git a/src/main/target/FF_PIKOBLX/FF_KOMBINID.mk b/src/main/target/FF_PIKOBLX/FF_KOMBINID.mk deleted file mode 100644 index 9244af15bf..0000000000 --- a/src/main/target/FF_PIKOBLX/FF_KOMBINID.mk +++ /dev/null @@ -1,3 +0,0 @@ -# KOMBINID is a variant of PIKOBLX (DSHOT ready version) -# FC with integrated PDB and current sensor -# 12V and 5V BEC onboard diff --git a/src/main/target/FF_PIKOBLX/FF_NUKE.mk b/src/main/target/FF_PIKOBLX/FF_NUKE.mk deleted file mode 100644 index 3f06589379..0000000000 --- a/src/main/target/FF_PIKOBLX/FF_NUKE.mk +++ /dev/null @@ -1,2 +0,0 @@ -# NUKE is a variant of PIKOBLX -# very small brushed FC, (16mmx16mm) hole spacing diff --git a/src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk b/src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk deleted file mode 100644 index 7a46ba683e..0000000000 --- a/src/main/target/FF_PIKOBLX/FF_RACEWHOOP.mk +++ /dev/null @@ -1,3 +0,0 @@ -# RACEWHOOP is a variant of PIKOBLX -# small FC with current sensor -# designed for vers small brushless copters (e.g. MOSKITO70) diff --git a/src/main/target/FF_PIKOBLX/FF_RADIANCE.mk b/src/main/target/FF_PIKOBLX/FF_RADIANCE.mk index ef6e760f96..616187aa8e 100644 --- a/src/main/target/FF_PIKOBLX/FF_RADIANCE.mk +++ b/src/main/target/FF_PIKOBLX/FF_RADIANCE.mk @@ -1,2 +1,2 @@ -# RADIANCE is a variant of PIKOBLX +# RADIANCED is a variant of PIKOBLX (DSHOT ready version) # similar to Kombini, but without PDB and current sensor diff --git a/src/main/target/FF_PIKOBLX/FF_RADIANCED.mk b/src/main/target/FF_PIKOBLX/FF_RADIANCED.mk deleted file mode 100644 index 616187aa8e..0000000000 --- a/src/main/target/FF_PIKOBLX/FF_RADIANCED.mk +++ /dev/null @@ -1,2 +0,0 @@ -# RADIANCED is a variant of PIKOBLX (DSHOT ready version) -# similar to Kombini, but without PDB and current sensor diff --git a/src/main/target/FF_PIKOBLX/config.c b/src/main/target/FF_PIKOBLX/config.c index 7cc94523a4..4d595e3a8c 100644 --- a/src/main/target/FF_PIKOBLX/config.c +++ b/src/main/target/FF_PIKOBLX/config.c @@ -52,16 +52,17 @@ void targetConfiguration(void) if (hardwareMotorType == MOTOR_BRUSHED) { motorConfigMutable()->dev.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; motorConfigMutable()->minthrottle = 1049; - -#if defined(FF_ACROWHOOPFR) - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; - rxConfigMutable()->sbus_inversion = 0; - featureSet(FEATURE_TELEMETRY); -#elif defined(FF_ACROWHOOPSP) + +#if defined(FF_ACROWHOOPSP) rxConfigMutable()->serialrx_provider = SERIALRX_SPEKTRUM2048; rxConfigMutable()->spektrum_sat_bind = 5; rxConfigMutable()->spektrum_sat_bind_autoreset = 1; +#else + serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART2)].functionMask = FUNCTION_TELEMETRY_FRSKY; + rxConfigMutable()->sbus_inversion = 0; + featureSet(FEATURE_TELEMETRY); #endif + parseRcChannels("TAER1234", rxConfigMutable()); pidProfilesMutable(0)->pid[PID_ROLL].P = 80; pidProfilesMutable(0)->pid[PID_ROLL].I = 37; diff --git a/src/main/target/FF_PIKOBLX/target.c b/src/main/target/FF_PIKOBLX/target.c index 8db259922b..8582b58682 100644 --- a/src/main/target/FF_PIKOBLX/target.c +++ b/src/main/target/FF_PIKOBLX/target.c @@ -25,7 +25,7 @@ #include "drivers/dma.h" const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { -#if defined(FF_RADIANCED) || defined(FF_KOMBINID) || defined(FF_RACEWHOOP) +#if defined(FF_RADIANCE) || defined(FF_KOMBINI) DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR, 1), // PWM1 - PA7 - *TIM17_CH1, TIM1_CH1N, TIM8_CH1 DEF_TIM(TIM3, CH1, PA6, TIM_USE_MOTOR, 1), // PWM2 - PA6 - *TIM3_CH1, TIM8_BKIN, TIM1_BKIN, TIM16_CH1 DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 1), // PWM3 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N diff --git a/src/main/target/FF_PIKOBLX/target.h b/src/main/target/FF_PIKOBLX/target.h index 7bea4508ea..09554c22a9 100644 --- a/src/main/target/FF_PIKOBLX/target.h +++ b/src/main/target/FF_PIKOBLX/target.h @@ -17,22 +17,12 @@ #pragma once -#if defined(FF_RADIANCED) -#define TARGET_BOARD_IDENTIFIER "RADD" // Furious FPV RADIANCE DSHOT -#elif defined(FF_RADIANCE) -#define TARGET_BOARD_IDENTIFIER "RADI" // Furious FPV RADIANCE V1 -#elif defined(FF_KOMBINID) -#define TARGET_BOARD_IDENTIFIER "KOMD" // Furious FPV KOMBINI DSHOT +#if defined(FF_RADIANCE) +#define TARGET_BOARD_IDENTIFIER "RADI" // Furious FPV RADIANCE #elif defined(FF_KOMBINI) -#define TARGET_BOARD_IDENTIFIER "KOMB" // Furious FPV KOMBINI V1 -#elif defined(FF_RACEWHOOP) -#define TARGET_BOARD_IDENTIFIER "RWHO" // Furious FPV RACEWHOOP -#elif defined(FF_ACROWHOOPFR) -#define TARGET_BOARD_IDENTIFIER "AWHF" // Furious FPV ACROWHOOP FRSKY +#define TARGET_BOARD_IDENTIFIER "KOMB" // Furious FPV KOMBINI #elif defined(FF_ACROWHOOPSP) #define TARGET_BOARD_IDENTIFIER "AWHS" // Furious FPV ACROWHOOP SPEKTRUM -#elif defined(FF_NUKE) -#define TARGET_BOARD_IDENTIFIER "NUKE" // Furious FPV NUKE #else #define TARGET_BOARD_IDENTIFIER "PIKO" // Furious FPV PIKOBLX #endif @@ -42,10 +32,6 @@ #define TARGET_CONFIG #define BRUSHED_ESC_AUTODETECT -#if defined(FF_ACROWHOOPFR) || defined(FF_ACROWHOOPSP) || defined(FF_NUKE) || defined(FF_RACEWHOOP) -#define RX_CHANNELS_TAER -#endif - #define LED0 PB9 #define LED1 PB5 @@ -101,17 +87,15 @@ #define VBAT_ADC_PIN PA5 -#if defined(FF_KOMBINI) || defined(FF_KOMBINID) +#if defined(FF_KOMBINI) #define CURRENT_METER_SCALE_DEFAULT 125 -#elif defined(FF_RACEWHOOP) -#define CURRENT_METER_SCALE_DEFAULT 1000 #endif #define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL #define SERIALRX_PROVIDER SERIALRX_SBUS #define SERIALRX_UART SERIAL_PORT_USART3 -#if defined(FF_RADIANCE) || defined(FF_RADIANCED) +#if defined(FF_RADIANCE) #define SPEKTRUM_BIND_PIN UART2_RX_PIN #else #define SPEKTRUM_BIND_PIN UART3_RX_PIN