First run to reduce number of targets

This commit is contained in:
Michael Jakob 2017-05-27 14:39:56 +02:00
parent 6050bd4600
commit b333e5cfd8
2 changed files with 29 additions and 36 deletions

View File

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

View File

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