Merge pull request #1702 from martinbudden/bf_imuconfig_in_structs
[betaflight.git] / src / main / fc / config.c
blob9e93c15ec18efc8da22f0271e1f1ade19de63b64
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"
24 #include "build/build_config.h"
25 #include "build/debug.h"
27 #include "blackbox/blackbox_io.h"
29 #include "cms/cms.h"
31 #include "common/color.h"
32 #include "common/axis.h"
33 #include "common/maths.h"
34 #include "common/filter.h"
36 #include "drivers/sensor.h"
37 #include "drivers/accgyro.h"
38 #include "drivers/compass.h"
39 #include "drivers/system.h"
40 #include "drivers/timer.h"
41 #include "drivers/pwm_rx.h"
42 #include "drivers/rx_spi.h"
43 #include "drivers/serial.h"
44 #include "drivers/pwm_output.h"
45 #include "drivers/vcd.h"
46 #include "drivers/max7456.h"
47 #include "drivers/sound_beeper.h"
48 #include "drivers/light_ws2811strip.h"
49 #include "drivers/sdcard.h"
51 #include "fc/config.h"
52 #include "fc/rc_controls.h"
53 #include "fc/rc_curves.h"
54 #include "fc/runtime_config.h"
56 #include "sensors/sensors.h"
57 #include "sensors/gyro.h"
58 #include "sensors/compass.h"
59 #include "sensors/acceleration.h"
60 #include "sensors/barometer.h"
61 #include "sensors/battery.h"
62 #include "sensors/boardalignment.h"
64 #include "io/beeper.h"
65 #include "io/serial.h"
66 #include "io/gimbal.h"
67 #include "io/motors.h"
68 #include "io/servos.h"
69 #include "io/ledstrip.h"
70 #include "io/gps.h"
71 #include "io/osd.h"
72 #include "io/vtx.h"
74 #include "rx/rx.h"
75 #include "rx/rx_spi.h"
77 #include "telemetry/telemetry.h"
79 #include "flight/mixer.h"
80 #include "flight/servos.h"
81 #include "flight/pid.h"
82 #include "flight/imu.h"
83 #include "flight/failsafe.h"
84 #include "flight/altitudehold.h"
85 #include "flight/navigation.h"
87 #include "config/config_eeprom.h"
88 #include "config/config_profile.h"
89 #include "config/config_master.h"
90 #include "config/feature.h"
92 #ifndef DEFAULT_RX_FEATURE
93 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
94 #endif
95 #ifndef RX_SPI_DEFAULT_PROTOCOL
96 #define RX_SPI_DEFAULT_PROTOCOL 0
97 #endif
99 #define BRUSHED_MOTORS_PWM_RATE 16000
100 #ifdef STM32F4
101 #define BRUSHLESS_MOTORS_PWM_RATE 2000
102 #else
103 #define BRUSHLESS_MOTORS_PWM_RATE 400
104 #endif
106 master_t masterConfig; // master config struct with data independent from profiles
107 profile_t *currentProfile;
109 static uint8_t currentControlRateProfileIndex = 0;
110 controlRateConfig_t *currentControlRateProfile;
112 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
114 accelerometerTrims->values.pitch = 0;
115 accelerometerTrims->values.roll = 0;
116 accelerometerTrims->values.yaw = 0;
119 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
121 controlRateConfig->rcRate8 = 100;
122 controlRateConfig->rcYawRate8 = 100;
123 controlRateConfig->rcExpo8 = 0;
124 controlRateConfig->thrMid8 = 50;
125 controlRateConfig->thrExpo8 = 0;
126 controlRateConfig->dynThrPID = 10;
127 controlRateConfig->rcYawExpo8 = 0;
128 controlRateConfig->tpa_breakpoint = 1650;
130 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
131 controlRateConfig->rates[axis] = 70;
135 static void resetPidProfile(pidProfile_t *pidProfile)
137 pidProfile->P8[ROLL] = 43;
138 pidProfile->I8[ROLL] = 40;
139 pidProfile->D8[ROLL] = 20;
140 pidProfile->P8[PITCH] = 58;
141 pidProfile->I8[PITCH] = 50;
142 pidProfile->D8[PITCH] = 22;
143 pidProfile->P8[YAW] = 70;
144 pidProfile->I8[YAW] = 45;
145 pidProfile->D8[YAW] = 20;
146 pidProfile->P8[PIDALT] = 50;
147 pidProfile->I8[PIDALT] = 0;
148 pidProfile->D8[PIDALT] = 0;
149 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
150 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
151 pidProfile->D8[PIDPOS] = 0;
152 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
153 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
154 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
155 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
156 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
157 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
158 pidProfile->P8[PIDLEVEL] = 50;
159 pidProfile->I8[PIDLEVEL] = 50;
160 pidProfile->D8[PIDLEVEL] = 100;
161 pidProfile->P8[PIDMAG] = 40;
162 pidProfile->P8[PIDVEL] = 55;
163 pidProfile->I8[PIDVEL] = 55;
164 pidProfile->D8[PIDVEL] = 75;
166 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
167 pidProfile->pidSumLimit = PIDSUM_LIMIT;
168 pidProfile->yaw_lpf_hz = 0;
169 pidProfile->rollPitchItermIgnoreRate = 130;
170 pidProfile->yawItermIgnoreRate = 32;
171 pidProfile->dterm_filter_type = FILTER_BIQUAD;
172 pidProfile->dterm_lpf_hz = 100; // filtering ON by default
173 pidProfile->dterm_notch_hz = 260;
174 pidProfile->dterm_notch_cutoff = 160;
175 pidProfile->vbatPidCompensation = 0;
176 pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
178 // Betaflight PID controller parameters
179 pidProfile->setpointRelaxRatio = 30;
180 pidProfile->dtermSetpointWeight = 200;
181 pidProfile->yawRateAccelLimit = 220;
182 pidProfile->rateAccelLimit = 0;
183 pidProfile->itermThrottleGain = 0;
184 pidProfile->levelSensitivity = 2.0f;
186 #ifdef GTUNE
187 pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
188 pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
189 pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
190 pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
191 pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
192 pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
193 pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
194 pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
195 pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
196 #endif
199 void resetProfile(profile_t *profile)
201 resetPidProfile(&profile->pidProfile);
203 for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
204 resetControlRateConfig(&profile->controlRateProfile[rI]);
207 profile->activeRateProfile = 0;
210 #ifdef GPS
211 void resetGpsProfile(gpsProfile_t *gpsProfile)
213 gpsProfile->gps_wp_radius = 200;
214 gpsProfile->gps_lpf = 20;
215 gpsProfile->nav_slew_rate = 30;
216 gpsProfile->nav_controls_heading = 1;
217 gpsProfile->nav_speed_min = 100;
218 gpsProfile->nav_speed_max = 300;
219 gpsProfile->ap_mode = 40;
221 #endif
223 #ifdef BARO
224 void resetBarometerConfig(barometerConfig_t *barometerConfig)
226 barometerConfig->baro_sample_count = 21;
227 barometerConfig->baro_noise_lpf = 0.6f;
228 barometerConfig->baro_cf_vel = 0.985f;
229 barometerConfig->baro_cf_alt = 0.965f;
231 #endif
233 void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
235 sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
236 sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
237 sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
240 #ifdef LED_STRIP
241 void resetLedStripConfig(ledStripConfig_t *ledStripConfig)
243 applyDefaultColors(ledStripConfig->colors);
244 applyDefaultLedStripConfig(ledStripConfig->ledConfigs);
245 applyDefaultModeColors(ledStripConfig->modeColors);
246 applyDefaultSpecialColors(&(ledStripConfig->specialColors));
247 ledStripConfig->ledstrip_visual_beeper = 0;
248 ledStripConfig->ledstrip_aux_channel = THROTTLE;
250 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
251 if (timerHardware[i].usageFlags & TIM_USE_LED) {
252 ledStripConfig->ioTag = timerHardware[i].tag;
253 return;
256 ledStripConfig->ioTag = IO_TAG_NONE;
258 #endif
260 #ifdef USE_SERVOS
261 void resetServoConfig(servoConfig_t *servoConfig)
263 servoConfig->servoCenterPulse = 1500;
264 servoConfig->servoPwmRate = 50;
266 int servoIndex = 0;
267 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) {
268 if (timerHardware[i].usageFlags & TIM_USE_SERVO) {
269 servoConfig->ioTags[servoIndex] = timerHardware[i].tag;
270 servoIndex++;
274 #endif
276 void resetMotorConfig(motorConfig_t *motorConfig)
278 #ifdef BRUSHED_MOTORS
279 motorConfig->minthrottle = 1000;
280 motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
281 motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
282 motorConfig->useUnsyncedPwm = true;
283 #else
284 motorConfig->minthrottle = 1070;
285 motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
286 motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
287 #endif
288 motorConfig->maxthrottle = 2000;
289 motorConfig->mincommand = 1000;
290 motorConfig->digitalIdleOffsetPercent = 3.0f;
292 int motorIndex = 0;
293 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
294 if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
295 motorConfig->ioTags[motorIndex] = timerHardware[i].tag;
296 motorIndex++;
301 #ifdef SONAR
302 void resetSonarConfig(sonarConfig_t *sonarConfig)
304 #if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
305 sonarConfig->triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
306 sonarConfig->echoTag = IO_TAG(SONAR_ECHO_PIN);
307 #else
308 #error Sonar not defined for target
309 #endif
311 #endif
313 #ifdef USE_SDCARD
314 void resetsdcardConfig(sdcardConfig_t *sdcardConfig)
316 #if defined(SDCARD_DMA_CHANNEL_TX)
317 sdcardConfig->useDma = true;
318 #else
319 sdcardConfig->useDma = false;
320 #endif
322 #endif
324 #ifdef USE_ADC
325 void resetAdcConfig(adcConfig_t *adcConfig)
327 #ifdef VBAT_ADC_PIN
328 adcConfig->vbat.enabled = true;
329 adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
330 #endif
332 #ifdef EXTERNAL1_ADC_PIN
333 adcConfig->external1.enabled = true;
334 adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
335 #endif
337 #ifdef CURRENT_METER_ADC_PIN
338 adcConfig->currentMeter.enabled = true;
339 adcConfig->currentMeter.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
340 #endif
342 #ifdef RSSI_ADC_PIN
343 adcConfig->rssi.enabled = true;
344 adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
345 #endif
348 #endif
351 #ifdef BEEPER
352 void resetBeeperConfig(beeperConfig_t *beeperConfig)
354 #ifdef BEEPER_INVERTED
355 beeperConfig->isOpenDrain = false;
356 beeperConfig->isInverted = true;
357 #else
358 beeperConfig->isOpenDrain = true;
359 beeperConfig->isInverted = false;
360 #endif
361 beeperConfig->ioTag = IO_TAG(BEEPER);
363 #endif
365 #if defined(USE_PWM) || defined(USE_PPM)
366 void resetPpmConfig(ppmConfig_t *ppmConfig)
368 #ifdef PPM_PIN
369 ppmConfig->ioTag = IO_TAG(PPM_PIN);
370 #else
371 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
372 if (timerHardware[i].usageFlags & TIM_USE_PPM) {
373 ppmConfig->ioTag = timerHardware[i].tag;
374 return;
378 ppmConfig->ioTag = IO_TAG_NONE;
379 #endif
382 void resetPwmConfig(pwmConfig_t *pwmConfig)
384 int inputIndex = 0;
385 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
386 if (timerHardware[i].usageFlags & TIM_USE_PWM) {
387 pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
388 inputIndex++;
392 #endif
394 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
396 flight3DConfig->deadband3d_low = 1406;
397 flight3DConfig->deadband3d_high = 1514;
398 flight3DConfig->neutral3d = 1460;
399 flight3DConfig->deadband3d_throttle = 50;
402 #ifdef TELEMETRY
403 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
405 telemetryConfig->telemetry_inversion = 1;
406 telemetryConfig->telemetry_switch = 0;
407 telemetryConfig->gpsNoFixLatitude = 0;
408 telemetryConfig->gpsNoFixLongitude = 0;
409 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
410 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
411 telemetryConfig->frsky_vfas_precision = 0;
412 telemetryConfig->frsky_vfas_cell_voltage = 0;
413 telemetryConfig->hottAlarmSoundInterval = 5;
414 telemetryConfig->pidValuesAsTelemetry = 0;
416 #endif
418 void resetBatteryConfig(batteryConfig_t *batteryConfig)
420 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
421 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
422 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
423 batteryConfig->vbatmaxcellvoltage = 43;
424 batteryConfig->vbatmincellvoltage = 33;
425 batteryConfig->vbatwarningcellvoltage = 35;
426 batteryConfig->vbathysteresis = 1;
427 batteryConfig->batteryMeterType = BATTERY_SENSOR_ADC;
428 batteryConfig->currentMeterOffset = 0;
429 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
430 batteryConfig->batteryCapacity = 0;
431 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
432 batteryConfig->batterynotpresentlevel = 55; // VBAT below 5.5 V will be igonored
433 batteryConfig->useVBatAlerts = true;
434 batteryConfig->useConsumptionAlerts = false;
435 batteryConfig->consumptionWarningPercentage = 10;
438 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
439 #define FIRST_PORT_INDEX 1
440 #define SECOND_PORT_INDEX 0
441 #else
442 #define FIRST_PORT_INDEX 0
443 #define SECOND_PORT_INDEX 1
444 #endif
446 void resetSerialConfig(serialConfig_t *serialConfig)
448 uint8_t index;
449 memset(serialConfig, 0, sizeof(serialConfig_t));
451 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
452 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
453 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
454 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
455 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
456 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
459 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
461 #if defined(USE_VCP)
462 // This allows MSP connection via USART & VCP so the board can be reconfigured.
463 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
464 #endif
466 serialConfig->reboot_character = 'R';
469 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
471 rcControlsConfig->deadband = 0;
472 rcControlsConfig->yaw_deadband = 0;
473 rcControlsConfig->alt_hold_deadband = 40;
474 rcControlsConfig->alt_hold_fast_change = 1;
477 void resetMixerConfig(mixerConfig_t *mixerConfig)
479 mixerConfig->yaw_motor_direction = 1;
482 #ifdef USE_SERVOS
483 void resetServoMixerConfig(servoMixerConfig_t *servoMixerConfig)
485 servoMixerConfig->tri_unarmed_servo = 1;
486 servoMixerConfig->servo_lowpass_freq = 400;
487 servoMixerConfig->servo_lowpass_enable = 0;
489 #endif
491 #ifdef USE_MAX7456
492 void resetMax7456Config(vcdProfile_t *pVcdProfile)
494 pVcdProfile->video_system = VIDEO_SYSTEM_AUTO;
495 pVcdProfile->h_offset = 0;
496 pVcdProfile->v_offset = 0;
498 #endif
500 uint8_t getCurrentProfile(void)
502 return masterConfig.current_profile_index;
505 void setProfile(uint8_t profileIndex)
507 currentProfile = &masterConfig.profile[profileIndex];
508 currentControlRateProfileIndex = currentProfile->activeRateProfile;
509 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
512 uint8_t getCurrentControlRateProfile(void)
514 return currentControlRateProfileIndex;
517 static void setControlRateProfile(uint8_t profileIndex)
519 currentControlRateProfileIndex = profileIndex;
520 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
521 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
524 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
526 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
529 uint16_t getCurrentMinthrottle(void)
531 return masterConfig.motorConfig.minthrottle;
535 void createDefaultConfig(master_t *config)
537 // Clear all configuration
538 memset(config, 0, sizeof(master_t));
540 uint32_t *featuresPtr = &config->enabledFeatures;
542 intFeatureClearAll(featuresPtr);
543 intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
544 #ifdef DEFAULT_FEATURES
545 intFeatureSet(DEFAULT_FEATURES, featuresPtr);
546 #endif
548 #ifdef USE_MAX7456
549 resetMax7456Config(&config->vcdProfile);
550 #endif
552 #ifdef OSD
553 intFeatureSet(FEATURE_OSD, featuresPtr);
554 osdResetConfig(&config->osdProfile);
555 #endif
557 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
558 // only enable the VBAT feature by default if the board has a voltage divider otherwise
559 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
560 intFeatureSet(FEATURE_VBAT, featuresPtr);
561 #endif
563 config->version = EEPROM_CONF_VERSION;
564 config->mixerConfig.mixerMode = MIXER_QUADX;
566 // global settings
567 config->current_profile_index = 0; // default profile
568 config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
569 config->imuConfig.dcm_ki = 0; // 0.003 * 10000
570 config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default
571 #ifdef STM32F10X
572 config->gyroConfig.gyro_sync_denom = 8;
573 config->pid_process_denom = 1;
574 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
575 config->gyroConfig.gyro_sync_denom = 1;
576 config->pid_process_denom = 4;
577 #else
578 config->gyroConfig.gyro_sync_denom = 4;
579 config->pid_process_denom = 2;
580 #endif
581 config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
582 config->gyroConfig.gyro_soft_lpf_hz = 90;
583 config->gyroConfig.gyro_soft_notch_hz_1 = 400;
584 config->gyroConfig.gyro_soft_notch_cutoff_1 = 300;
585 config->gyroConfig.gyro_soft_notch_hz_2 = 200;
586 config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
588 config->debug_mode = DEBUG_MODE;
590 resetAccelerometerTrims(&config->sensorTrims.accZero);
592 resetSensorAlignment(&config->sensorAlignmentConfig);
594 config->boardAlignment.rollDegrees = 0;
595 config->boardAlignment.pitchDegrees = 0;
596 config->boardAlignment.yawDegrees = 0;
597 config->sensorSelectionConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
598 config->max_angle_inclination = 700; // 70 degrees
599 config->rcControlsConfig.yaw_control_direction = 1;
600 config->gyroConfig.gyroMovementCalibrationThreshold = 32;
602 // xxx_hardware: 0:default/autodetect, 1: disable
603 config->sensorSelectionConfig.mag_hardware = 1;
605 config->sensorSelectionConfig.baro_hardware = 1;
607 resetBatteryConfig(&config->batteryConfig);
609 #if defined(USE_PWM) || defined(USE_PPM)
610 resetPpmConfig(&config->ppmConfig);
611 resetPwmConfig(&config->pwmConfig);
612 #endif
614 #ifdef TELEMETRY
615 resetTelemetryConfig(&config->telemetryConfig);
616 #endif
618 #ifdef USE_ADC
619 resetAdcConfig(&config->adcConfig);
620 #endif
622 #ifdef BEEPER
623 resetBeeperConfig(&config->beeperConfig);
624 #endif
626 #ifdef SONAR
627 resetSonarConfig(&config->sonarConfig);
628 #endif
630 #ifdef USE_SDCARD
631 intFeatureSet(FEATURE_SDCARD, featuresPtr);
632 resetsdcardConfig(&config->sdcardConfig);
633 #endif
635 #ifdef SERIALRX_PROVIDER
636 config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
637 #else
638 config->rxConfig.serialrx_provider = 0;
639 #endif
640 config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
641 config->rxConfig.sbus_inversion = 1;
642 config->rxConfig.spektrum_sat_bind = 0;
643 config->rxConfig.spektrum_sat_bind_autoreset = 1;
644 config->rxConfig.midrc = 1500;
645 config->rxConfig.mincheck = 1100;
646 config->rxConfig.maxcheck = 1900;
647 config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
648 config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
650 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
651 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
652 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
653 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
656 config->rxConfig.rssi_channel = 0;
657 config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
658 config->rxConfig.rssi_ppm_invert = 0;
659 config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
660 config->rxConfig.rcInterpolationInterval = 19;
661 config->rxConfig.fpvCamAngleDegrees = 0;
662 config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
663 config->rxConfig.airModeActivateThreshold = 1350;
665 resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
667 config->inputFilteringMode = INPUT_FILTERING_DISABLED;
669 config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
670 config->armingConfig.disarm_kill_switch = 1;
671 config->armingConfig.auto_disarm_delay = 5;
672 config->imuConfig.small_angle = 25;
674 config->airplaneConfig.fixedwing_althold_dir = 1;
676 // Motor/ESC/Servo
677 resetMixerConfig(&config->mixerConfig);
678 resetMotorConfig(&config->motorConfig);
679 #ifdef USE_SERVOS
680 resetServoMixerConfig(&config->servoMixerConfig);
681 resetServoConfig(&config->servoConfig);
682 #endif
683 resetFlight3DConfig(&config->flight3DConfig);
685 #ifdef LED_STRIP
686 resetLedStripConfig(&config->ledStripConfig);
687 #endif
689 #ifdef GPS
690 // gps/nav stuff
691 config->gpsConfig.provider = GPS_NMEA;
692 config->gpsConfig.sbasMode = SBAS_AUTO;
693 config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
694 config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
695 #endif
697 resetSerialConfig(&config->serialConfig);
699 resetProfile(&config->profile[0]);
701 resetRollAndPitchTrims(&config->accelerometerTrims);
703 config->compassConfig.mag_declination = 0;
704 config->accelerometerConfig.acc_lpf_hz = 10.0f;
706 config->imuConfig.accDeadband.xy = 40;
707 config->imuConfig.accDeadband.z = 40;
708 config->imuConfig.acc_unarmedcal = 1;
710 #ifdef BARO
711 resetBarometerConfig(&config->barometerConfig);
712 #endif
714 // Radio
715 #ifdef RX_CHANNELS_TAER
716 parseRcChannels("TAER1234", &config->rxConfig);
717 #else
718 parseRcChannels("AETR1234", &config->rxConfig);
719 #endif
721 resetRcControlsConfig(&config->rcControlsConfig);
723 config->throttleCorrectionConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
724 config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
726 // Failsafe Variables
727 config->failsafeConfig.failsafe_delay = 10; // 1sec
728 config->failsafeConfig.failsafe_off_delay = 10; // 1sec
729 config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
730 config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
731 config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
732 config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
734 #ifdef USE_SERVOS
735 // servos
736 for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
737 config->servoConf[i].min = DEFAULT_SERVO_MIN;
738 config->servoConf[i].max = DEFAULT_SERVO_MAX;
739 config->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
740 config->servoConf[i].rate = 100;
741 config->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
742 config->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
743 config->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
746 // gimbal
747 config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
748 #endif
750 #ifdef GPS
751 resetGpsProfile(&config->gpsProfile);
752 #endif
754 // custom mixer. clear by defaults.
755 for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
756 config->customMotorMixer[i].throttle = 0.0f;
759 #ifdef VTX
760 config->vtx_band = 4; //Fatshark/Airwaves
761 config->vtx_channel = 1; //CH1
762 config->vtx_mode = 0; //CH+BAND mode
763 config->vtx_mhz = 5740; //F0
764 #endif
766 #ifdef TRANSPONDER
767 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
769 memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
770 #endif
772 #ifdef BLACKBOX
773 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
774 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
775 config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
776 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
777 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
778 config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
779 #else
780 config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
781 #endif
783 config->blackboxConfig.rate_num = 1;
784 config->blackboxConfig.rate_denom = 1;
785 config->blackboxConfig.on_motor_test = 0; // default off
786 #endif // BLACKBOX
788 #ifdef SERIALRX_UART
789 if (featureConfigured(FEATURE_RX_SERIAL)) {
790 int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART);
791 if (serialIndex >= 0) {
792 config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL;
795 #endif
797 #if defined(TARGET_CONFIG)
798 targetConfiguration(config);
799 #endif
801 // copy first profile into remaining profile
802 for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
803 memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
807 static void resetConf(void)
809 createDefaultConfig(&masterConfig);
811 setProfile(0);
813 #ifdef LED_STRIP
814 reevaluateLedConfig();
815 #endif
818 void activateControlRateConfig(void)
820 generateThrottleCurve(currentControlRateProfile, &masterConfig.motorConfig);
823 void activateConfig(void)
825 activateControlRateConfig();
827 resetAdjustmentStates();
829 useRcControlsConfig(
830 masterConfig.modeActivationConditions,
831 &masterConfig.motorConfig,
832 &currentProfile->pidProfile
835 #ifdef TELEMETRY
836 telemetryUseConfig(&masterConfig.telemetryConfig);
837 #endif
839 #ifdef GPS
840 gpsUseProfile(&masterConfig.gpsProfile);
841 gpsUsePIDs(&currentProfile->pidProfile);
842 #endif
844 useFailsafeConfig(&masterConfig.failsafeConfig);
845 setAccelerationTrims(&masterConfig.sensorTrims.accZero);
846 setAccelerationFilter(masterConfig.accelerometerConfig.acc_lpf_hz);
848 mixerUseConfigs(
849 &masterConfig.flight3DConfig,
850 &masterConfig.motorConfig,
851 &masterConfig.mixerConfig,
852 &masterConfig.airplaneConfig,
853 &masterConfig.rxConfig
856 #ifdef USE_SERVOS
857 servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoConf, &masterConfig.gimbalConfig);
858 #endif
861 imuConfigure(
862 &masterConfig.imuConfig,
863 &currentProfile->pidProfile,
864 masterConfig.throttleCorrectionConfig.throttle_correction_angle
867 configureAltitudeHold(
868 &currentProfile->pidProfile,
869 &masterConfig.barometerConfig,
870 &masterConfig.rcControlsConfig,
871 &masterConfig.motorConfig
874 #ifdef BARO
875 useBarometerConfig(&masterConfig.barometerConfig);
876 #endif
879 void validateAndFixConfig(void)
881 if((masterConfig.motorConfig.motorPwmProtocol == PWM_TYPE_BRUSHED) && (masterConfig.motorConfig.mincommand < 1000)){
882 masterConfig.motorConfig.mincommand = 1000;
885 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
886 featureSet(DEFAULT_RX_FEATURE);
889 if (featureConfigured(FEATURE_RX_PPM)) {
890 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
893 if (featureConfigured(FEATURE_RX_MSP)) {
894 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
897 if (featureConfigured(FEATURE_RX_SERIAL)) {
898 featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
901 if (featureConfigured(FEATURE_RX_SPI)) {
902 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
905 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
906 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
907 #if defined(STM32F10X)
908 // rssi adc needs the same ports
909 featureClear(FEATURE_RSSI_ADC);
910 // current meter needs the same ports
911 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
912 featureClear(FEATURE_CURRENT_METER);
914 #endif
916 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
917 // led strip needs the same ports
918 featureClear(FEATURE_LED_STRIP);
919 #endif
921 // software serial needs free PWM ports
922 featureClear(FEATURE_SOFTSERIAL);
925 #ifdef USE_SOFTSPI
926 if (featureConfigured(FEATURE_SOFTSPI)) {
927 featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
928 #if defined(STM32F10X)
929 featureClear(FEATURE_LED_STRIP);
930 // rssi adc needs the same ports
931 featureClear(FEATURE_RSSI_ADC);
932 // current meter needs the same ports
933 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
934 featureClear(FEATURE_CURRENT_METER);
936 #endif
938 #endif
940 #if defined(NAZE) && defined(SONAR)
941 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
942 featureClear(FEATURE_CURRENT_METER);
944 #endif
946 #if defined(OLIMEXINO) && defined(SONAR)
947 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
948 featureClear(FEATURE_CURRENT_METER);
950 #endif
952 #if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
953 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) {
954 featureClear(FEATURE_DASHBOARD);
956 #endif
958 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
959 // shared pin
960 if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
961 featureClear(FEATURE_SONAR);
962 featureClear(FEATURE_SOFTSERIAL);
963 featureClear(FEATURE_RSSI_ADC);
965 #endif
967 #if defined(COLIBRI_RACE)
968 masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
969 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
970 featureClear(FEATURE_RX_PARALLEL_PWM);
971 featureClear(FEATURE_RX_MSP);
972 featureSet(FEATURE_RX_PPM);
974 #endif
976 useRxConfig(&masterConfig.rxConfig);
978 serialConfig_t *serialConfig = &masterConfig.serialConfig;
980 if (!isSerialConfigValid(serialConfig)) {
981 resetSerialConfig(serialConfig);
984 validateAndFixGyroConfig();
986 #if defined(TARGET_VALIDATECONFIG)
987 targetValidateConfiguration(&masterConfig);
988 #endif
991 void validateAndFixGyroConfig(void)
993 // Prevent invalid notch cutoff
994 if (masterConfig.gyroConfig.gyro_soft_notch_cutoff_1 >= masterConfig.gyroConfig.gyro_soft_notch_hz_1) {
995 masterConfig.gyroConfig.gyro_soft_notch_hz_1 = 0;
997 if (masterConfig.gyroConfig.gyro_soft_notch_cutoff_2 >= masterConfig.gyroConfig.gyro_soft_notch_hz_2) {
998 masterConfig.gyroConfig.gyro_soft_notch_hz_2 = 0;
1001 if (masterConfig.gyroConfig.gyro_lpf != GYRO_LPF_256HZ && masterConfig.gyroConfig.gyro_lpf != GYRO_LPF_NONE) {
1002 masterConfig.pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
1003 masterConfig.gyroConfig.gyro_sync_denom = 1;
1007 void readEEPROMAndNotify(void)
1009 // re-read written data
1010 readEEPROM();
1011 beeperConfirmationBeeps(1);
1014 void ensureEEPROMContainsValidData(void)
1016 if (isEEPROMContentValid()) {
1017 return;
1020 resetEEPROM();
1023 void resetEEPROM(void)
1025 resetConf();
1026 writeEEPROM();
1029 void saveConfigAndNotify(void)
1031 writeEEPROM();
1032 readEEPROMAndNotify();
1035 void changeProfile(uint8_t profileIndex)
1037 masterConfig.current_profile_index = profileIndex;
1038 writeEEPROM();
1039 readEEPROM();
1040 beeperConfirmationBeeps(profileIndex + 1);
1043 void changeControlRateProfile(uint8_t profileIndex)
1045 if (profileIndex > MAX_RATEPROFILES) {
1046 profileIndex = MAX_RATEPROFILES - 1;
1048 setControlRateProfile(profileIndex);
1049 activateControlRateConfig();
1052 void beeperOffSet(uint32_t mask)
1054 masterConfig.beeper_off_flags |= mask;
1057 void beeperOffSetAll(uint8_t beeperCount)
1059 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1062 void beeperOffClear(uint32_t mask)
1064 masterConfig.beeper_off_flags &= ~(mask);
1067 void beeperOffClearAll(void)
1069 masterConfig.beeper_off_flags = 0;
1072 uint32_t getBeeperOffMask(void)
1074 return masterConfig.beeper_off_flags;
1077 void setBeeperOffMask(uint32_t mask)
1079 masterConfig.beeper_off_flags = mask;
1082 uint32_t getPreferredBeeperOffMask(void)
1084 return masterConfig.preferred_beeper_off_flags;
1087 void setPreferredBeeperOffMask(uint32_t mask)
1089 masterConfig.preferred_beeper_off_flags = mask;