1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

merge upstream into sirinfpv branch

This commit is contained in:
Evgeny Sychov 2016-06-10 19:42:54 -07:00
commit eb5963809d
77 changed files with 3017 additions and 946 deletions

View file

@ -55,6 +55,7 @@
#include "io/ledstrip.h"
#include "io/gps.h"
#include "io/osd.h"
#include "io/vtx.h"
#include "rx/rx.h"
@ -73,6 +74,10 @@
#include "config/config_profile.h"
#include "config/config_master.h"
#ifndef DEFAULT_RX_FEATURE
#define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
#endif
#define BRUSHED_MOTORS_PWM_RATE 16000
#define BRUSHLESS_MOTORS_PWM_RATE 400
@ -125,8 +130,14 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es
#define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
#endif
// use the last flash pages for storage
#ifdef CUSTOM_FLASH_MEMORY_ADDRESS
size_t custom_flash_memory_address = 0;
#define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
#else
// use the last flash pages for storage
#define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
#endif
master_t masterConfig; // master config struct with data independent from profiles
profile_t *currentProfile;
@ -135,7 +146,7 @@ static uint32_t activeFeaturesLatch = 0;
static uint8_t currentControlRateProfileIndex = 0;
controlRateConfig_t *currentControlRateProfile;
static const uint8_t EEPROM_CONF_VERSION = 133;
static const uint8_t EEPROM_CONF_VERSION = 140;
static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
{
@ -149,14 +160,14 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->pidController = 1;
pidProfile->P8[ROLL] = 45;
pidProfile->I8[ROLL] = 30;
pidProfile->D8[ROLL] = 18;
pidProfile->I8[ROLL] = 40;
pidProfile->D8[ROLL] = 15;
pidProfile->P8[PITCH] = 45;
pidProfile->I8[PITCH] = 30;
pidProfile->D8[PITCH] = 18;
pidProfile->I8[PITCH] = 40;
pidProfile->D8[PITCH] = 15;
pidProfile->P8[YAW] = 90;
pidProfile->I8[YAW] = 40;
pidProfile->D8[YAW] = 0;
pidProfile->I8[YAW] = 45;
pidProfile->D8[YAW] = 20;
pidProfile->P8[PIDALT] = 50;
pidProfile->I8[PIDALT] = 0;
pidProfile->D8[PIDALT] = 0;
@ -178,14 +189,11 @@ static void resetPidProfile(pidProfile_t *pidProfile)
pidProfile->D8[PIDVEL] = 75;
pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
pidProfile->yaw_lpf_hz = 70.0f;
pidProfile->dterm_differentiator = 1;
pidProfile->rollPitchItermResetRate = 200;
pidProfile->rollPitchItermResetAlways = 0;
pidProfile->yawItermResetRate = 50;
pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default
pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes
pidProfile->yaw_lpf_hz = 80;
pidProfile->rollPitchItermIgnoreRate = 200;
pidProfile->yawItermIgnoreRate = 45;
pidProfile->dterm_lpf_hz = 110; // filtering ON by default
pidProfile->dynamic_pid = 1;
#ifdef GTUNE
pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
@ -234,6 +242,7 @@ void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
escAndServoConfig->maxthrottle = 1850;
escAndServoConfig->mincommand = 1000;
escAndServoConfig->servoCenterPulse = 1500;
escAndServoConfig->escDesyncProtection = 10000;
}
void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
@ -306,15 +315,16 @@ void resetSerialConfig(serialConfig_t *serialConfig)
static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
controlRateConfig->rcRate8 = 100;
controlRateConfig->rcExpo8 = 60;
controlRateConfig->rcYawRate8 = 100;
controlRateConfig->rcExpo8 = 10;
controlRateConfig->thrMid8 = 50;
controlRateConfig->thrExpo8 = 0;
controlRateConfig->dynThrPID = 0;
controlRateConfig->rcYawExpo8 = 20;
controlRateConfig->tpa_breakpoint = 1500;
controlRateConfig->dynThrPID = 20;
controlRateConfig->rcYawExpo8 = 10;
controlRateConfig->tpa_breakpoint = 1650;
for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
controlRateConfig->rates[axis] = 50;
controlRateConfig->rates[axis] = 70;
}
}
@ -328,7 +338,6 @@ void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
void resetMixerConfig(mixerConfig_t *mixerConfig) {
mixerConfig->yaw_motor_direction = 1;
mixerConfig->yaw_jump_prevention_limit = 200;
#ifdef USE_SERVOS
mixerConfig->tri_unarmed_servo = 1;
mixerConfig->servo_lowpass_freq = 400;
@ -378,17 +387,12 @@ static void resetConf(void)
memset(&masterConfig, 0, sizeof(master_t));
setProfile(0);
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
featureClearAll();
#if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE)
featureSet(FEATURE_RX_PPM);
featureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE | FEATURE_SUPEREXPO_RATES);
#ifdef DEFAULT_FEATURES
featureSet(DEFAULT_FEATURES);
#endif
//#if defined(SPRACINGF3MINI)
// featureSet(FEATURE_DISPLAY);
//#endif
#ifdef SIRINFPV
featureSet(FEATURE_OSD);
featureSet(FEATURE_RX_SERIAL);
@ -418,18 +422,22 @@ static void resetConf(void)
featureSet(FEATURE_VBAT);
#endif
featureSet(FEATURE_FAILSAFE);
featureSet(FEATURE_ONESHOT125);
masterConfig.version = EEPROM_CONF_VERSION;
masterConfig.mixerMode = MIXER_QUADX;
// global settings
masterConfig.current_profile_index = 0; // default profile
masterConfig.dcm_kp = 2500; // 1.0 * 10000
masterConfig.dcm_ki = 0; // 0.003 * 10000
masterConfig.gyro_lpf = 0; // 256HZ default
#ifdef STM32F10X
masterConfig.gyro_sync_denom = 8;
masterConfig.gyro_soft_lpf_hz = 80.0f;
#else
masterConfig.gyro_sync_denom = 4;
#endif
masterConfig.gyro_soft_lpf_hz = 100;
masterConfig.pid_process_denom = 1;
masterConfig.pid_process_denom = 2;
masterConfig.debug_mode = 0;
@ -459,7 +467,7 @@ static void resetConf(void)
masterConfig.rxConfig.spektrum_sat_bind = 0;
masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
masterConfig.rxConfig.midrc = 1500;
masterConfig.rxConfig.mincheck = 1080;
masterConfig.rxConfig.mincheck = 1100;
masterConfig.rxConfig.maxcheck = 1900;
masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
@ -476,9 +484,7 @@ static void resetConf(void)
masterConfig.rxConfig.rcSmoothing = 0;
masterConfig.rxConfig.fpvCamAngleDegrees = 0;
masterConfig.rxConfig.max_aux_channel = 6;
masterConfig.rxConfig.superExpoFactor = 30;
masterConfig.rxConfig.superExpoFactorYaw = 30;
masterConfig.rxConfig.superExpoYawMode = 0;
masterConfig.rxConfig.airModeActivateThreshold = 1350;
resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
@ -503,7 +509,8 @@ static void resetConf(void)
masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
#endif
masterConfig.servo_pwm_rate = 50;
masterConfig.use_oneshot42 = 0;
masterConfig.fast_pwm_protocol = 1;
masterConfig.use_unsyncedPwm = 0;
#ifdef CC3D
masterConfig.use_buzzer_p6 = 0;
#endif
@ -518,11 +525,7 @@ static void resetConf(void)
resetSerialConfig(&masterConfig.serialConfig);
#if defined(STM32F10X) && !defined(CC3D)
masterConfig.emf_avoidance = 1;
#else
masterConfig.emf_avoidance = 0;
#endif
masterConfig.emf_avoidance = 0; // TODO - needs removal
resetPidProfile(&currentProfile->pidProfile);
@ -583,10 +586,17 @@ static void resetConf(void)
#ifdef LED_STRIP
applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT);
applyDefaultLedStripConfig(masterConfig.ledConfigs);
masterConfig.ledstrip_visual_beeper = 0;
#endif
#ifdef VTX
masterConfig.vtx_band = 4; //Fatshark/Airwaves
masterConfig.vtx_channel = 1; //CH1
masterConfig.vtx_mode = 0; //CH+BAND mode
masterConfig.vtx_mhz = 5740; //F0
#endif
#ifdef SPRACINGF3
featureSet(FEATURE_BLACKBOX);
masterConfig.blackbox_device = 1;
#ifdef TRANSPONDER
static const uint8_t defaultTransponderData[6] = { 0x12, 0x34, 0x56, 0x78, 0x9A, 0xBC }; // Note, this is NOT a valid transponder code, it's just for testing production hardware
@ -608,22 +618,18 @@ static void resetConf(void)
masterConfig.blackbox_rate_denom = 1;
#endif
#if defined(FURYF3)
masterConfig.blackbox_device = 2;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
#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;
featureSet(FEATURE_VBAT);
featureSet(FEATURE_FAILSAFE);
#endif
#ifdef SPRACINGF3EVO
featureSet(FEATURE_TRANSPONDER);
featureSet(FEATURE_RSSI_ADC);
featureSet(FEATURE_CURRENT_METER);
featureSet(FEATURE_TELEMETRY);
#endif
// alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
@ -647,7 +653,6 @@ static void resetConf(void)
currentProfile->pidProfile.pidController = 2;
masterConfig.failsafeConfig.failsafe_delay = 2;
masterConfig.failsafeConfig.failsafe_off_delay = 0;
masterConfig.mixerConfig.yaw_jump_prevention_limit = 500;
currentControlRateProfile->rcRate8 = 100;
currentControlRateProfile->rates[FD_PITCH] = 20;
currentControlRateProfile->rates[FD_ROLL] = 20;
@ -703,6 +708,17 @@ static void resetConf(void)
masterConfig.customMotorMixer[7].yaw = -1.0f;
#endif
// alternative defaults settings for SINGULARITY target
#if defined(SINGULARITY)
masterConfig.blackbox_device = 1;
masterConfig.blackbox_rate_num = 1;
masterConfig.blackbox_rate_denom = 1;
masterConfig.batteryConfig.vbatscale = 77;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
#endif
// copy first profile into remaining profile
for (i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
@ -744,8 +760,6 @@ static bool isEEPROMContentValid(void)
void activateControlRateConfig(void)
{
generatePitchRollCurve(currentControlRateProfile);
generateYawCurve(currentControlRateProfile);
generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig);
}
@ -818,7 +832,7 @@ void activateConfig(void)
void validateAndFixConfig(void)
{
if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
featureSet(FEATURE_RX_PARALLEL_PWM);
}
if (featureConfigured(FEATURE_RX_PPM)) {
@ -1135,12 +1149,12 @@ void setBeeperOffMask(uint32_t mask)
masterConfig.beeper_off_flags = mask;
}
uint32_t getPreferedBeeperOffMask(void)
uint32_t getPreferredBeeperOffMask(void)
{
return masterConfig.prefered_beeper_off_flags;
return masterConfig.preferred_beeper_off_flags;
}
void setPreferedBeeperOffMask(uint32_t mask)
void setPreferredBeeperOffMask(uint32_t mask)
{
masterConfig.prefered_beeper_off_flags = mask;
masterConfig.preferred_beeper_off_flags = mask;
}