mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Cleanup line endings.
This commit is contained in:
parent
2238f535be
commit
9f1a0fcb4c
47 changed files with 6212 additions and 6191 deletions
|
@ -76,7 +76,8 @@ void mixerUseConfigs(servoParam_t *servoConfToUse, flight3DConfig_t *flight3DCon
|
|||
|
||||
// use the last flash pages for storage
|
||||
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
|
||||
|
||||
master_t masterConfig; // master config struct with data independent from profiles
|
||||
profile_t currentProfile; // profile config struct
|
||||
|
||||
static const uint8_t EEPROM_CONF_VERSION = 73;
|
||||
|
@ -134,7 +135,7 @@ static void resetPidProfile(pidProfile_t *pidProfile)
|
|||
|
||||
#ifdef GPS
|
||||
void resetGpsProfile(gpsProfile_t *gpsProfile)
|
||||
{
|
||||
{
|
||||
gpsProfile->gps_wp_radius = 200;
|
||||
gpsProfile->gps_lpf = 20;
|
||||
gpsProfile->nav_slew_rate = 30;
|
||||
|
@ -146,7 +147,7 @@ void resetGpsProfile(gpsProfile_t *gpsProfile)
|
|||
#endif
|
||||
|
||||
void resetBarometerConfig(barometerConfig_t *barometerConfig)
|
||||
{
|
||||
{
|
||||
barometerConfig->baro_sample_count = 21;
|
||||
barometerConfig->baro_noise_lpf = 0.6f;
|
||||
barometerConfig->baro_cf_vel = 0.985f;
|
||||
|
@ -404,7 +405,7 @@ void activateConfig(void)
|
|||
imuRuntimeConfig.gyro_cmpfm_factor = masterConfig.gyro_cmpfm_factor;
|
||||
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);
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue