1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Fixed initialisation of pid and rate profiles

This commit is contained in:
Martin Budden 2017-02-26 06:37:45 +00:00
parent a3ad97b0a4
commit 5fb4062a00

View file

@ -936,8 +936,13 @@ void createDefaultConfig(master_t *config)
resetSerialConfig(&config->serialConfig);
resetProfile(&config->profile[0]);
resetControlRateProfile(&config->controlRateProfile[0]);
for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
resetProfile(&config->profile[ii]);
}
for (int ii = 0; ii < MAX_CONTROL_RATE_PROFILE_COUNT; ++ii) {
resetControlRateProfile(&config->controlRateProfile[ii]);
}
config->compassConfig.mag_declination = 0;
@ -1049,11 +1054,6 @@ void createDefaultConfig(master_t *config)
#if defined(TARGET_CONFIG)
targetConfiguration(config);
#endif
// copy first profile into remaining profile
for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
}
}
void resetConfigs(void)