mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-25 09:16:07 +03:00
Move custom configuration for AlienFlight and Colibri Race to target
directory
This commit is contained in:
parent
fc4dbcdfcf
commit
67a48ca4c9
9 changed files with 389 additions and 39 deletions
|
@ -89,6 +89,7 @@
|
|||
#endif
|
||||
|
||||
void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
|
||||
void targetConfiguration(void);
|
||||
|
||||
#if !defined(FLASH_SIZE)
|
||||
#error "Flash size not defined for target. (specify in KB)"
|
||||
|
@ -652,41 +653,8 @@ static void resetConf(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
// alternative defaults settings for COLIBRI RACE targets
|
||||
#if defined(COLIBRI_RACE)
|
||||
masterConfig.escAndServoConfig.minthrottle = 1025;
|
||||
masterConfig.escAndServoConfig.maxthrottle = 1980;
|
||||
masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
|
||||
masterConfig.batteryConfig.vbatmincellvoltage = 30;
|
||||
#endif
|
||||
|
||||
#if defined(TARGET_CONFIG)
|
||||
targetConfiguration(&masterConfig);
|
||||
#endif
|
||||
|
||||
#if defined(ALIENFLIGHT)
|
||||
featureClear(FEATURE_ONESHOT125);
|
||||
#ifdef ALIENFLIGHTF3
|
||||
masterConfig.mag_hardware = MAG_NONE; // disabled by default
|
||||
#endif
|
||||
masterConfig.rxConfig.spektrum_sat_bind = 5;
|
||||
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
|
||||
masterConfig.motor_pwm_rate = 32000;
|
||||
masterConfig.failsafeConfig.failsafe_delay = 2;
|
||||
masterConfig.failsafeConfig.failsafe_off_delay = 0;
|
||||
currentControlRateProfile->rates[FD_PITCH] = 40;
|
||||
currentControlRateProfile->rates[FD_ROLL] = 40;
|
||||
currentControlRateProfile->rates[FD_YAW] = 40;
|
||||
parseRcChannels("TAER1234", &masterConfig.rxConfig);
|
||||
|
||||
masterConfig.customMotorMixer[0] = (motorMixer_t){ 1.0f, -0.414178f, 1.0f, -1.0f }; // REAR_R
|
||||
masterConfig.customMotorMixer[1] = (motorMixer_t){ 1.0f, -0.414178f, -1.0f, 1.0f }; // FRONT_R
|
||||
masterConfig.customMotorMixer[2] = (motorMixer_t){ 1.0f, 0.414178f, 1.0f, 1.0f }; // REAR_L
|
||||
masterConfig.customMotorMixer[3] = (motorMixer_t){ 1.0f, 0.414178f, -1.0f, -1.0f }; // FRONT_L
|
||||
masterConfig.customMotorMixer[4] = (motorMixer_t){ 1.0f, -1.0f, -0.414178f, -1.0f }; // MIDFRONT_R
|
||||
masterConfig.customMotorMixer[5] = (motorMixer_t){ 1.0f, 1.0f, -0.414178f, 1.0f }; // MIDFRONT_L
|
||||
masterConfig.customMotorMixer[6] = (motorMixer_t){ 1.0f, -1.0f, 0.414178f, 1.0f }; // MIDREAR_R
|
||||
masterConfig.customMotorMixer[7] = (motorMixer_t){ 1.0f, 1.0f, 0.414178f, -1.0f }; // MIDREAR_L#endif
|
||||
targetConfiguration();
|
||||
#endif
|
||||
|
||||
// copy first profile into remaining profile
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue