mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-21 23:35:34 +03:00
Instead of copying a profile from the master config into memory again,
just use it in-place. This saves ~308bytes of memory.
Prior to this there were 4 profiles in ram all the time, the 3 main
profiles and a copy of one of them.
This commit was aided by a side effect of the work done to clean up the
output of the cli dump command since it is now easy to conditionally
apply the changes to the memory addressed used to read/write cli
variables. See 8c3a869251
.
Conflicts:
src/main/io/serial_msp.c
This commit is contained in:
parent
bc34fc3744
commit
f51efaa7c0
10 changed files with 262 additions and 262 deletions
|
@ -84,7 +84,7 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon
|
|||
static uint32_t flashWriteAddress = (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG));
|
||||
|
||||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t currentProfile; // profile config struct
|
||||
profile_t *currentProfile; // profile config struct
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 75;
|
||||
|
||||
|
@ -290,66 +290,66 @@ static void resetConf(void)
|
|||
masterConfig.looptime = 3500;
|
||||
masterConfig.emf_avoidance = 0;
|
||||
|
||||
currentProfile.pidController = 0;
|
||||
resetPidProfile(¤tProfile.pidProfile);
|
||||
currentProfile->pidController = 0;
|
||||
resetPidProfile(¤tProfile->pidProfile);
|
||||
|
||||
currentProfile.controlRateConfig.rcRate8 = 90;
|
||||
currentProfile.controlRateConfig.rcExpo8 = 65;
|
||||
currentProfile.controlRateConfig.rollPitchRate = 0;
|
||||
currentProfile.controlRateConfig.yawRate = 0;
|
||||
currentProfile.dynThrPID = 0;
|
||||
currentProfile.tpa_breakpoint = 1500;
|
||||
currentProfile.controlRateConfig.thrMid8 = 50;
|
||||
currentProfile.controlRateConfig.thrExpo8 = 0;
|
||||
currentProfile->controlRateConfig.rcRate8 = 90;
|
||||
currentProfile->controlRateConfig.rcExpo8 = 65;
|
||||
currentProfile->controlRateConfig.rollPitchRate = 0;
|
||||
currentProfile->controlRateConfig.yawRate = 0;
|
||||
currentProfile->dynThrPID = 0;
|
||||
currentProfile->tpa_breakpoint = 1500;
|
||||
currentProfile->controlRateConfig.thrMid8 = 50;
|
||||
currentProfile->controlRateConfig.thrExpo8 = 0;
|
||||
|
||||
// for (i = 0; i < CHECKBOXITEMS; i++)
|
||||
// cfg.activate[i] = 0;
|
||||
|
||||
resetRollAndPitchTrims(¤tProfile.accelerometerTrims);
|
||||
resetRollAndPitchTrims(¤tProfile->accelerometerTrims);
|
||||
|
||||
currentProfile.mag_declination = 0;
|
||||
currentProfile.acc_lpf_factor = 4;
|
||||
currentProfile.accz_lpf_cutoff = 5.0f;
|
||||
currentProfile.accDeadband.xy = 40;
|
||||
currentProfile.accDeadband.z = 40;
|
||||
currentProfile->mag_declination = 0;
|
||||
currentProfile->acc_lpf_factor = 4;
|
||||
currentProfile->accz_lpf_cutoff = 5.0f;
|
||||
currentProfile->accDeadband.xy = 40;
|
||||
currentProfile->accDeadband.z = 40;
|
||||
|
||||
resetBarometerConfig(¤tProfile.barometerConfig);
|
||||
resetBarometerConfig(¤tProfile->barometerConfig);
|
||||
|
||||
currentProfile.acc_unarmedcal = 1;
|
||||
currentProfile->acc_unarmedcal = 1;
|
||||
|
||||
// Radio
|
||||
parseRcChannels("AETR1234", &masterConfig.rxConfig);
|
||||
currentProfile.deadband = 0;
|
||||
currentProfile.yaw_deadband = 0;
|
||||
currentProfile.alt_hold_deadband = 40;
|
||||
currentProfile.alt_hold_fast_change = 1;
|
||||
currentProfile.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||
currentProfile.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
currentProfile->deadband = 0;
|
||||
currentProfile->yaw_deadband = 0;
|
||||
currentProfile->alt_hold_deadband = 40;
|
||||
currentProfile->alt_hold_fast_change = 1;
|
||||
currentProfile->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
|
||||
currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
|
||||
|
||||
// Failsafe Variables
|
||||
currentProfile.failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
currentProfile.failsafeConfig.failsafe_off_delay = 200; // 20sec
|
||||
currentProfile.failsafeConfig.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people.
|
||||
currentProfile.failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe
|
||||
currentProfile.failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe
|
||||
currentProfile->failsafeConfig.failsafe_delay = 10; // 1sec
|
||||
currentProfile->failsafeConfig.failsafe_off_delay = 200; // 20sec
|
||||
currentProfile->failsafeConfig.failsafe_throttle = 1200; // decent default which should always be below hover throttle for people.
|
||||
currentProfile->failsafeConfig.failsafe_min_usec = 985; // any of first 4 channels below this value will trigger failsafe
|
||||
currentProfile->failsafeConfig.failsafe_max_usec = 2115; // any of first 4 channels above this value will trigger failsafe
|
||||
|
||||
// servos
|
||||
for (i = 0; i < 8; i++) {
|
||||
currentProfile.servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
currentProfile.servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
currentProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
currentProfile.servoConf[i].rate = servoRates[i];
|
||||
currentProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN;
|
||||
currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX;
|
||||
currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
|
||||
currentProfile->servoConf[i].rate = servoRates[i];
|
||||
currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
|
||||
}
|
||||
|
||||
currentProfile.mixerConfig.yaw_direction = 1;
|
||||
currentProfile.mixerConfig.tri_unarmed_servo = 1;
|
||||
currentProfile->mixerConfig.yaw_direction = 1;
|
||||
currentProfile->mixerConfig.tri_unarmed_servo = 1;
|
||||
|
||||
// gimbal
|
||||
currentProfile.gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
|
||||
currentProfile->gimbalConfig.gimbal_flags = GIMBAL_NORMAL;
|
||||
|
||||
#ifdef GPS
|
||||
resetGpsProfile(¤tProfile.gpsProfile);
|
||||
resetGpsProfile(¤tProfile->gpsProfile);
|
||||
#endif
|
||||
|
||||
// custom mixer. clear by defaults.
|
||||
|
@ -397,43 +397,43 @@ void activateConfig(void)
|
|||
{
|
||||
static imuRuntimeConfig_t imuRuntimeConfig;
|
||||
|
||||
generatePitchCurve(¤tProfile.controlRateConfig);
|
||||
generateThrottleCurve(¤tProfile.controlRateConfig, &masterConfig.escAndServoConfig);
|
||||
generatePitchCurve(¤tProfile->controlRateConfig);
|
||||
generateThrottleCurve(¤tProfile->controlRateConfig, &masterConfig.escAndServoConfig);
|
||||
|
||||
useGyroConfig(&masterConfig.gyroConfig);
|
||||
#ifdef TELEMETRY
|
||||
useTelemetryConfig(&masterConfig.telemetryConfig);
|
||||
#endif
|
||||
setPIDController(currentProfile.pidController);
|
||||
setPIDController(currentProfile->pidController);
|
||||
#ifdef GPS
|
||||
gpsUseProfile(¤tProfile.gpsProfile);
|
||||
gpsUsePIDs(¤tProfile.pidProfile);
|
||||
gpsUseProfile(¤tProfile->gpsProfile);
|
||||
gpsUsePIDs(¤tProfile->pidProfile);
|
||||
#endif
|
||||
useFailsafeConfig(¤tProfile.failsafeConfig);
|
||||
useFailsafeConfig(¤tProfile->failsafeConfig);
|
||||
setAccelerationTrims(&masterConfig.accZero);
|
||||
mixerUseConfigs(
|
||||
currentProfile.servoConf,
|
||||
currentProfile->servoConf,
|
||||
&masterConfig.flight3DConfig,
|
||||
&masterConfig.escAndServoConfig,
|
||||
¤tProfile.mixerConfig,
|
||||
¤tProfile->mixerConfig,
|
||||
&masterConfig.airplaneConfig,
|
||||
&masterConfig.rxConfig,
|
||||
¤tProfile.gimbalConfig
|
||||
¤tProfile->gimbalConfig
|
||||
);
|
||||
|
||||
imuRuntimeConfig.gyro_cmpf_factor = masterConfig.gyro_cmpf_factor;
|
||||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||
imuRuntimeConfig.acc_lpf_factor = currentProfile.acc_lpf_factor;
|
||||
imuRuntimeConfig.acc_unarmedcal = currentProfile.acc_unarmedcal;;
|
||||
imuRuntimeConfig.acc_lpf_factor = currentProfile->acc_lpf_factor;
|
||||
imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;;
|
||||
imuRuntimeConfig.small_angle = masterConfig.small_angle;
|
||||
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile.pidProfile, ¤tProfile.barometerConfig, ¤tProfile.accDeadband);
|
||||
configureImu(&imuRuntimeConfig, ¤tProfile->pidProfile, ¤tProfile->barometerConfig, ¤tProfile->accDeadband);
|
||||
|
||||
calculateThrottleAngleScale(currentProfile.throttle_correction_angle);
|
||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile.accz_lpf_cutoff);
|
||||
calculateThrottleAngleScale(currentProfile->throttle_correction_angle);
|
||||
calculateAccZLowPassFilterRCTimeConstant(currentProfile->accz_lpf_cutoff);
|
||||
|
||||
#ifdef BARO
|
||||
useBarometerConfig(¤tProfile.barometerConfig);
|
||||
useBarometerConfig(¤tProfile->barometerConfig);
|
||||
#endif
|
||||
}
|
||||
|
||||
|
@ -529,7 +529,8 @@ void readEEPROM(void)
|
|||
// Copy current profile
|
||||
if (masterConfig.current_profile_index > 2) // sanity check
|
||||
masterConfig.current_profile_index = 0;
|
||||
memcpy(¤tProfile, &masterConfig.profile[masterConfig.current_profile_index], sizeof(profile_t));
|
||||
|
||||
currentProfile = &masterConfig.profile[masterConfig.current_profile_index];
|
||||
|
||||
validateAndFixConfig();
|
||||
activateConfig();
|
||||
|
@ -542,13 +543,6 @@ void readEEPROMAndNotify(void)
|
|||
blinkLedAndSoundBeeper(15, 20, 1);
|
||||
}
|
||||
|
||||
void copyCurrentProfileToProfileSlot(uint8_t profileSlotIndex)
|
||||
{
|
||||
// copy current in-memory profile to stored configuration
|
||||
memcpy(&masterConfig.profile[profileSlotIndex], ¤tProfile, sizeof(profile_t));
|
||||
}
|
||||
|
||||
|
||||
void writeEEPROM(void)
|
||||
{
|
||||
// Generate compile time error if the config does not fit in the reserved area of flash.
|
||||
|
@ -632,9 +626,8 @@ void resetEEPROM(void)
|
|||
writeEEPROM();
|
||||
}
|
||||
|
||||
void saveAndReloadCurrentProfileToCurrentProfileSlot(void)
|
||||
void saveConfigAndNotify(void)
|
||||
{
|
||||
copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
|
||||
writeEEPROM();
|
||||
readEEPROMAndNotify();
|
||||
}
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue