Removed more target specific conditionals from the main codebase
[betaflight.git] / src / main / fc / config.c
blob4068606c8679610ec93622d0db983689caa15f4a
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>
21 #include <math.h>
23 #include "platform.h"
25 #include "build/build_config.h"
26 #include "build/debug.h"
28 #include "blackbox/blackbox_io.h"
30 #include "cms/cms.h"
32 #include "common/axis.h"
33 #include "common/color.h"
34 #include "common/filter.h"
35 #include "common/maths.h"
37 #include "config/config_eeprom.h"
38 #include "config/config_master.h"
39 #include "config/config_profile.h"
40 #include "config/feature.h"
41 #include "config/parameter_group.h"
42 #include "config/parameter_group_ids.h"
44 #include "drivers/accgyro.h"
45 #include "drivers/compass.h"
46 #include "drivers/io.h"
47 #include "drivers/light_ws2811strip.h"
48 #include "drivers/max7456.h"
49 #include "drivers/pwm_esc_detect.h"
50 #include "drivers/pwm_output.h"
51 #include "drivers/rx_pwm.h"
52 #include "drivers/rx_spi.h"
53 #include "drivers/sdcard.h"
54 #include "drivers/sensor.h"
55 #include "drivers/serial.h"
56 #include "drivers/sound_beeper.h"
57 #include "drivers/system.h"
58 #include "drivers/timer.h"
59 #include "drivers/vcd.h"
61 #include "fc/config.h"
62 #include "fc/rc_controls.h"
63 #include "fc/fc_rc.h"
64 #include "fc/runtime_config.h"
66 #include "flight/altitudehold.h"
67 #include "flight/failsafe.h"
68 #include "flight/imu.h"
69 #include "flight/mixer.h"
70 #include "flight/navigation.h"
71 #include "flight/pid.h"
72 #include "flight/servos.h"
74 #include "io/beeper.h"
75 #include "io/gimbal.h"
76 #include "io/gps.h"
77 #include "io/ledstrip.h"
78 #include "io/motors.h"
79 #include "io/osd.h"
80 #include "io/serial.h"
81 #include "io/servos.h"
82 #include "io/vtx.h"
84 #include "rx/rx.h"
85 #include "rx/rx_spi.h"
87 #include "sensors/acceleration.h"
88 #include "sensors/barometer.h"
89 #include "sensors/battery.h"
90 #include "sensors/boardalignment.h"
91 #include "sensors/compass.h"
92 #include "sensors/gyro.h"
93 #include "sensors/sensors.h"
95 #include "telemetry/telemetry.h"
97 #ifndef DEFAULT_RX_FEATURE
98 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
99 #endif
100 #ifndef RX_SPI_DEFAULT_PROTOCOL
101 #define RX_SPI_DEFAULT_PROTOCOL 0
102 #endif
104 #define BRUSHED_MOTORS_PWM_RATE 16000
105 #define BRUSHLESS_MOTORS_PWM_RATE 480
107 master_t masterConfig; // master config struct with data independent from profiles
108 profile_t *currentProfile;
110 static uint8_t currentControlRateProfileIndex = 0;
111 controlRateConfig_t *currentControlRateProfile;
113 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
115 accelerometerTrims->values.pitch = 0;
116 accelerometerTrims->values.roll = 0;
117 accelerometerTrims->values.yaw = 0;
120 static void resetCompassConfig(compassConfig_t* compassConfig)
122 compassConfig->mag_align = ALIGN_DEFAULT;
123 #ifdef MAG_INT_EXTI
124 compassConfig->interruptTag = IO_TAG(MAG_INT_EXTI);
125 #else
126 compassConfig->interruptTag = IO_TAG_NONE;
127 #endif
130 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
132 controlRateConfig->rcRate8 = 100;
133 controlRateConfig->rcYawRate8 = 100;
134 controlRateConfig->rcExpo8 = 0;
135 controlRateConfig->thrMid8 = 50;
136 controlRateConfig->thrExpo8 = 0;
137 controlRateConfig->dynThrPID = 10;
138 controlRateConfig->rcYawExpo8 = 0;
139 controlRateConfig->tpa_breakpoint = 1650;
141 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
142 controlRateConfig->rates[axis] = 70;
146 static void resetPidProfile(pidProfile_t *pidProfile)
148 pidProfile->P8[ROLL] = 44;
149 pidProfile->I8[ROLL] = 40;
150 pidProfile->D8[ROLL] = 20;
151 pidProfile->P8[PITCH] = 58;
152 pidProfile->I8[PITCH] = 50;
153 pidProfile->D8[PITCH] = 22;
154 pidProfile->P8[YAW] = 70;
155 pidProfile->I8[YAW] = 45;
156 pidProfile->D8[YAW] = 20;
157 pidProfile->P8[PIDALT] = 50;
158 pidProfile->I8[PIDALT] = 0;
159 pidProfile->D8[PIDALT] = 0;
160 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
161 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
162 pidProfile->D8[PIDPOS] = 0;
163 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
164 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
165 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
166 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
167 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
168 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
169 pidProfile->P8[PIDLEVEL] = 50;
170 pidProfile->I8[PIDLEVEL] = 50;
171 pidProfile->D8[PIDLEVEL] = 100;
172 pidProfile->P8[PIDMAG] = 40;
173 pidProfile->P8[PIDVEL] = 55;
174 pidProfile->I8[PIDVEL] = 55;
175 pidProfile->D8[PIDVEL] = 75;
177 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
178 pidProfile->pidSumLimit = PIDSUM_LIMIT;
179 pidProfile->yaw_lpf_hz = 0;
180 pidProfile->itermWindupPointPercent = 50;
181 pidProfile->dterm_filter_type = FILTER_BIQUAD;
182 pidProfile->dterm_lpf_hz = 100; // filtering ON by default
183 pidProfile->dterm_notch_hz = 260;
184 pidProfile->dterm_notch_cutoff = 160;
185 pidProfile->vbatPidCompensation = 0;
186 pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
187 pidProfile->levelAngleLimit = 55;
188 pidProfile->levelSensitivity = 55;
189 pidProfile->setpointRelaxRatio = 25;
190 pidProfile->dtermSetpointWeight = 190;
191 pidProfile->yawRateAccelLimit = 10.0f;
192 pidProfile->rateAccelLimit = 0.0f;
193 pidProfile->itermThrottleThreshold = 350;
194 pidProfile->itermAcceleratorGain = 1.0f;
197 void resetProfile(profile_t *profile)
199 resetPidProfile(&profile->pidProfile);
201 for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
202 resetControlRateConfig(&profile->controlRateProfile[rI]);
205 profile->activeRateProfile = 0;
208 #ifdef GPS
209 void resetGpsProfile(gpsProfile_t *gpsProfile)
211 gpsProfile->gps_wp_radius = 200;
212 gpsProfile->gps_lpf = 20;
213 gpsProfile->nav_slew_rate = 30;
214 gpsProfile->nav_controls_heading = 1;
215 gpsProfile->nav_speed_min = 100;
216 gpsProfile->nav_speed_max = 300;
217 gpsProfile->ap_mode = 40;
219 #endif
221 #ifdef BARO
222 void resetBarometerConfig(barometerConfig_t *barometerConfig)
224 barometerConfig->baro_sample_count = 21;
225 barometerConfig->baro_noise_lpf = 0.6f;
226 barometerConfig->baro_cf_vel = 0.985f;
227 barometerConfig->baro_cf_alt = 0.965f;
229 #endif
231 #ifdef LED_STRIP
232 void resetLedStripConfig(ledStripConfig_t *ledStripConfig)
234 applyDefaultColors(ledStripConfig->colors);
235 applyDefaultLedStripConfig(ledStripConfig->ledConfigs);
236 applyDefaultModeColors(ledStripConfig->modeColors);
237 applyDefaultSpecialColors(&(ledStripConfig->specialColors));
238 ledStripConfig->ledstrip_visual_beeper = 0;
239 ledStripConfig->ledstrip_aux_channel = THROTTLE;
241 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
242 if (timerHardware[i].usageFlags & TIM_USE_LED) {
243 ledStripConfig->ioTag = timerHardware[i].tag;
244 return;
247 ledStripConfig->ioTag = IO_TAG_NONE;
249 #endif
251 #ifdef USE_SERVOS
252 void resetServoConfig(servoConfig_t *servoConfig)
254 servoConfig->servoCenterPulse = 1500;
255 servoConfig->servoPwmRate = 50;
257 int servoIndex = 0;
258 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) {
259 if (timerHardware[i].usageFlags & TIM_USE_SERVO) {
260 servoConfig->ioTags[servoIndex] = timerHardware[i].tag;
261 servoIndex++;
265 #endif
267 void resetMotorConfig(motorConfig_t *motorConfig)
269 #ifdef BRUSHED_MOTORS
270 motorConfig->minthrottle = 1000;
271 motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
272 motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
273 motorConfig->useUnsyncedPwm = true;
274 #else
275 #ifdef BRUSHED_ESC_AUTODETECT
276 if (hardwareMotorType == MOTOR_BRUSHED) {
277 motorConfig->minthrottle = 1000;
278 motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
279 motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
280 motorConfig->useUnsyncedPwm = true;
281 } else
282 #endif
284 motorConfig->minthrottle = 1070;
285 motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
286 motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
288 #endif
289 motorConfig->maxthrottle = 2000;
290 motorConfig->mincommand = 1000;
291 motorConfig->digitalIdleOffsetPercent = 4.5f;
293 int motorIndex = 0;
294 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
295 if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
296 motorConfig->ioTags[motorIndex] = timerHardware[i].tag;
297 motorIndex++;
302 #ifdef SONAR
303 void resetSonarConfig(sonarConfig_t *sonarConfig)
305 #if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
306 sonarConfig->triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
307 sonarConfig->echoTag = IO_TAG(SONAR_ECHO_PIN);
308 #else
309 #error Sonar not defined for target
310 #endif
312 #endif
314 #ifdef USE_SDCARD
315 void resetsdcardConfig(sdcardConfig_t *sdcardConfig)
317 #if defined(SDCARD_DMA_CHANNEL_TX)
318 sdcardConfig->useDma = true;
319 #else
320 sdcardConfig->useDma = false;
321 #endif
323 #endif
325 #ifdef USE_ADC
326 void resetAdcConfig(adcConfig_t *adcConfig)
328 #ifdef VBAT_ADC_PIN
329 adcConfig->vbat.enabled = true;
330 adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
331 #endif
333 #ifdef EXTERNAL1_ADC_PIN
334 adcConfig->external1.enabled = true;
335 adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
336 #endif
338 #ifdef CURRENT_METER_ADC_PIN
339 adcConfig->currentMeter.enabled = true;
340 adcConfig->currentMeter.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
341 #endif
343 #ifdef RSSI_ADC_PIN
344 adcConfig->rssi.enabled = true;
345 adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
346 #endif
349 #endif
352 #ifdef BEEPER
353 void resetBeeperConfig(beeperConfig_t *beeperConfig)
355 #ifdef BEEPER_INVERTED
356 beeperConfig->isOpenDrain = false;
357 beeperConfig->isInverted = true;
358 #else
359 beeperConfig->isOpenDrain = true;
360 beeperConfig->isInverted = false;
361 #endif
362 beeperConfig->ioTag = IO_TAG(BEEPER);
364 #endif
366 #if defined(USE_PWM) || defined(USE_PPM)
367 void resetPpmConfig(ppmConfig_t *ppmConfig)
369 #ifdef PPM_PIN
370 ppmConfig->ioTag = IO_TAG(PPM_PIN);
371 #else
372 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
373 if (timerHardware[i].usageFlags & TIM_USE_PPM) {
374 ppmConfig->ioTag = timerHardware[i].tag;
375 return;
379 ppmConfig->ioTag = IO_TAG_NONE;
380 #endif
383 void resetPwmConfig(pwmConfig_t *pwmConfig)
385 int inputIndex = 0;
386 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
387 if (timerHardware[i].usageFlags & TIM_USE_PWM) {
388 pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
389 inputIndex++;
393 #endif
395 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
397 flight3DConfig->deadband3d_low = 1406;
398 flight3DConfig->deadband3d_high = 1514;
399 flight3DConfig->neutral3d = 1460;
400 flight3DConfig->deadband3d_throttle = 50;
403 #ifdef TELEMETRY
404 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
406 telemetryConfig->telemetry_inversion = 1;
407 telemetryConfig->sportHalfDuplex = 1;
408 telemetryConfig->telemetry_switch = 0;
409 telemetryConfig->gpsNoFixLatitude = 0;
410 telemetryConfig->gpsNoFixLongitude = 0;
411 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
412 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
413 telemetryConfig->frsky_vfas_precision = 0;
414 telemetryConfig->frsky_vfas_cell_voltage = 0;
415 telemetryConfig->hottAlarmSoundInterval = 5;
416 telemetryConfig->pidValuesAsTelemetry = 0;
417 #ifdef TELEMETRY_IBUS
418 telemetryConfig->report_cell_voltage = false;
419 #endif
421 #endif
423 void resetBatteryConfig(batteryConfig_t *batteryConfig)
425 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
426 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
427 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
428 batteryConfig->vbatmaxcellvoltage = 43;
429 batteryConfig->vbatmincellvoltage = 33;
430 batteryConfig->vbatwarningcellvoltage = 35;
431 batteryConfig->vbathysteresis = 1;
432 batteryConfig->batteryMeterType = BATTERY_SENSOR_ADC;
433 batteryConfig->currentMeterOffset = 0;
434 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
435 batteryConfig->batteryCapacity = 0;
436 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
437 batteryConfig->batterynotpresentlevel = 55; // VBAT below 5.5 V will be igonored
438 batteryConfig->useVBatAlerts = true;
439 batteryConfig->useConsumptionAlerts = false;
440 batteryConfig->consumptionWarningPercentage = 10;
443 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
444 #define FIRST_PORT_INDEX 1
445 #define SECOND_PORT_INDEX 0
446 #else
447 #define FIRST_PORT_INDEX 0
448 #define SECOND_PORT_INDEX 1
449 #endif
451 void resetSerialConfig(serialConfig_t *serialConfig)
453 memset(serialConfig, 0, sizeof(serialConfig_t));
454 serialConfig->serial_update_rate_hz = 100;
455 serialConfig->reboot_character = 'R';
457 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
458 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
459 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
460 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
461 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
462 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
465 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
466 #if defined(USE_VCP) && defined(USE_MSP_UART)
467 // This allows MSP connection via USART & VCP so the board can be reconfigured.
468 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
469 #endif
472 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
474 rcControlsConfig->deadband = 0;
475 rcControlsConfig->yaw_deadband = 0;
476 rcControlsConfig->alt_hold_deadband = 40;
477 rcControlsConfig->alt_hold_fast_change = 1;
480 void resetMixerConfig(mixerConfig_t *mixerConfig)
482 #ifdef TARGET_DEFAULT_MIXER
483 mixerConfig->mixerMode = TARGET_DEFAULT_MIXER;
484 #else
485 mixerConfig->mixerMode = MIXER_QUADX;
486 #endif
487 mixerConfig->yaw_motor_direction = 1;
490 #ifdef USE_SERVOS
491 void resetServoMixerConfig(servoMixerConfig_t *servoMixerConfig)
493 servoMixerConfig->tri_unarmed_servo = 1;
494 servoMixerConfig->servo_lowpass_freq = 400;
495 servoMixerConfig->servo_lowpass_enable = 0;
497 #endif
499 #ifdef USE_MAX7456
500 void resetMax7456Config(vcdProfile_t *pVcdProfile)
502 pVcdProfile->video_system = VIDEO_SYSTEM_AUTO;
503 pVcdProfile->h_offset = 0;
504 pVcdProfile->v_offset = 0;
506 #endif
508 void resetDisplayPortProfile(displayPortProfile_t *pDisplayPortProfile)
510 pDisplayPortProfile->colAdjust = 0;
511 pDisplayPortProfile->rowAdjust = 0;
514 void resetStatusLedConfig(statusLedConfig_t *statusLedConfig)
516 for (int i = 0; i < LED_NUMBER; i++) {
517 statusLedConfig->ledTags[i] = IO_TAG_NONE;
520 #ifdef LED0
521 statusLedConfig->ledTags[0] = IO_TAG(LED0);
522 #endif
523 #ifdef LED1
524 statusLedConfig->ledTags[1] = IO_TAG(LED1);
525 #endif
526 #ifdef LED2
527 statusLedConfig->ledTags[2] = IO_TAG(LED2);
528 #endif
530 statusLedConfig->polarity = 0
531 #ifdef LED0_INVERTED
532 | BIT(0)
533 #endif
534 #ifdef LED1_INVERTED
535 | BIT(1)
536 #endif
537 #ifdef LED2_INVERTED
538 | BIT(2)
539 #endif
543 #ifdef USE_FLASHFS
544 void resetFlashConfig(flashConfig_t *flashConfig)
546 #ifdef M25P16_CS_PIN
547 flashConfig->csTag = IO_TAG(M25P16_CS_PIN);
548 #else
549 flashConfig->csTag = IO_TAG_NONE;
550 #endif
552 #endif
554 uint8_t getCurrentProfile(void)
556 return masterConfig.current_profile_index;
559 static void setProfile(uint8_t profileIndex)
561 currentProfile = &masterConfig.profile[profileIndex];
562 currentControlRateProfileIndex = currentProfile->activeRateProfile;
563 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
566 uint8_t getCurrentControlRateProfile(void)
568 return currentControlRateProfileIndex;
571 static void setControlRateProfile(uint8_t profileIndex)
573 currentControlRateProfileIndex = profileIndex;
574 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
575 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
578 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
580 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
583 uint16_t getCurrentMinthrottle(void)
585 return motorConfig()->minthrottle;
589 void createDefaultConfig(master_t *config)
591 // Clear all configuration
592 memset(config, 0, sizeof(master_t));
594 uint32_t *featuresPtr = &config->featureConfig.enabledFeatures;
596 intFeatureClearAll(featuresPtr);
597 intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
598 #ifdef DEFAULT_FEATURES
599 intFeatureSet(DEFAULT_FEATURES, featuresPtr);
600 #endif
602 #ifdef USE_MSP_DISPLAYPORT
603 resetDisplayPortProfile(&config->displayPortProfileMsp);
604 #endif
605 #ifdef USE_MAX7456
606 resetDisplayPortProfile(&config->displayPortProfileMax7456);
607 #endif
609 #ifdef USE_MAX7456
610 resetMax7456Config(&config->vcdProfile);
611 #endif
613 #ifdef OSD
614 intFeatureSet(FEATURE_OSD, featuresPtr);
615 osdResetConfig(&config->osdProfile);
616 #endif
618 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
619 // only enable the VBAT feature by default if the board has a voltage divider otherwise
620 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
621 intFeatureSet(FEATURE_VBAT, featuresPtr);
622 #endif
624 config->version = EEPROM_CONF_VERSION;
626 // global settings
627 config->current_profile_index = 0; // default profile
628 config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
629 config->imuConfig.dcm_ki = 0; // 0.003 * 10000
630 config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default
631 #ifdef STM32F10X
632 config->gyroConfig.gyro_sync_denom = 8;
633 config->pidConfig.pid_process_denom = 1;
634 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
635 config->gyroConfig.gyro_sync_denom = 1;
636 config->pidConfig.pid_process_denom = 4;
637 #else
638 config->gyroConfig.gyro_sync_denom = 4;
639 config->pidConfig.pid_process_denom = 2;
640 #endif
641 config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
642 config->gyroConfig.gyro_soft_lpf_hz = 90;
643 config->gyroConfig.gyro_soft_notch_hz_1 = 400;
644 config->gyroConfig.gyro_soft_notch_cutoff_1 = 300;
645 config->gyroConfig.gyro_soft_notch_hz_2 = 200;
646 config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
648 config->systemConfig.debug_mode = DEBUG_MODE;
649 config->task_statistics = true;
651 resetAccelerometerTrims(&config->accelerometerConfig.accZero);
653 config->gyroConfig.gyro_align = ALIGN_DEFAULT;
654 config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
656 resetCompassConfig(&config->compassConfig);
658 config->boardAlignment.rollDegrees = 0;
659 config->boardAlignment.pitchDegrees = 0;
660 config->boardAlignment.yawDegrees = 0;
661 config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
662 config->rcControlsConfig.yaw_control_direction = 1;
663 config->gyroConfig.gyroMovementCalibrationThreshold = 48;
665 // xxx_hardware: 0:default/autodetect, 1: disable
666 config->compassConfig.mag_hardware = 1;
668 config->barometerConfig.baro_hardware = 1;
670 resetBatteryConfig(&config->batteryConfig);
672 #if defined(USE_PWM) || defined(USE_PPM)
673 resetPpmConfig(&config->ppmConfig);
674 resetPwmConfig(&config->pwmConfig);
675 #endif
677 #ifdef TELEMETRY
678 resetTelemetryConfig(&config->telemetryConfig);
679 #endif
681 #ifdef USE_ADC
682 resetAdcConfig(&config->adcConfig);
683 #endif
685 #ifdef BEEPER
686 resetBeeperConfig(&config->beeperConfig);
687 #endif
689 #ifdef SONAR
690 resetSonarConfig(&config->sonarConfig);
691 #endif
693 #ifdef USE_SDCARD
694 intFeatureSet(FEATURE_SDCARD, featuresPtr);
695 resetsdcardConfig(&config->sdcardConfig);
696 #endif
698 #ifdef SERIALRX_PROVIDER
699 config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
700 #else
701 config->rxConfig.serialrx_provider = 0;
702 #endif
703 config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
704 config->rxConfig.sbus_inversion = 1;
705 config->rxConfig.spektrum_sat_bind = 0;
706 config->rxConfig.spektrum_sat_bind_autoreset = 1;
707 config->rxConfig.midrc = 1500;
708 config->rxConfig.mincheck = 1100;
709 config->rxConfig.maxcheck = 1900;
710 config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
711 config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
713 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
714 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
715 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
716 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
719 config->rxConfig.rssi_channel = 0;
720 config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
721 config->rxConfig.rssi_ppm_invert = 0;
722 config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
723 config->rxConfig.rcInterpolationChannels = 0;
724 config->rxConfig.rcInterpolationInterval = 19;
725 config->rxConfig.fpvCamAngleDegrees = 0;
726 config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
727 config->rxConfig.airModeActivateThreshold = 1350;
729 resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
731 #ifdef USE_PWM
732 config->pwmConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
733 #endif
735 config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
736 config->armingConfig.disarm_kill_switch = 1;
737 config->armingConfig.auto_disarm_delay = 5;
738 config->imuConfig.small_angle = 25;
740 config->airplaneConfig.fixedwing_althold_dir = 1;
742 // Motor/ESC/Servo
743 resetMixerConfig(&config->mixerConfig);
744 resetMotorConfig(&config->motorConfig);
745 #ifdef USE_SERVOS
746 resetServoMixerConfig(&config->servoMixerConfig);
747 resetServoConfig(&config->servoConfig);
748 #endif
749 resetFlight3DConfig(&config->flight3DConfig);
751 #ifdef LED_STRIP
752 resetLedStripConfig(&config->ledStripConfig);
753 #endif
755 #ifdef GPS
756 // gps/nav stuff
757 config->gpsConfig.provider = GPS_NMEA;
758 config->gpsConfig.sbasMode = SBAS_AUTO;
759 config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
760 config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
761 #endif
763 resetSerialConfig(&config->serialConfig);
765 resetProfile(&config->profile[0]);
767 resetRollAndPitchTrims(&config->accelerometerConfig.accelerometerTrims);
769 config->compassConfig.mag_declination = 0;
770 config->accelerometerConfig.acc_lpf_hz = 10.0f;
772 config->imuConfig.accDeadband.xy = 40;
773 config->imuConfig.accDeadband.z = 40;
774 config->imuConfig.acc_unarmedcal = 1;
776 #ifdef BARO
777 resetBarometerConfig(&config->barometerConfig);
778 #endif
780 // Radio
781 #ifdef RX_CHANNELS_TAER
782 parseRcChannels("TAER1234", &config->rxConfig);
783 #else
784 parseRcChannels("AETR1234", &config->rxConfig);
785 #endif
787 resetRcControlsConfig(&config->rcControlsConfig);
789 config->throttleCorrectionConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
790 config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
792 // Failsafe Variables
793 config->failsafeConfig.failsafe_delay = 10; // 1sec
794 config->failsafeConfig.failsafe_off_delay = 10; // 1sec
795 config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
796 config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
797 config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
798 config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
800 #ifdef USE_SERVOS
801 // servos
802 for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
803 config->servoProfile.servoConf[i].min = DEFAULT_SERVO_MIN;
804 config->servoProfile.servoConf[i].max = DEFAULT_SERVO_MAX;
805 config->servoProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
806 config->servoProfile.servoConf[i].rate = 100;
807 config->servoProfile.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
808 config->servoProfile.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
809 config->servoProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
812 // gimbal
813 config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
815 // Channel forwarding;
816 config->channelForwardingConfig.startChannel = AUX1;
817 #endif
819 #ifdef GPS
820 resetGpsProfile(&config->gpsProfile);
821 #endif
823 // custom mixer. clear by defaults.
824 for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
825 config->customMotorMixer[i].throttle = 0.0f;
828 #ifdef VTX
829 config->vtx_band = 4; //Fatshark/Airwaves
830 config->vtx_channel = 1; //CH1
831 config->vtx_mode = 0; //CH+BAND mode
832 config->vtx_mhz = 5740; //F0
833 #endif
835 #ifdef TRANSPONDER
836 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
838 memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
839 #endif
841 #ifdef BLACKBOX
842 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
843 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
844 config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
845 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
846 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
847 config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
848 #else
849 config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
850 #endif
852 config->blackboxConfig.rate_num = 1;
853 config->blackboxConfig.rate_denom = 1;
854 config->blackboxConfig.on_motor_test = 0; // default off
855 #endif // BLACKBOX
857 #ifdef SERIALRX_UART
858 if (featureConfigured(FEATURE_RX_SERIAL)) {
859 int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART);
860 if (serialIndex >= 0) {
861 config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL;
864 #endif
866 #ifdef USE_FLASHFS
867 resetFlashConfig(&config->flashConfig);
868 #endif
870 resetStatusLedConfig(&config->statusLedConfig);
872 /* merely to force a reset if the person inadvertently flashes the wrong target */
873 strncpy(config->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER));
875 #if defined(TARGET_CONFIG)
876 targetConfiguration(config);
877 #endif
879 // copy first profile into remaining profile
880 for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
881 memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
885 void resetConfigs(void)
887 createDefaultConfig(&masterConfig);
888 pgResetAll(MAX_PROFILE_COUNT);
889 pgActivateProfile(0);
891 setProfile(0);
892 setControlRateProfile(0);
894 #ifdef LED_STRIP
895 reevaluateLedConfig();
896 #endif
899 void activateConfig(void)
901 generateThrottleCurve();
903 resetAdjustmentStates();
905 useRcControlsConfig(modeActivationConditions(0), &currentProfile->pidProfile);
906 useAdjustmentConfig(&currentProfile->pidProfile);
908 #ifdef GPS
909 gpsUseProfile(&masterConfig.gpsProfile);
910 gpsUsePIDs(&currentProfile->pidProfile);
911 #endif
913 failsafeReset();
914 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
915 setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
917 mixerUseConfigs(&masterConfig.airplaneConfig);
919 #ifdef USE_SERVOS
920 servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.channelForwardingConfig);
921 #endif
923 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
925 configureAltitudeHold(&currentProfile->pidProfile);
928 void validateAndFixConfig(void)
930 if((motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
931 motorConfigMutable()->mincommand = 1000;
934 if ((motorConfig()->motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
935 motorConfigMutable()->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
938 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
939 featureSet(DEFAULT_RX_FEATURE);
942 if (featureConfigured(FEATURE_RX_PPM)) {
943 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
946 if (featureConfigured(FEATURE_RX_MSP)) {
947 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
950 if (featureConfigured(FEATURE_RX_SERIAL)) {
951 featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
954 if (featureConfigured(FEATURE_RX_SPI)) {
955 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
958 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
959 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
960 #if defined(STM32F10X)
961 // rssi adc needs the same ports
962 featureClear(FEATURE_RSSI_ADC);
963 // current meter needs the same ports
964 if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
965 featureClear(FEATURE_CURRENT_METER);
967 #endif
968 // software serial needs free PWM ports
969 featureClear(FEATURE_SOFTSERIAL);
972 #ifdef USE_SOFTSPI
973 if (featureConfigured(FEATURE_SOFTSPI)) {
974 featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
975 #if defined(STM32F10X)
976 featureClear(FEATURE_LED_STRIP);
977 // rssi adc needs the same ports
978 featureClear(FEATURE_RSSI_ADC);
979 // current meter needs the same ports
980 if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
981 featureClear(FEATURE_CURRENT_METER);
983 #endif
985 #endif
987 useRxConfig(&masterConfig.rxConfig);
989 serialConfig_t *serialConfig = &masterConfig.serialConfig;
991 if (!isSerialConfigValid(serialConfig)) {
992 resetSerialConfig(serialConfig);
995 validateAndFixGyroConfig();
997 #if defined(TARGET_VALIDATECONFIG)
998 targetValidateConfiguration(&masterConfig);
999 #endif
1002 void validateAndFixGyroConfig(void)
1004 // Prevent invalid notch cutoff
1005 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
1006 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
1008 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
1009 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
1012 float samplingTime = 0.000125f;
1014 if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
1015 pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
1016 gyroConfigMutable()->gyro_sync_denom = 1;
1017 gyroConfigMutable()->gyro_use_32khz = false;
1018 samplingTime = 0.001f;
1021 if (gyroConfig()->gyro_use_32khz) {
1022 samplingTime = 0.00003125;
1023 // F1 and F3 can't handle high sample speed.
1024 #if defined(STM32F1)
1025 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
1026 #elif defined(STM32F3)
1027 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
1028 #endif
1029 } else {
1030 #if defined(STM32F1)
1031 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
1032 #endif
1035 #if !defined(GYRO_USES_SPI) || !defined(USE_MPU_DATA_READY_SIGNAL)
1036 gyroConfigMutable()->gyro_isr_update = false;
1037 #endif
1039 // check for looptime restrictions based on motor protocol. Motor times have safety margin
1040 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
1041 float motorUpdateRestriction;
1042 switch(motorConfig()->motorPwmProtocol) {
1043 case (PWM_TYPE_STANDARD):
1044 motorUpdateRestriction = 1.0f/BRUSHLESS_MOTORS_PWM_RATE;
1045 break;
1046 case (PWM_TYPE_ONESHOT125):
1047 motorUpdateRestriction = 0.0005f;
1048 break;
1049 case (PWM_TYPE_ONESHOT42):
1050 motorUpdateRestriction = 0.0001f;
1051 break;
1052 #ifdef USE_DSHOT
1053 case (PWM_TYPE_DSHOT150):
1054 motorUpdateRestriction = 0.000250f;
1055 break;
1056 case (PWM_TYPE_DSHOT300):
1057 motorUpdateRestriction = 0.0001f;
1058 break;
1059 #endif
1060 default:
1061 motorUpdateRestriction = 0.00003125f;
1064 if (pidLooptime < motorUpdateRestriction) {
1065 const uint8_t maxPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
1066 pidConfigMutable()->pid_process_denom = MIN(pidConfigMutable()->pid_process_denom, maxPidProcessDenom);
1069 // Prevent overriding the max rate of motors
1070 if (motorConfig()->useUnsyncedPwm && (motorConfig()->motorPwmProtocol <= PWM_TYPE_BRUSHED) && motorConfig()->motorPwmProtocol != PWM_TYPE_STANDARD) {
1071 uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
1073 if(motorConfig()->motorPwmRate > maxEscRate)
1074 motorConfigMutable()->motorPwmRate = maxEscRate;
1078 void readEEPROM(void)
1080 suspendRxSignal();
1082 // Sanity check, read flash
1083 if (!loadEEPROM()) {
1084 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
1087 // pgActivateProfile(getCurrentProfile());
1088 // setControlRateProfile(rateProfileSelection()->defaultRateProfileIndex);
1090 if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) {// sanity check
1091 masterConfig.current_profile_index = 0;
1094 setProfile(masterConfig.current_profile_index);
1096 validateAndFixConfig();
1097 activateConfig();
1099 resumeRxSignal();
1102 void writeEEPROM(void)
1104 suspendRxSignal();
1106 writeConfigToEEPROM();
1108 resumeRxSignal();
1111 void resetEEPROM(void)
1113 resetConfigs();
1114 writeEEPROM();
1117 void ensureEEPROMContainsValidData(void)
1119 if (isEEPROMContentValid()) {
1120 return;
1122 resetEEPROM();
1125 void saveConfigAndNotify(void)
1127 writeEEPROM();
1128 readEEPROM();
1129 beeperConfirmationBeeps(1);
1132 void changeProfile(uint8_t profileIndex)
1134 if (profileIndex >= MAX_PROFILE_COUNT) {
1135 profileIndex = MAX_PROFILE_COUNT - 1;
1137 masterConfig.current_profile_index = profileIndex;
1138 writeEEPROM();
1139 readEEPROM();
1140 beeperConfirmationBeeps(profileIndex + 1);
1143 void changeControlRateProfile(uint8_t profileIndex)
1145 if (profileIndex >= MAX_RATEPROFILES) {
1146 profileIndex = MAX_RATEPROFILES - 1;
1148 setControlRateProfile(profileIndex);
1149 generateThrottleCurve();
1152 void beeperOffSet(uint32_t mask)
1154 masterConfig.beeper_off_flags |= mask;
1157 void beeperOffSetAll(uint8_t beeperCount)
1159 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1162 void beeperOffClear(uint32_t mask)
1164 masterConfig.beeper_off_flags &= ~(mask);
1167 void beeperOffClearAll(void)
1169 masterConfig.beeper_off_flags = 0;
1172 uint32_t getBeeperOffMask(void)
1174 return masterConfig.beeper_off_flags;
1177 void setBeeperOffMask(uint32_t mask)
1179 masterConfig.beeper_off_flags = mask;
1182 uint32_t getPreferredBeeperOffMask(void)
1184 return masterConfig.preferred_beeper_off_flags;
1187 void setPreferredBeeperOffMask(uint32_t mask)
1189 masterConfig.preferred_beeper_off_flags = mask;