3.0.1 Defaults // Improve setpoint transition
[betaflight.git] / src / main / config / config.c
blob752eb85fd19e44e484be5ff7d28a97a3295026e5
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
22 #include "platform.h"
23 #include "debug.h"
25 #include "build_config.h"
27 #include "blackbox/blackbox_io.h"
29 #include "common/color.h"
30 #include "common/axis.h"
31 #include "common/maths.h"
32 #include "common/filter.h"
34 #include "drivers/sensor.h"
35 #include "drivers/accgyro.h"
36 #include "drivers/compass.h"
37 #include "drivers/system.h"
38 #include "drivers/gpio.h"
39 #include "drivers/timer.h"
40 #include "drivers/pwm_rx.h"
41 #include "drivers/serial.h"
42 #include "drivers/pwm_output.h"
43 #include "drivers/max7456.h"
45 #include "sensors/sensors.h"
46 #include "sensors/gyro.h"
47 #include "sensors/compass.h"
48 #include "sensors/acceleration.h"
49 #include "sensors/barometer.h"
50 #include "sensors/boardalignment.h"
51 #include "sensors/battery.h"
53 #include "io/beeper.h"
54 #include "io/serial.h"
55 #include "io/gimbal.h"
56 #include "io/escservo.h"
57 #include "io/rc_controls.h"
58 #include "io/rc_curves.h"
59 #include "io/ledstrip.h"
60 #include "io/gps.h"
61 #include "io/osd.h"
62 #include "io/vtx.h"
64 #include "rx/rx.h"
66 #include "telemetry/telemetry.h"
68 #include "flight/mixer.h"
69 #include "flight/pid.h"
70 #include "flight/imu.h"
71 #include "flight/failsafe.h"
72 #include "flight/altitudehold.h"
73 #include "flight/navigation.h"
75 #include "config/runtime_config.h"
76 #include "config/config.h"
78 #include "config/config_profile.h"
79 #include "config/config_master.h"
81 #ifndef DEFAULT_RX_FEATURE
82 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
83 #endif
85 #define BRUSHED_MOTORS_PWM_RATE 16000
86 #ifdef STM32F4
87 #define BRUSHLESS_MOTORS_PWM_RATE 2000
88 #else
89 #define BRUSHLESS_MOTORS_PWM_RATE 400
90 #endif
92 void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
93 void targetConfiguration(master_t *config);
95 #if !defined(FLASH_SIZE)
96 #error "Flash size not defined for target. (specify in KB)"
97 #endif
100 #ifndef FLASH_PAGE_SIZE
101 #ifdef STM32F303xC
102 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
103 #endif
105 #ifdef STM32F10X_MD
106 #define FLASH_PAGE_SIZE ((uint16_t)0x400)
107 #endif
109 #ifdef STM32F10X_HD
110 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
111 #endif
113 #if defined(STM32F40_41xxx)
114 #define FLASH_PAGE_SIZE ((uint32_t)0x20000)
115 #endif
117 #if defined (STM32F411xE)
118 #define FLASH_PAGE_SIZE ((uint32_t)0x20000)
119 #endif
121 #endif
123 #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
124 #ifdef STM32F10X_MD
125 #define FLASH_PAGE_COUNT 128
126 #endif
128 #ifdef STM32F10X_HD
129 #define FLASH_PAGE_COUNT 128
130 #endif
131 #endif
133 #if defined(FLASH_SIZE)
134 #if defined(STM32F40_41xxx)
135 #define FLASH_PAGE_COUNT 4 // just to make calculations work
136 #elif defined (STM32F411xE)
137 #define FLASH_PAGE_COUNT 4 // just to make calculations work
138 #else
139 #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
140 #endif
141 #endif
143 #if !defined(FLASH_PAGE_SIZE)
144 #error "Flash page size not defined for target."
145 #endif
147 #if !defined(FLASH_PAGE_COUNT)
148 #error "Flash page count not defined for target."
149 #endif
151 #if FLASH_SIZE <= 128
152 #define FLASH_TO_RESERVE_FOR_CONFIG 0x800
153 #else
154 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
155 #endif
157 // use the last flash pages for storage
158 #ifdef CUSTOM_FLASH_MEMORY_ADDRESS
159 size_t custom_flash_memory_address = 0;
160 #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
161 #else
162 // use the last flash pages for storage
163 #ifndef CONFIG_START_FLASH_ADDRESS
164 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
165 #endif
166 #endif
168 master_t masterConfig; // master config struct with data independent from profiles
169 profile_t *currentProfile;
170 static uint32_t activeFeaturesLatch = 0;
172 static uint8_t currentControlRateProfileIndex = 0;
173 controlRateConfig_t *currentControlRateProfile;
175 static const uint8_t EEPROM_CONF_VERSION = 146;
177 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
179 accelerometerTrims->values.pitch = 0;
180 accelerometerTrims->values.roll = 0;
181 accelerometerTrims->values.yaw = 0;
184 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
186 controlRateConfig->rcRate8 = 100;
187 controlRateConfig->rcYawRate8 = 100;
188 controlRateConfig->rcExpo8 = 0;
189 controlRateConfig->thrMid8 = 50;
190 controlRateConfig->thrExpo8 = 0;
191 controlRateConfig->dynThrPID = 10;
192 controlRateConfig->rcYawExpo8 = 0;
193 controlRateConfig->tpa_breakpoint = 1650;
195 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
196 controlRateConfig->rates[axis] = 70;
200 static void resetPidProfile(pidProfile_t *pidProfile)
202 #if defined(SKIP_PID_FLOAT)
203 pidProfile->pidController = PID_CONTROLLER_LEGACY;
204 #else
205 pidProfile->pidController = PID_CONTROLLER_BETAFLIGHT;
206 #endif
208 pidProfile->P8[ROLL] = 43;
209 pidProfile->I8[ROLL] = 40;
210 pidProfile->D8[ROLL] = 20;
211 pidProfile->P8[PITCH] = 58;
212 pidProfile->I8[PITCH] = 50;
213 pidProfile->D8[PITCH] = 22;
214 pidProfile->P8[YAW] = 70;
215 pidProfile->I8[YAW] = 45;
216 pidProfile->D8[YAW] = 20;
217 pidProfile->P8[PIDALT] = 50;
218 pidProfile->I8[PIDALT] = 0;
219 pidProfile->D8[PIDALT] = 0;
220 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
221 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
222 pidProfile->D8[PIDPOS] = 0;
223 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
224 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
225 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
226 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
227 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
228 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
229 pidProfile->P8[PIDLEVEL] = 50;
230 pidProfile->I8[PIDLEVEL] = 50;
231 pidProfile->D8[PIDLEVEL] = 100;
232 pidProfile->P8[PIDMAG] = 40;
233 pidProfile->P8[PIDVEL] = 55;
234 pidProfile->I8[PIDVEL] = 55;
235 pidProfile->D8[PIDVEL] = 75;
237 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
238 pidProfile->pidSumLimit = PIDSUM_LIMIT;
239 pidProfile->yaw_lpf_hz = 0;
240 pidProfile->rollPitchItermIgnoreRate = 130;
241 pidProfile->yawItermIgnoreRate = 32;
242 pidProfile->dterm_filter_type = FILTER_BIQUAD;
243 pidProfile->dterm_lpf_hz = 100; // filtering ON by default
244 pidProfile->dterm_notch_hz = 260;
245 pidProfile->dterm_notch_cutoff = 160;
246 pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
247 pidProfile->vbatPidCompensation = 0;
248 pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
250 // Betaflight PID controller parameters
251 pidProfile->setpointRelaxRatio = 30;
252 pidProfile->dtermSetpointWeight = 200;
253 pidProfile->yawRateAccelLimit = 220;
254 pidProfile->rateAccelLimit = 0;
255 pidProfile->itermThrottleGain = 0;
256 pidProfile->levelSensitivity = 2.0f;
258 #ifdef GTUNE
259 pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
260 pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
261 pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
262 pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
263 pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
264 pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
265 pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
266 pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
267 pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
268 #endif
271 void resetProfile(profile_t *profile)
273 resetPidProfile(&profile->pidProfile);
275 for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
276 resetControlRateConfig(&profile->controlRateProfile[rI]);
279 profile->activeRateProfile = 0;
282 #ifdef GPS
283 void resetGpsProfile(gpsProfile_t *gpsProfile)
285 gpsProfile->gps_wp_radius = 200;
286 gpsProfile->gps_lpf = 20;
287 gpsProfile->nav_slew_rate = 30;
288 gpsProfile->nav_controls_heading = 1;
289 gpsProfile->nav_speed_min = 100;
290 gpsProfile->nav_speed_max = 300;
291 gpsProfile->ap_mode = 40;
293 #endif
295 #ifdef BARO
296 void resetBarometerConfig(barometerConfig_t *barometerConfig)
298 barometerConfig->baro_sample_count = 21;
299 barometerConfig->baro_noise_lpf = 0.6f;
300 barometerConfig->baro_cf_vel = 0.985f;
301 barometerConfig->baro_cf_alt = 0.965f;
303 #endif
305 void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
307 sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
308 sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
309 sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
312 void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
314 #ifdef BRUSHED_MOTORS
315 escAndServoConfig->minthrottle = 1000;
316 #else
317 escAndServoConfig->minthrottle = 1070;
318 #endif
319 escAndServoConfig->maxthrottle = 2000;
320 escAndServoConfig->mincommand = 1000;
321 escAndServoConfig->servoCenterPulse = 1500;
322 escAndServoConfig->maxEscThrottleJumpMs = 0;
325 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
327 flight3DConfig->deadband3d_low = 1406;
328 flight3DConfig->deadband3d_high = 1514;
329 flight3DConfig->neutral3d = 1460;
330 flight3DConfig->deadband3d_throttle = 50;
333 #ifdef TELEMETRY
334 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
336 telemetryConfig->telemetry_inversion = 1;
337 telemetryConfig->telemetry_switch = 0;
338 telemetryConfig->gpsNoFixLatitude = 0;
339 telemetryConfig->gpsNoFixLongitude = 0;
340 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
341 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
342 telemetryConfig->frsky_vfas_precision = 0;
343 telemetryConfig->frsky_vfas_cell_voltage = 0;
344 telemetryConfig->hottAlarmSoundInterval = 5;
346 #endif
348 void resetBatteryConfig(batteryConfig_t *batteryConfig)
350 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
351 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
352 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
353 batteryConfig->vbatmaxcellvoltage = 43;
354 batteryConfig->vbatmincellvoltage = 33;
355 batteryConfig->vbatwarningcellvoltage = 35;
356 batteryConfig->vbathysteresis = 1;
357 batteryConfig->currentMeterOffset = 0;
358 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
359 batteryConfig->batteryCapacity = 0;
360 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
363 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
364 #define FIRST_PORT_INDEX 1
365 #define SECOND_PORT_INDEX 0
366 #else
367 #define FIRST_PORT_INDEX 0
368 #define SECOND_PORT_INDEX 1
369 #endif
371 void resetSerialConfig(serialConfig_t *serialConfig)
373 uint8_t index;
374 memset(serialConfig, 0, sizeof(serialConfig_t));
376 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
377 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
378 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
379 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
380 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
381 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
384 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
386 #if defined(USE_VCP)
387 // This allows MSP connection via USART & VCP so the board can be reconfigured.
388 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
389 #endif
391 serialConfig->reboot_character = 'R';
394 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
396 rcControlsConfig->deadband = 0;
397 rcControlsConfig->yaw_deadband = 0;
398 rcControlsConfig->alt_hold_deadband = 40;
399 rcControlsConfig->alt_hold_fast_change = 1;
402 void resetMixerConfig(mixerConfig_t *mixerConfig)
404 mixerConfig->yaw_motor_direction = 1;
405 #ifdef USE_SERVOS
406 mixerConfig->tri_unarmed_servo = 1;
407 mixerConfig->servo_lowpass_freq = 400;
408 mixerConfig->servo_lowpass_enable = 0;
409 #endif
412 uint8_t getCurrentProfile(void)
414 return masterConfig.current_profile_index;
417 static void setProfile(uint8_t profileIndex)
419 currentProfile = &masterConfig.profile[profileIndex];
420 currentControlRateProfileIndex = currentProfile->activeRateProfile;
421 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
424 uint8_t getCurrentControlRateProfile(void)
426 return currentControlRateProfileIndex;
429 static void setControlRateProfile(uint8_t profileIndex)
431 currentControlRateProfileIndex = profileIndex;
432 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
433 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
436 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
438 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
441 uint16_t getCurrentMinthrottle(void)
443 return masterConfig.escAndServoConfig.minthrottle;
446 static void intFeatureClearAll(master_t *config);
447 static void intFeatureSet(uint32_t mask, master_t *config);
448 static void intFeatureClear(uint32_t mask, master_t *config);
450 // Default settings
451 void createDefaultConfig(master_t *config)
453 // Clear all configuration
454 memset(config, 0, sizeof(master_t));
456 intFeatureClearAll(config);
457 intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , config);
458 #ifdef DEFAULT_FEATURES
459 intFeatureSet(DEFAULT_FEATURES, config);
460 #endif
462 #ifdef OSD
463 intFeatureSet(FEATURE_OSD, config);
464 resetOsdConfig(&config->osdProfile);
465 #endif
467 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
468 // only enable the VBAT feature by default if the board has a voltage divider otherwise
469 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
470 intFeatureSet(FEATURE_VBAT, config);
471 #endif
473 config->version = EEPROM_CONF_VERSION;
474 config->mixerMode = MIXER_QUADX;
476 // global settings
477 config->current_profile_index = 0; // default profile
478 config->dcm_kp = 2500; // 1.0 * 10000
479 config->dcm_ki = 0; // 0.003 * 10000
480 config->gyro_lpf = 0; // 256HZ default
481 #ifdef STM32F10X
482 config->gyro_sync_denom = 8;
483 config->pid_process_denom = 1;
484 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500)
485 config->gyro_sync_denom = 1;
486 config->pid_process_denom = 4;
487 #else
488 config->gyro_sync_denom = 4;
489 config->pid_process_denom = 2;
490 #endif
491 config->gyro_soft_type = FILTER_PT1;
492 config->gyro_soft_lpf_hz = 90;
493 config->gyro_soft_notch_hz_1 = 400;
494 config->gyro_soft_notch_cutoff_1 = 300;
495 config->gyro_soft_notch_hz_2 = 200;
496 config->gyro_soft_notch_cutoff_2 = 100;
498 config->debug_mode = DEBUG_NONE;
500 resetAccelerometerTrims(&config->accZero);
502 resetSensorAlignment(&config->sensorAlignmentConfig);
504 config->boardAlignment.rollDegrees = 0;
505 config->boardAlignment.pitchDegrees = 0;
506 config->boardAlignment.yawDegrees = 0;
507 config->acc_hardware = ACC_DEFAULT; // default/autodetect
508 config->max_angle_inclination = 700; // 70 degrees
509 config->yaw_control_direction = 1;
510 config->gyroConfig.gyroMovementCalibrationThreshold = 32;
512 // xxx_hardware: 0:default/autodetect, 1: disable
513 config->mag_hardware = 1;
515 config->baro_hardware = 1;
517 resetBatteryConfig(&config->batteryConfig);
519 #ifdef TELEMETRY
520 resetTelemetryConfig(&config->telemetryConfig);
521 #endif
523 #ifdef SERIALRX_PROVIDER
524 config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
525 #else
526 config->rxConfig.serialrx_provider = 0;
527 #endif
528 config->rxConfig.sbus_inversion = 1;
529 config->rxConfig.spektrum_sat_bind = 0;
530 config->rxConfig.spektrum_sat_bind_autoreset = 1;
531 config->rxConfig.midrc = 1500;
532 config->rxConfig.mincheck = 1100;
533 config->rxConfig.maxcheck = 1900;
534 config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
535 config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
537 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
538 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
539 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
540 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
543 config->rxConfig.rssi_channel = 0;
544 config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
545 config->rxConfig.rssi_ppm_invert = 0;
546 config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
547 config->rxConfig.rcInterpolationInterval = 19;
548 config->rxConfig.fpvCamAngleDegrees = 0;
549 config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
550 config->rxConfig.airModeActivateThreshold = 1350;
552 resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
554 config->inputFilteringMode = INPUT_FILTERING_DISABLED;
556 config->gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
557 config->disarm_kill_switch = 1;
558 config->auto_disarm_delay = 5;
559 config->small_angle = 25;
561 resetMixerConfig(&config->mixerConfig);
563 config->airplaneConfig.fixedwing_althold_dir = 1;
565 // Motor/ESC/Servo
566 resetEscAndServoConfig(&config->escAndServoConfig);
567 resetFlight3DConfig(&config->flight3DConfig);
569 #ifdef BRUSHED_MOTORS
570 config->motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
571 config->motor_pwm_protocol = PWM_TYPE_BRUSHED;
572 config->use_unsyncedPwm = true;
573 #else
574 config->motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
575 config->motor_pwm_protocol = PWM_TYPE_ONESHOT125;
576 #endif
578 config->servo_pwm_rate = 50;
580 #ifdef CC3D
581 config->use_buzzer_p6 = 0;
582 #endif
584 #ifdef GPS
585 // gps/nav stuff
586 config->gpsConfig.provider = GPS_NMEA;
587 config->gpsConfig.sbasMode = SBAS_AUTO;
588 config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
589 config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
590 #endif
592 resetSerialConfig(&config->serialConfig);
594 resetProfile(&config->profile[0]);
596 resetRollAndPitchTrims(&config->accelerometerTrims);
598 config->mag_declination = 0;
599 config->acc_lpf_hz = 10.0f;
600 config->accDeadband.xy = 40;
601 config->accDeadband.z = 40;
602 config->acc_unarmedcal = 1;
604 #ifdef BARO
605 resetBarometerConfig(&config->barometerConfig);
606 #endif
608 // Radio
609 #ifdef RX_CHANNELS_TAER
610 parseRcChannels("TAER1234", &config->rxConfig);
611 #else
612 parseRcChannels("AETR1234", &config->rxConfig);
613 #endif
615 resetRcControlsConfig(&config->rcControlsConfig);
617 config->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
618 config->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
620 // Failsafe Variables
621 config->failsafeConfig.failsafe_delay = 10; // 1sec
622 config->failsafeConfig.failsafe_off_delay = 10; // 1sec
623 config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
624 config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
625 config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
626 config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
628 #ifdef USE_SERVOS
629 // servos
630 for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
631 config->servoConf[i].min = DEFAULT_SERVO_MIN;
632 config->servoConf[i].max = DEFAULT_SERVO_MAX;
633 config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
634 config->servoConf[i].rate = 100;
635 config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
636 config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
637 config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
640 // gimbal
641 config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
642 #endif
644 #ifdef GPS
645 resetGpsProfile(&config->gpsProfile);
646 #endif
648 // custom mixer. clear by defaults.
649 for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
650 config->customMotorMixer[i].throttle = 0.0f;
653 #ifdef LED_STRIP
654 applyDefaultColors(config->colors);
655 applyDefaultLedStripConfig(config->ledConfigs);
656 applyDefaultModeColors(config->modeColors);
657 applyDefaultSpecialColors(&(config->specialColors));
658 config->ledstrip_visual_beeper = 0;
659 #endif
661 #ifdef VTX
662 config->vtx_band = 4; //Fatshark/Airwaves
663 config->vtx_channel = 1; //CH1
664 config->vtx_mode = 0; //CH+BAND mode
665 config->vtx_mhz = 5740; //F0
666 #endif
668 #ifdef TRANSPONDER
669 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
671 memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
672 #endif
674 #ifdef BLACKBOX
675 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
676 intFeatureSet(FEATURE_BLACKBOX, config);
677 config->blackbox_device = BLACKBOX_DEVICE_FLASH;
678 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
679 intFeatureSet(FEATURE_BLACKBOX, config);
680 config->blackbox_device = BLACKBOX_DEVICE_SDCARD;
681 #else
682 config->blackbox_device = BLACKBOX_DEVICE_SERIAL;
683 #endif
685 config->blackbox_rate_num = 1;
686 config->blackbox_rate_denom = 1;
687 config->blackbox_on_motor_test = 0; // default off
688 #endif // BLACKBOX
690 #ifdef SERIALRX_UART
691 if (featureConfigured(FEATURE_RX_SERIAL)) {
692 config->serialConfig.portConfigs[SERIALRX_UART].functionMask = FUNCTION_RX_SERIAL;
694 #endif
696 #if defined(TARGET_CONFIG)
697 targetConfiguration(config);
698 #endif
701 // copy first profile into remaining profile
702 for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
703 memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
707 static void resetConf(void)
709 createDefaultConfig(&masterConfig);
711 setProfile(0);
713 #ifdef LED_STRIP
714 reevaluateLedConfig();
715 #endif
718 static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
720 uint8_t checksum = 0;
721 const uint8_t *byteOffset;
723 for (byteOffset = data; byteOffset < (data + length); byteOffset++)
724 checksum ^= *byteOffset;
725 return checksum;
728 static bool isEEPROMContentValid(void)
730 const master_t *temp = (const master_t *) CONFIG_START_FLASH_ADDRESS;
731 uint8_t checksum = 0;
733 // check version number
734 if (EEPROM_CONF_VERSION != temp->version)
735 return false;
737 // check size and magic numbers
738 if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
739 return false;
741 // verify integrity of temporary copy
742 checksum = calculateChecksum((const uint8_t *) temp, sizeof(master_t));
743 if (checksum != 0)
744 return false;
746 // looks good, let's roll!
747 return true;
750 void activateControlRateConfig(void)
752 generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig);
755 void activateConfig(void)
757 static imuRuntimeConfig_t imuRuntimeConfig;
759 activateControlRateConfig();
761 resetAdjustmentStates();
763 useRcControlsConfig(
764 masterConfig.modeActivationConditions,
765 &masterConfig.escAndServoConfig,
766 &currentProfile->pidProfile
769 // Prevent invalid notch cutoff
770 if (masterConfig.gyro_soft_notch_cutoff_1 >= masterConfig.gyro_soft_notch_hz_1)
771 masterConfig.gyro_soft_notch_hz_1 = 0;
773 if (masterConfig.gyro_soft_notch_cutoff_2 >= masterConfig.gyro_soft_notch_hz_2)
774 masterConfig.gyro_soft_notch_hz_2 = 0;
776 gyroUseConfig(&masterConfig.gyroConfig,
777 masterConfig.gyro_soft_lpf_hz,
778 masterConfig.gyro_soft_notch_hz_1,
779 masterConfig.gyro_soft_notch_cutoff_1,
780 masterConfig.gyro_soft_notch_hz_2,
781 masterConfig.gyro_soft_notch_cutoff_2,
782 masterConfig.gyro_soft_type);
784 #ifdef TELEMETRY
785 telemetryUseConfig(&masterConfig.telemetryConfig);
786 #endif
787 pidSetController(currentProfile->pidProfile.pidController);
789 #ifdef GPS
790 gpsUseProfile(&masterConfig.gpsProfile);
791 gpsUsePIDs(&currentProfile->pidProfile);
792 #endif
794 useFailsafeConfig(&masterConfig.failsafeConfig);
795 setAccelerationTrims(&masterConfig.accZero);
796 setAccelerationFilter(masterConfig.acc_lpf_hz);
798 mixerUseConfigs(
799 #ifdef USE_SERVOS
800 masterConfig.servoConf,
801 &masterConfig.gimbalConfig,
802 #endif
803 &masterConfig.flight3DConfig,
804 &masterConfig.escAndServoConfig,
805 &masterConfig.mixerConfig,
806 &masterConfig.airplaneConfig,
807 &masterConfig.rxConfig
810 imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
811 imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
812 imuRuntimeConfig.acc_unarmedcal = masterConfig.acc_unarmedcal;
813 imuRuntimeConfig.small_angle = masterConfig.small_angle;
815 imuConfigure(
816 &imuRuntimeConfig,
817 &currentProfile->pidProfile,
818 &masterConfig.accDeadband,
819 masterConfig.throttle_correction_angle
822 configureAltitudeHold(
823 &currentProfile->pidProfile,
824 &masterConfig.barometerConfig,
825 &masterConfig.rcControlsConfig,
826 &masterConfig.escAndServoConfig
829 #ifdef BARO
830 useBarometerConfig(&masterConfig.barometerConfig);
831 #endif
834 void validateAndFixConfig(void)
836 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
837 featureSet(DEFAULT_RX_FEATURE);
840 if (featureConfigured(FEATURE_RX_PPM)) {
841 featureClear(FEATURE_RX_PARALLEL_PWM);
844 if (featureConfigured(FEATURE_RX_MSP)) {
845 featureClear(FEATURE_RX_SERIAL);
846 featureClear(FEATURE_RX_PARALLEL_PWM);
847 featureClear(FEATURE_RX_PPM);
850 if (featureConfigured(FEATURE_RX_SERIAL)) {
851 featureClear(FEATURE_RX_PARALLEL_PWM);
852 featureClear(FEATURE_RX_PPM);
855 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
856 #if defined(STM32F10X)
857 // rssi adc needs the same ports
858 featureClear(FEATURE_RSSI_ADC);
859 // current meter needs the same ports
860 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
861 featureClear(FEATURE_CURRENT_METER);
863 #endif
865 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
866 // led strip needs the same ports
867 featureClear(FEATURE_LED_STRIP);
868 #endif
870 // software serial needs free PWM ports
871 featureClear(FEATURE_SOFTSERIAL);
875 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
876 if (featureConfigured(FEATURE_SOFTSERIAL) && (
878 #ifdef USE_SOFTSERIAL1
879 || (WS2811_TIMER == SOFTSERIAL_1_TIMER)
880 #endif
881 #ifdef USE_SOFTSERIAL2
882 || (WS2811_TIMER == SOFTSERIAL_2_TIMER)
883 #endif
884 )) {
885 // led strip needs the same timer as softserial
886 featureClear(FEATURE_LED_STRIP);
888 #endif
890 #if defined(NAZE) && defined(SONAR)
891 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
892 featureClear(FEATURE_CURRENT_METER);
894 #endif
896 #if defined(OLIMEXINO) && defined(SONAR)
897 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
898 featureClear(FEATURE_CURRENT_METER);
900 #endif
902 #if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
903 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
904 featureClear(FEATURE_DISPLAY);
906 #endif
908 /*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
909 if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
910 featureClear(FEATURE_LED_STRIP);
912 #endif
915 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
916 // shared pin
917 if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
918 featureClear(FEATURE_SONAR);
919 featureClear(FEATURE_SOFTSERIAL);
920 featureClear(FEATURE_RSSI_ADC);
922 #endif
924 #if defined(COLIBRI_RACE)
925 masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
926 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
927 featureClear(FEATURE_RX_PARALLEL_PWM);
928 featureClear(FEATURE_RX_MSP);
929 featureSet(FEATURE_RX_PPM);
931 #endif
933 useRxConfig(&masterConfig.rxConfig);
935 serialConfig_t *serialConfig = &masterConfig.serialConfig;
937 if (!isSerialConfigValid(serialConfig)) {
938 resetSerialConfig(serialConfig);
942 void initEEPROM(void)
946 void readEEPROM(void)
948 // Sanity check
949 if (!isEEPROMContentValid())
950 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
952 suspendRxSignal();
954 // Read flash
955 memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
957 if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) // sanity check
958 masterConfig.current_profile_index = 0;
960 setProfile(masterConfig.current_profile_index);
962 validateAndFixConfig();
963 activateConfig();
965 resumeRxSignal();
968 void readEEPROMAndNotify(void)
970 // re-read written data
971 readEEPROM();
972 beeperConfirmationBeeps(1);
975 void writeEEPROM(void)
977 // Generate compile time error if the config does not fit in the reserved area of flash.
978 BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
980 FLASH_Status status = 0;
981 uint32_t wordOffset;
982 int8_t attemptsRemaining = 3;
984 suspendRxSignal();
986 // prepare checksum/version constants
987 masterConfig.version = EEPROM_CONF_VERSION;
988 masterConfig.size = sizeof(master_t);
989 masterConfig.magic_be = 0xBE;
990 masterConfig.magic_ef = 0xEF;
991 masterConfig.chk = 0; // erase checksum before recalculating
992 masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
994 // write it
995 FLASH_Unlock();
996 while (attemptsRemaining--) {
997 #if defined(STM32F4)
998 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_OPERR | FLASH_FLAG_WRPERR | FLASH_FLAG_PGAERR | FLASH_FLAG_PGPERR | FLASH_FLAG_PGSERR);
999 #elif defined(STM32F303)
1000 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
1001 #elif defined(STM32F10X)
1002 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
1003 #endif
1004 for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
1005 if (wordOffset % FLASH_PAGE_SIZE == 0) {
1006 #if defined(STM32F40_41xxx)
1007 status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000
1008 #elif defined (STM32F411xE)
1009 status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000
1010 #else
1011 status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
1012 #endif
1013 if (status != FLASH_COMPLETE) {
1014 break;
1018 status = FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS + wordOffset,
1019 *(uint32_t *) ((char *) &masterConfig + wordOffset));
1020 if (status != FLASH_COMPLETE) {
1021 break;
1024 if (status == FLASH_COMPLETE) {
1025 break;
1028 FLASH_Lock();
1030 // Flash write failed - just die now
1031 if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
1032 failureMode(FAILURE_FLASH_WRITE_FAILED);
1035 resumeRxSignal();
1038 void ensureEEPROMContainsValidData(void)
1040 if (isEEPROMContentValid()) {
1041 return;
1044 resetEEPROM();
1047 void resetEEPROM(void)
1049 resetConf();
1050 writeEEPROM();
1053 void saveConfigAndNotify(void)
1055 writeEEPROM();
1056 readEEPROMAndNotify();
1059 void changeProfile(uint8_t profileIndex)
1061 masterConfig.current_profile_index = profileIndex;
1062 writeEEPROM();
1063 readEEPROM();
1064 beeperConfirmationBeeps(profileIndex + 1);
1067 void changeControlRateProfile(uint8_t profileIndex)
1069 if (profileIndex > MAX_RATEPROFILES) {
1070 profileIndex = MAX_RATEPROFILES - 1;
1072 setControlRateProfile(profileIndex);
1073 activateControlRateConfig();
1076 void latchActiveFeatures()
1078 activeFeaturesLatch = masterConfig.enabledFeatures;
1081 bool featureConfigured(uint32_t mask)
1083 return masterConfig.enabledFeatures & mask;
1086 bool feature(uint32_t mask)
1088 return activeFeaturesLatch & mask;
1091 void featureSet(uint32_t mask)
1093 intFeatureSet(mask, &masterConfig);
1096 static void intFeatureSet(uint32_t mask, master_t *config)
1098 config->enabledFeatures |= mask;
1101 void featureClear(uint32_t mask)
1103 intFeatureClear(mask, &masterConfig);
1106 static void intFeatureClear(uint32_t mask, master_t *config)
1108 config->enabledFeatures &= ~(mask);
1111 void featureClearAll()
1113 intFeatureClearAll(&masterConfig);
1116 static void intFeatureClearAll(master_t *config)
1118 config->enabledFeatures = 0;
1121 uint32_t featureMask(void)
1123 return masterConfig.enabledFeatures;
1126 void beeperOffSet(uint32_t mask)
1128 masterConfig.beeper_off_flags |= mask;
1131 void beeperOffSetAll(uint8_t beeperCount)
1133 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1136 void beeperOffClear(uint32_t mask)
1138 masterConfig.beeper_off_flags &= ~(mask);
1141 void beeperOffClearAll(void)
1143 masterConfig.beeper_off_flags = 0;
1146 uint32_t getBeeperOffMask(void)
1148 return masterConfig.beeper_off_flags;
1151 void setBeeperOffMask(uint32_t mask)
1153 masterConfig.beeper_off_flags = mask;
1156 uint32_t getPreferredBeeperOffMask(void)
1158 return masterConfig.preferred_beeper_off_flags;
1161 void setPreferredBeeperOffMask(uint32_t mask)
1163 masterConfig.preferred_beeper_off_flags = mask;