Allow 32k for dshot600
[betaflight.git] / src / main / fc / config.c
blobfdfc7686a9af0b984d8ec74c3c01491faf26d140
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/color.h"
33 #include "common/axis.h"
34 #include "common/maths.h"
35 #include "common/filter.h"
37 #include "drivers/sensor.h"
38 #include "drivers/accgyro.h"
39 #include "drivers/compass.h"
40 #include "drivers/io.h"
41 #include "drivers/light_ws2811strip.h"
42 #include "drivers/max7456.h"
43 #include "drivers/pwm_esc_detect.h"
44 #include "drivers/pwm_output.h"
45 #include "drivers/rx_pwm.h"
46 #include "drivers/rx_spi.h"
47 #include "drivers/sdcard.h"
48 #include "drivers/serial.h"
49 #include "drivers/sound_beeper.h"
50 #include "drivers/system.h"
51 #include "drivers/timer.h"
52 #include "drivers/vcd.h"
54 #include "fc/config.h"
55 #include "fc/rc_controls.h"
56 #include "fc/rc_curves.h"
57 #include "fc/runtime_config.h"
59 #include "sensors/sensors.h"
60 #include "sensors/gyro.h"
61 #include "sensors/compass.h"
62 #include "sensors/acceleration.h"
63 #include "sensors/barometer.h"
64 #include "sensors/battery.h"
65 #include "sensors/boardalignment.h"
67 #include "io/beeper.h"
68 #include "io/serial.h"
69 #include "io/gimbal.h"
70 #include "io/motors.h"
71 #include "io/servos.h"
72 #include "io/ledstrip.h"
73 #include "io/gps.h"
74 #include "io/osd.h"
75 #include "io/vtx.h"
77 #include "rx/rx.h"
78 #include "rx/rx_spi.h"
80 #include "telemetry/telemetry.h"
82 #include "flight/mixer.h"
83 #include "flight/servos.h"
84 #include "flight/pid.h"
85 #include "flight/imu.h"
86 #include "flight/failsafe.h"
87 #include "flight/altitudehold.h"
88 #include "flight/navigation.h"
90 #include "config/config_eeprom.h"
91 #include "config/config_profile.h"
92 #include "config/config_master.h"
93 #include "config/feature.h"
95 #ifndef DEFAULT_RX_FEATURE
96 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
97 #endif
98 #ifndef RX_SPI_DEFAULT_PROTOCOL
99 #define RX_SPI_DEFAULT_PROTOCOL 0
100 #endif
102 #define BRUSHED_MOTORS_PWM_RATE 16000
103 #ifdef STM32F4
104 #define BRUSHLESS_MOTORS_PWM_RATE 2000
105 #else
106 #define BRUSHLESS_MOTORS_PWM_RATE 400
107 #endif
109 master_t masterConfig; // master config struct with data independent from profiles
110 profile_t *currentProfile;
112 static uint8_t currentControlRateProfileIndex = 0;
113 controlRateConfig_t *currentControlRateProfile;
115 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
117 accelerometerTrims->values.pitch = 0;
118 accelerometerTrims->values.roll = 0;
119 accelerometerTrims->values.yaw = 0;
122 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig)
124 controlRateConfig->rcRate8 = 100;
125 controlRateConfig->rcYawRate8 = 100;
126 controlRateConfig->rcExpo8 = 0;
127 controlRateConfig->thrMid8 = 50;
128 controlRateConfig->thrExpo8 = 0;
129 controlRateConfig->dynThrPID = 10;
130 controlRateConfig->rcYawExpo8 = 0;
131 controlRateConfig->tpa_breakpoint = 1650;
133 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
134 controlRateConfig->rates[axis] = 70;
138 static void resetPidProfile(pidProfile_t *pidProfile)
140 pidProfile->P8[ROLL] = 43;
141 pidProfile->I8[ROLL] = 40;
142 pidProfile->D8[ROLL] = 20;
143 pidProfile->P8[PITCH] = 58;
144 pidProfile->I8[PITCH] = 50;
145 pidProfile->D8[PITCH] = 22;
146 pidProfile->P8[YAW] = 70;
147 pidProfile->I8[YAW] = 45;
148 pidProfile->D8[YAW] = 20;
149 pidProfile->P8[PIDALT] = 50;
150 pidProfile->I8[PIDALT] = 0;
151 pidProfile->D8[PIDALT] = 0;
152 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
153 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
154 pidProfile->D8[PIDPOS] = 0;
155 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
156 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
157 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
158 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
159 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
160 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
161 pidProfile->P8[PIDLEVEL] = 50;
162 pidProfile->I8[PIDLEVEL] = 50;
163 pidProfile->D8[PIDLEVEL] = 100;
164 pidProfile->P8[PIDMAG] = 40;
165 pidProfile->P8[PIDVEL] = 55;
166 pidProfile->I8[PIDVEL] = 55;
167 pidProfile->D8[PIDVEL] = 75;
169 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
170 pidProfile->pidSumLimit = PIDSUM_LIMIT;
171 pidProfile->yaw_lpf_hz = 0;
172 pidProfile->rollPitchItermIgnoreRate = 200;
173 pidProfile->yawItermIgnoreRate = 55;
174 pidProfile->dterm_filter_type = FILTER_BIQUAD;
175 pidProfile->dterm_lpf_hz = 100; // filtering ON by default
176 pidProfile->dterm_notch_hz = 260;
177 pidProfile->dterm_notch_cutoff = 160;
178 pidProfile->vbatPidCompensation = 0;
179 pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
180 pidProfile->levelAngleLimit = 70; // 70 degrees
181 pidProfile->levelSensitivity = 100; // 100 degrees at full stick
182 pidProfile->setpointRelaxRatio = 30;
183 pidProfile->dtermSetpointWeight = 200;
184 pidProfile->yawRateAccelLimit = 10.0f;
185 pidProfile->rateAccelLimit = 0.0f;
186 pidProfile->itermThrottleThreshold = 350;
189 void resetProfile(profile_t *profile)
191 resetPidProfile(&profile->pidProfile);
193 for (int rI = 0; rI<MAX_RATEPROFILES; rI++) {
194 resetControlRateConfig(&profile->controlRateProfile[rI]);
197 profile->activeRateProfile = 0;
200 #ifdef GPS
201 void resetGpsProfile(gpsProfile_t *gpsProfile)
203 gpsProfile->gps_wp_radius = 200;
204 gpsProfile->gps_lpf = 20;
205 gpsProfile->nav_slew_rate = 30;
206 gpsProfile->nav_controls_heading = 1;
207 gpsProfile->nav_speed_min = 100;
208 gpsProfile->nav_speed_max = 300;
209 gpsProfile->ap_mode = 40;
211 #endif
213 #ifdef BARO
214 void resetBarometerConfig(barometerConfig_t *barometerConfig)
216 barometerConfig->baro_sample_count = 21;
217 barometerConfig->baro_noise_lpf = 0.6f;
218 barometerConfig->baro_cf_vel = 0.985f;
219 barometerConfig->baro_cf_alt = 0.965f;
221 #endif
223 #ifdef LED_STRIP
224 void resetLedStripConfig(ledStripConfig_t *ledStripConfig)
226 applyDefaultColors(ledStripConfig->colors);
227 applyDefaultLedStripConfig(ledStripConfig->ledConfigs);
228 applyDefaultModeColors(ledStripConfig->modeColors);
229 applyDefaultSpecialColors(&(ledStripConfig->specialColors));
230 ledStripConfig->ledstrip_visual_beeper = 0;
231 ledStripConfig->ledstrip_aux_channel = THROTTLE;
233 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
234 if (timerHardware[i].usageFlags & TIM_USE_LED) {
235 ledStripConfig->ioTag = timerHardware[i].tag;
236 return;
239 ledStripConfig->ioTag = IO_TAG_NONE;
241 #endif
243 #ifdef USE_SERVOS
244 void resetServoConfig(servoConfig_t *servoConfig)
246 servoConfig->servoCenterPulse = 1500;
247 servoConfig->servoPwmRate = 50;
249 int servoIndex = 0;
250 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && servoIndex < MAX_SUPPORTED_SERVOS; i++) {
251 if (timerHardware[i].usageFlags & TIM_USE_SERVO) {
252 servoConfig->ioTags[servoIndex] = timerHardware[i].tag;
253 servoIndex++;
257 #endif
259 void resetMotorConfig(motorConfig_t *motorConfig)
261 #ifdef BRUSHED_MOTORS
262 motorConfig->minthrottle = 1000;
263 motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
264 motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
265 motorConfig->useUnsyncedPwm = true;
266 #else
267 #ifdef BRUSHED_ESC_AUTODETECT
268 if (hardwareMotorType == MOTOR_BRUSHED) {
269 motorConfig->minthrottle = 1000;
270 motorConfig->motorPwmRate = BRUSHED_MOTORS_PWM_RATE;
271 motorConfig->motorPwmProtocol = PWM_TYPE_BRUSHED;
272 motorConfig->useUnsyncedPwm = true;
273 } else
274 #endif
276 motorConfig->minthrottle = 1070;
277 motorConfig->motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
278 motorConfig->motorPwmProtocol = PWM_TYPE_ONESHOT125;
280 #endif
281 motorConfig->maxthrottle = 2000;
282 motorConfig->mincommand = 1000;
283 motorConfig->digitalIdleOffsetPercent = 3.0f;
285 int motorIndex = 0;
286 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && motorIndex < MAX_SUPPORTED_MOTORS; i++) {
287 if (timerHardware[i].usageFlags & TIM_USE_MOTOR) {
288 motorConfig->ioTags[motorIndex] = timerHardware[i].tag;
289 motorIndex++;
294 #ifdef SONAR
295 void resetSonarConfig(sonarConfig_t *sonarConfig)
297 #if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
298 sonarConfig->triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
299 sonarConfig->echoTag = IO_TAG(SONAR_ECHO_PIN);
300 #else
301 #error Sonar not defined for target
302 #endif
304 #endif
306 #ifdef USE_SDCARD
307 void resetsdcardConfig(sdcardConfig_t *sdcardConfig)
309 #if defined(SDCARD_DMA_CHANNEL_TX)
310 sdcardConfig->useDma = true;
311 #else
312 sdcardConfig->useDma = false;
313 #endif
315 #endif
317 #ifdef USE_ADC
318 void resetAdcConfig(adcConfig_t *adcConfig)
320 #ifdef VBAT_ADC_PIN
321 adcConfig->vbat.enabled = true;
322 adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
323 #endif
325 #ifdef EXTERNAL1_ADC_PIN
326 adcConfig->external1.enabled = true;
327 adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
328 #endif
330 #ifdef CURRENT_METER_ADC_PIN
331 adcConfig->currentMeter.enabled = true;
332 adcConfig->currentMeter.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
333 #endif
335 #ifdef RSSI_ADC_PIN
336 adcConfig->rssi.enabled = true;
337 adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
338 #endif
341 #endif
344 #ifdef BEEPER
345 void resetBeeperConfig(beeperConfig_t *beeperConfig)
347 #ifdef BEEPER_INVERTED
348 beeperConfig->isOpenDrain = false;
349 beeperConfig->isInverted = true;
350 #else
351 beeperConfig->isOpenDrain = true;
352 beeperConfig->isInverted = false;
353 #endif
354 beeperConfig->ioTag = IO_TAG(BEEPER);
356 #endif
358 #if defined(USE_PWM) || defined(USE_PPM)
359 void resetPpmConfig(ppmConfig_t *ppmConfig)
361 #ifdef PPM_PIN
362 ppmConfig->ioTag = IO_TAG(PPM_PIN);
363 #else
364 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
365 if (timerHardware[i].usageFlags & TIM_USE_PPM) {
366 ppmConfig->ioTag = timerHardware[i].tag;
367 return;
371 ppmConfig->ioTag = IO_TAG_NONE;
372 #endif
375 void resetPwmConfig(pwmConfig_t *pwmConfig)
377 int inputIndex = 0;
378 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
379 if (timerHardware[i].usageFlags & TIM_USE_PWM) {
380 pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
381 inputIndex++;
385 #endif
387 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
389 flight3DConfig->deadband3d_low = 1406;
390 flight3DConfig->deadband3d_high = 1514;
391 flight3DConfig->neutral3d = 1460;
392 flight3DConfig->deadband3d_throttle = 50;
395 #ifdef TELEMETRY
396 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
398 telemetryConfig->telemetry_inversion = 1;
399 telemetryConfig->sportHalfDuplex = 1;
400 telemetryConfig->telemetry_switch = 0;
401 telemetryConfig->gpsNoFixLatitude = 0;
402 telemetryConfig->gpsNoFixLongitude = 0;
403 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
404 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
405 telemetryConfig->frsky_vfas_precision = 0;
406 telemetryConfig->frsky_vfas_cell_voltage = 0;
407 telemetryConfig->hottAlarmSoundInterval = 5;
408 telemetryConfig->pidValuesAsTelemetry = 0;
410 #endif
412 void resetBatteryConfig(batteryConfig_t *batteryConfig)
414 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
415 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
416 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
417 batteryConfig->vbatmaxcellvoltage = 43;
418 batteryConfig->vbatmincellvoltage = 33;
419 batteryConfig->vbatwarningcellvoltage = 35;
420 batteryConfig->vbathysteresis = 1;
421 batteryConfig->batteryMeterType = BATTERY_SENSOR_ADC;
422 batteryConfig->currentMeterOffset = 0;
423 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
424 batteryConfig->batteryCapacity = 0;
425 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
426 batteryConfig->batterynotpresentlevel = 55; // VBAT below 5.5 V will be igonored
427 batteryConfig->useVBatAlerts = true;
428 batteryConfig->useConsumptionAlerts = false;
429 batteryConfig->consumptionWarningPercentage = 10;
432 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
433 #define FIRST_PORT_INDEX 1
434 #define SECOND_PORT_INDEX 0
435 #else
436 #define FIRST_PORT_INDEX 0
437 #define SECOND_PORT_INDEX 1
438 #endif
440 void resetSerialConfig(serialConfig_t *serialConfig)
442 memset(serialConfig, 0, sizeof(serialConfig_t));
443 serialConfig->serial_update_rate_hz = 100;
444 serialConfig->reboot_character = 'R';
446 for (int index = 0; index < SERIAL_PORT_COUNT; index++) {
447 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
448 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
449 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
450 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
451 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
454 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
455 #if defined(USE_VCP)
456 // This allows MSP connection via USART & VCP so the board can be reconfigured.
457 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
458 #endif
461 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig)
463 rcControlsConfig->deadband = 0;
464 rcControlsConfig->yaw_deadband = 0;
465 rcControlsConfig->alt_hold_deadband = 40;
466 rcControlsConfig->alt_hold_fast_change = 1;
469 void resetMixerConfig(mixerConfig_t *mixerConfig)
471 mixerConfig->yaw_motor_direction = 1;
474 #ifdef USE_SERVOS
475 void resetServoMixerConfig(servoMixerConfig_t *servoMixerConfig)
477 servoMixerConfig->tri_unarmed_servo = 1;
478 servoMixerConfig->servo_lowpass_freq = 400;
479 servoMixerConfig->servo_lowpass_enable = 0;
481 #endif
483 #ifdef USE_MAX7456
484 void resetMax7456Config(vcdProfile_t *pVcdProfile)
486 pVcdProfile->video_system = VIDEO_SYSTEM_AUTO;
487 pVcdProfile->h_offset = 0;
488 pVcdProfile->v_offset = 0;
490 #endif
492 void resetStatusLedConfig(statusLedConfig_t *statusLedConfig)
494 for (int i = 0; i < LED_NUMBER; i++) {
495 statusLedConfig->ledTags[i] = IO_TAG_NONE;
498 #ifdef LED0
499 statusLedConfig->ledTags[0] = IO_TAG(LED0);
500 #endif
501 #ifdef LED1
502 statusLedConfig->ledTags[1] = IO_TAG(LED1);
503 #endif
504 #ifdef LED2
505 statusLedConfig->ledTags[2] = IO_TAG(LED2);
506 #endif
508 statusLedConfig->polarity = 0
509 #ifdef LED0_INVERTED
510 | BIT(0)
511 #endif
512 #ifdef LED1_INVERTED
513 | BIT(1)
514 #endif
515 #ifdef LED2_INVERTED
516 | BIT(2)
517 #endif
521 #ifdef USE_FLASHFS
522 void resetFlashConfig(flashConfig_t *flashConfig)
524 #ifdef M25P16_CS_PIN
525 flashConfig->csTag = IO_TAG(M25P16_CS_PIN);
526 #else
527 flashConfig->csTag = IO_TAG_NONE;
528 #endif
530 #endif
532 uint8_t getCurrentProfile(void)
534 return masterConfig.current_profile_index;
537 void setProfile(uint8_t profileIndex)
539 currentProfile = &masterConfig.profile[profileIndex];
540 currentControlRateProfileIndex = currentProfile->activeRateProfile;
541 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
544 uint8_t getCurrentControlRateProfile(void)
546 return currentControlRateProfileIndex;
549 static void setControlRateProfile(uint8_t profileIndex)
551 currentControlRateProfileIndex = profileIndex;
552 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
553 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
556 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex)
558 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
561 uint16_t getCurrentMinthrottle(void)
563 return motorConfig()->minthrottle;
567 void createDefaultConfig(master_t *config)
569 // Clear all configuration
570 memset(config, 0, sizeof(master_t));
572 uint32_t *featuresPtr = &config->enabledFeatures;
574 intFeatureClearAll(featuresPtr);
575 intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
576 #ifdef DEFAULT_FEATURES
577 intFeatureSet(DEFAULT_FEATURES, featuresPtr);
578 #endif
580 #ifdef USE_MAX7456
581 resetMax7456Config(&config->vcdProfile);
582 #endif
584 #ifdef OSD
585 intFeatureSet(FEATURE_OSD, featuresPtr);
586 osdResetConfig(&config->osdProfile);
587 #endif
589 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
590 // only enable the VBAT feature by default if the board has a voltage divider otherwise
591 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
592 intFeatureSet(FEATURE_VBAT, featuresPtr);
593 #endif
595 config->version = EEPROM_CONF_VERSION;
596 config->mixerConfig.mixerMode = MIXER_QUADX;
598 // global settings
599 config->current_profile_index = 0; // default profile
600 config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
601 config->imuConfig.dcm_ki = 0; // 0.003 * 10000
602 config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default
603 #ifdef STM32F10X
604 config->gyroConfig.gyro_sync_denom = 8;
605 config->pidConfig.pid_process_denom = 1;
606 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
607 config->gyroConfig.gyro_sync_denom = 1;
608 config->pidConfig.pid_process_denom = 4;
609 #else
610 config->gyroConfig.gyro_sync_denom = 4;
611 config->pidConfig.pid_process_denom = 2;
612 #endif
613 config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
614 config->gyroConfig.gyro_soft_lpf_hz = 90;
615 config->gyroConfig.gyro_soft_notch_hz_1 = 400;
616 config->gyroConfig.gyro_soft_notch_cutoff_1 = 300;
617 config->gyroConfig.gyro_soft_notch_hz_2 = 200;
618 config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
620 config->debug_mode = DEBUG_MODE;
621 config->task_statistics = true;
623 resetAccelerometerTrims(&config->accelerometerConfig.accZero);
625 config->gyroConfig.gyro_align = ALIGN_DEFAULT;
626 config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
627 config->compassConfig.mag_align = ALIGN_DEFAULT;
629 config->boardAlignment.rollDegrees = 0;
630 config->boardAlignment.pitchDegrees = 0;
631 config->boardAlignment.yawDegrees = 0;
632 config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
633 config->rcControlsConfig.yaw_control_direction = 1;
634 config->gyroConfig.gyroMovementCalibrationThreshold = 32;
636 // xxx_hardware: 0:default/autodetect, 1: disable
637 config->compassConfig.mag_hardware = 1;
639 config->barometerConfig.baro_hardware = 1;
641 resetBatteryConfig(&config->batteryConfig);
643 #if defined(USE_PWM) || defined(USE_PPM)
644 resetPpmConfig(&config->ppmConfig);
645 resetPwmConfig(&config->pwmConfig);
646 #endif
648 #ifdef TELEMETRY
649 resetTelemetryConfig(&config->telemetryConfig);
650 #endif
652 #ifdef USE_ADC
653 resetAdcConfig(&config->adcConfig);
654 #endif
656 #ifdef BEEPER
657 resetBeeperConfig(&config->beeperConfig);
658 #endif
660 #ifdef SONAR
661 resetSonarConfig(&config->sonarConfig);
662 #endif
664 #ifdef USE_SDCARD
665 intFeatureSet(FEATURE_SDCARD, featuresPtr);
666 resetsdcardConfig(&config->sdcardConfig);
667 #endif
669 #ifdef SERIALRX_PROVIDER
670 config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
671 #else
672 config->rxConfig.serialrx_provider = 0;
673 #endif
674 config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
675 config->rxConfig.sbus_inversion = 1;
676 config->rxConfig.spektrum_sat_bind = 0;
677 config->rxConfig.spektrum_sat_bind_autoreset = 1;
678 config->rxConfig.midrc = 1500;
679 config->rxConfig.mincheck = 1100;
680 config->rxConfig.maxcheck = 1900;
681 config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
682 config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
684 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
685 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &config->rxConfig.failsafe_channel_configurations[i];
686 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
687 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
690 config->rxConfig.rssi_channel = 0;
691 config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
692 config->rxConfig.rssi_ppm_invert = 0;
693 config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
694 config->rxConfig.rcInterpolationChannels = 0;
695 config->rxConfig.rcInterpolationInterval = 19;
696 config->rxConfig.fpvCamAngleDegrees = 0;
697 config->rxConfig.max_aux_channel = MAX_AUX_CHANNELS;
698 config->rxConfig.airModeActivateThreshold = 1350;
700 resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
702 #ifdef USE_PWM
703 config->pwmConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
704 #endif
706 config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
707 config->armingConfig.disarm_kill_switch = 1;
708 config->armingConfig.auto_disarm_delay = 5;
709 config->imuConfig.small_angle = 25;
711 config->airplaneConfig.fixedwing_althold_dir = 1;
713 // Motor/ESC/Servo
714 resetMixerConfig(&config->mixerConfig);
715 resetMotorConfig(&config->motorConfig);
716 #ifdef USE_SERVOS
717 resetServoMixerConfig(&config->servoMixerConfig);
718 resetServoConfig(&config->servoConfig);
719 #endif
720 resetFlight3DConfig(&config->flight3DConfig);
722 #ifdef LED_STRIP
723 resetLedStripConfig(&config->ledStripConfig);
724 #endif
726 #ifdef GPS
727 // gps/nav stuff
728 config->gpsConfig.provider = GPS_NMEA;
729 config->gpsConfig.sbasMode = SBAS_AUTO;
730 config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
731 config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
732 #endif
734 resetSerialConfig(&config->serialConfig);
736 resetProfile(&config->profile[0]);
738 resetRollAndPitchTrims(&config->accelerometerConfig.accelerometerTrims);
740 config->compassConfig.mag_declination = 0;
741 config->accelerometerConfig.acc_lpf_hz = 10.0f;
743 config->imuConfig.accDeadband.xy = 40;
744 config->imuConfig.accDeadband.z = 40;
745 config->imuConfig.acc_unarmedcal = 1;
747 #ifdef BARO
748 resetBarometerConfig(&config->barometerConfig);
749 #endif
751 // Radio
752 #ifdef RX_CHANNELS_TAER
753 parseRcChannels("TAER1234", &config->rxConfig);
754 #else
755 parseRcChannels("AETR1234", &config->rxConfig);
756 #endif
758 resetRcControlsConfig(&config->rcControlsConfig);
760 config->throttleCorrectionConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
761 config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
763 // Failsafe Variables
764 config->failsafeConfig.failsafe_delay = 10; // 1sec
765 config->failsafeConfig.failsafe_off_delay = 10; // 1sec
766 config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
767 config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
768 config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
769 config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
771 #ifdef USE_SERVOS
772 // servos
773 for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
774 config->servoProfile.servoConf[i].min = DEFAULT_SERVO_MIN;
775 config->servoProfile.servoConf[i].max = DEFAULT_SERVO_MAX;
776 config->servoProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
777 config->servoProfile.servoConf[i].rate = 100;
778 config->servoProfile.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
779 config->servoProfile.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
780 config->servoProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
783 // gimbal
784 config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
785 #endif
787 #ifdef GPS
788 resetGpsProfile(&config->gpsProfile);
789 #endif
791 // custom mixer. clear by defaults.
792 for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
793 config->customMotorMixer[i].throttle = 0.0f;
796 #ifdef VTX
797 config->vtx_band = 4; //Fatshark/Airwaves
798 config->vtx_channel = 1; //CH1
799 config->vtx_mode = 0; //CH+BAND mode
800 config->vtx_mhz = 5740; //F0
801 #endif
803 #ifdef TRANSPONDER
804 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
806 memcpy(config->transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
807 #endif
809 #ifdef BLACKBOX
810 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
811 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
812 config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
813 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
814 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
815 config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
816 #else
817 config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
818 #endif
820 config->blackboxConfig.rate_num = 1;
821 config->blackboxConfig.rate_denom = 1;
822 config->blackboxConfig.on_motor_test = 0; // default off
823 #endif // BLACKBOX
825 #ifdef SERIALRX_UART
826 if (featureConfigured(FEATURE_RX_SERIAL)) {
827 int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART);
828 if (serialIndex >= 0) {
829 config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL;
832 #endif
834 #ifdef USE_FLASHFS
835 resetFlashConfig(&config->flashConfig);
836 #endif
838 resetStatusLedConfig(&config->statusLedConfig);
840 /* merely to force a reset if the person inadvertently flashes the wrong target */
841 strncpy(config->boardIdentifier, TARGET_BOARD_IDENTIFIER, sizeof(TARGET_BOARD_IDENTIFIER));
843 #if defined(TARGET_CONFIG)
844 targetConfiguration(config);
845 #endif
847 // copy first profile into remaining profile
848 for (int i = 1; i < MAX_PROFILE_COUNT; i++) {
849 memcpy(&config->profile[i], &config->profile[0], sizeof(profile_t));
853 static void resetConf(void)
855 createDefaultConfig(&masterConfig);
857 setProfile(0);
859 #ifdef LED_STRIP
860 reevaluateLedConfig();
861 #endif
864 void activateControlRateConfig(void)
866 generateThrottleCurve(currentControlRateProfile, &masterConfig.motorConfig);
869 void activateConfig(void)
871 activateControlRateConfig();
873 resetAdjustmentStates();
875 useRcControlsConfig(
876 modeActivationProfile()->modeActivationConditions,
877 &masterConfig.motorConfig,
878 &currentProfile->pidProfile
881 #ifdef TELEMETRY
882 telemetryUseConfig(&masterConfig.telemetryConfig);
883 #endif
885 #ifdef GPS
886 gpsUseProfile(&masterConfig.gpsProfile);
887 gpsUsePIDs(&currentProfile->pidProfile);
888 #endif
890 useFailsafeConfig(&masterConfig.failsafeConfig);
891 setAccelerationTrims(&accelerometerConfig()->accZero);
892 setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
894 mixerUseConfigs(
895 &masterConfig.flight3DConfig,
896 &masterConfig.motorConfig,
897 &masterConfig.mixerConfig,
898 &masterConfig.airplaneConfig,
899 &masterConfig.rxConfig
902 #ifdef USE_SERVOS
903 servoUseConfigs(&masterConfig.servoMixerConfig, masterConfig.servoProfile.servoConf, &masterConfig.gimbalConfig);
904 #endif
907 imuConfigure(
908 &masterConfig.imuConfig,
909 &currentProfile->pidProfile,
910 throttleCorrectionConfig()->throttle_correction_angle
913 configureAltitudeHold(
914 &currentProfile->pidProfile,
915 &masterConfig.barometerConfig,
916 &masterConfig.rcControlsConfig,
917 &masterConfig.motorConfig
920 #ifdef BARO
921 useBarometerConfig(&masterConfig.barometerConfig);
922 #endif
925 void validateAndFixConfig(void)
927 if((motorConfig()->motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
928 motorConfig()->mincommand = 1000;
931 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
932 featureSet(DEFAULT_RX_FEATURE);
935 if (featureConfigured(FEATURE_RX_PPM)) {
936 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
939 if (featureConfigured(FEATURE_RX_MSP)) {
940 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
943 if (featureConfigured(FEATURE_RX_SERIAL)) {
944 featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
947 if (featureConfigured(FEATURE_RX_SPI)) {
948 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
951 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
952 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
953 #if defined(STM32F10X)
954 // rssi adc needs the same ports
955 featureClear(FEATURE_RSSI_ADC);
956 // current meter needs the same ports
957 if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
958 featureClear(FEATURE_CURRENT_METER);
960 #endif
962 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
963 // led strip needs the same ports
964 featureClear(FEATURE_LED_STRIP);
965 #endif
967 // software serial needs free PWM ports
968 featureClear(FEATURE_SOFTSERIAL);
971 #ifdef USE_SOFTSPI
972 if (featureConfigured(FEATURE_SOFTSPI)) {
973 featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL | FEATURE_VBAT);
974 #if defined(STM32F10X)
975 featureClear(FEATURE_LED_STRIP);
976 // rssi adc needs the same ports
977 featureClear(FEATURE_RSSI_ADC);
978 // current meter needs the same ports
979 if (batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
980 featureClear(FEATURE_CURRENT_METER);
982 #endif
984 #endif
986 #if defined(NAZE) && defined(SONAR)
987 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
988 featureClear(FEATURE_CURRENT_METER);
990 #endif
992 #if defined(OLIMEXINO) && defined(SONAR)
993 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && batteryConfig()->currentMeterType == CURRENT_SENSOR_ADC) {
994 featureClear(FEATURE_CURRENT_METER);
996 #endif
998 #if defined(CC3D) && defined(DISPLAY) && defined(USE_UART3)
999 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DASHBOARD)) {
1000 featureClear(FEATURE_DASHBOARD);
1002 #endif
1004 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
1005 // shared pin
1006 if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
1007 featureClear(FEATURE_SONAR);
1008 featureClear(FEATURE_SOFTSERIAL);
1009 featureClear(FEATURE_RSSI_ADC);
1011 #endif
1013 #if defined(COLIBRI_RACE)
1014 serialConfig()->portConfigs[0].functionMask = FUNCTION_MSP;
1015 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
1016 featureClear(FEATURE_RX_PARALLEL_PWM);
1017 featureClear(FEATURE_RX_MSP);
1018 featureSet(FEATURE_RX_PPM);
1020 #endif
1022 useRxConfig(&masterConfig.rxConfig);
1024 serialConfig_t *serialConfig = &masterConfig.serialConfig;
1026 if (!isSerialConfigValid(serialConfig)) {
1027 resetSerialConfig(serialConfig);
1030 validateAndFixGyroConfig();
1032 #if defined(TARGET_VALIDATECONFIG)
1033 targetValidateConfiguration(&masterConfig);
1034 #endif
1037 void validateAndFixGyroConfig(void)
1039 // Prevent invalid notch cutoff
1040 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
1041 gyroConfig()->gyro_soft_notch_hz_1 = 0;
1043 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
1044 gyroConfig()->gyro_soft_notch_hz_2 = 0;
1047 float samplingTime = 0.000125f;
1049 if (gyroConfig()->gyro_use_32khz) {
1050 #ifdef GYRO_SUPPORTS_32KHZ
1051 samplingTime = 0.00003125;
1052 // F1 and F3 can't handle high pid speed.
1053 #if defined(STM32F1)
1054 pidConfig()->pid_process_denom = constrain(pidConfig()->pid_process_denom, 16, 16);
1055 #endif
1056 #if defined(STM32F3)
1057 pidConfig()->pid_process_denom = constrain(pidConfig()->pid_process_denom, 4, 16);
1058 #endif
1059 #else
1060 gyroConfig()->gyro_use_32khz = false;
1061 #endif
1064 #if !defined(GYRO_USES_SPI) || !defined(USE_MPU_DATA_READY_SIGNAL)
1065 gyroConfig()->gyro_isr_update = false;
1066 #endif
1068 if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
1069 pidConfig()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
1070 gyroConfig()->gyro_sync_denom = 1;
1071 samplingTime = 0.001f;
1074 // check for looptime restrictions based on motor protocol. Motor times have safety margin
1075 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
1076 float motorUpdateRestriction;
1077 switch(motorConfig()->motorPwmProtocol) {
1078 case (PWM_TYPE_STANDARD):
1079 motorUpdateRestriction = 0.002f;
1080 break;
1081 case (PWM_TYPE_ONESHOT125):
1082 motorUpdateRestriction = 0.0005f;
1083 break;
1084 case (PWM_TYPE_ONESHOT42):
1085 motorUpdateRestriction = 0.0001f;
1086 break;
1087 case (PWM_TYPE_DSHOT150):
1088 motorUpdateRestriction = 0.000250f;
1089 break;
1090 case (PWM_TYPE_DSHOT300):
1091 motorUpdateRestriction = 0.0001f;
1092 break;
1093 default:
1094 motorUpdateRestriction = 0.00003125f;
1097 if(pidLooptime < motorUpdateRestriction)
1098 pidConfig()->pid_process_denom = motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom);
1100 // Prevent overriding the max rate of motors
1101 if(motorConfig()->useUnsyncedPwm && (motorConfig()->motorPwmProtocol <= PWM_TYPE_BRUSHED)) {
1102 uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
1104 if(motorConfig()->motorPwmRate > maxEscRate)
1105 motorConfig()->motorPwmRate = maxEscRate;
1109 void ensureEEPROMContainsValidData(void)
1111 if (isEEPROMContentValid()) {
1112 return;
1115 resetEEPROM();
1118 void resetEEPROM(void)
1120 resetConf();
1121 writeEEPROM();
1124 void saveConfigAndNotify(void)
1126 writeEEPROM();
1127 readEEPROM();
1128 beeperConfirmationBeeps(1);
1131 void changeProfile(uint8_t profileIndex)
1133 if (profileIndex >= MAX_PROFILE_COUNT) {
1134 profileIndex = MAX_PROFILE_COUNT - 1;
1136 masterConfig.current_profile_index = profileIndex;
1137 writeEEPROM();
1138 readEEPROM();
1139 beeperConfirmationBeeps(profileIndex + 1);
1142 void changeControlRateProfile(uint8_t profileIndex)
1144 if (profileIndex >= MAX_RATEPROFILES) {
1145 profileIndex = MAX_RATEPROFILES - 1;
1147 setControlRateProfile(profileIndex);
1148 activateControlRateConfig();
1151 void beeperOffSet(uint32_t mask)
1153 masterConfig.beeper_off_flags |= mask;
1156 void beeperOffSetAll(uint8_t beeperCount)
1158 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1161 void beeperOffClear(uint32_t mask)
1163 masterConfig.beeper_off_flags &= ~(mask);
1166 void beeperOffClearAll(void)
1168 masterConfig.beeper_off_flags = 0;
1171 uint32_t getBeeperOffMask(void)
1173 return masterConfig.beeper_off_flags;
1176 void setBeeperOffMask(uint32_t mask)
1178 masterConfig.beeper_off_flags = mask;
1181 uint32_t getPreferredBeeperOffMask(void)
1183 return masterConfig.preferred_beeper_off_flags;
1186 void setPreferredBeeperOffMask(uint32_t mask)
1188 masterConfig.preferred_beeper_off_flags = mask;