Final reduction of targets

This commit is contained in:
Michael Jakob 2017-05-27 18:58:31 +02:00
parent b333e5cfd8
commit 337d9823a3
11 changed files with 15 additions and 48 deletions

View File

@ -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 \

View File

@ -1,3 +0,0 @@
# ACROWHOOPFR is a variant of PIKOBLX
# small brushed FC with FrSky receiver onboard
# designed for inductrix and similar copters

View File

@ -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

View File

@ -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

View File

@ -1,2 +0,0 @@
# NUKE is a variant of PIKOBLX
# very small brushed FC, (16mmx16mm) hole spacing

View File

@ -1,3 +0,0 @@
# RACEWHOOP is a variant of PIKOBLX
# small FC with current sensor
# designed for vers small brushless copters (e.g. MOSKITO70)

View File

@ -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

View File

@ -1,2 +0,0 @@
# RADIANCED is a variant of PIKOBLX (DSHOT ready version)
# similar to Kombini, but without PDB and current sensor

View File

@ -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;

View File

@ -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

View File

@ -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