CF/BF - First cut of Current/Voltage/Battery cleanup.
[betaflight.git] / src / main / fc / config.c
blob42e7be6d4a919d39452c77e9b0c80db9dc515b8d
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_profile.h"
39 #include "config/feature.h"
40 #include "config/parameter_group.h"
41 #include "config/parameter_group_ids.h"
43 #include "drivers/accgyro.h"
44 #include "drivers/compass.h"
45 #include "drivers/io.h"
46 #include "drivers/light_led.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/sonar_hcsr04.h"
57 #include "drivers/sound_beeper.h"
58 #include "drivers/system.h"
59 #include "drivers/timer.h"
60 #include "drivers/vcd.h"
62 #include "fc/config.h"
63 #include "fc/controlrate_profile.h"
64 #include "fc/fc_core.h"
65 #include "fc/fc_rc.h"
66 #include "fc/rc_adjustments.h"
67 #include "fc/rc_controls.h"
68 #include "fc/runtime_config.h"
70 #include "flight/altitudehold.h"
71 #include "flight/failsafe.h"
72 #include "flight/imu.h"
73 #include "flight/mixer.h"
74 #include "flight/navigation.h"
75 #include "flight/pid.h"
76 #include "flight/servos.h"
78 #include "io/beeper.h"
79 #include "io/gimbal.h"
80 #include "io/gps.h"
81 #include "io/ledstrip.h"
82 #include "io/motors.h"
83 #include "io/osd.h"
84 #include "io/serial.h"
85 #include "io/servos.h"
86 #include "io/vtx.h"
88 #include "rx/rx.h"
89 #include "rx/rx_spi.h"
91 #include "sensors/acceleration.h"
92 #include "sensors/barometer.h"
93 #include "sensors/battery.h"
94 #include "sensors/boardalignment.h"
95 #include "sensors/compass.h"
96 #include "sensors/gyro.h"
97 #include "sensors/sensors.h"
99 #include "telemetry/telemetry.h"
101 pidProfile_t *currentPidProfile;
103 #ifndef DEFAULT_FEATURES
104 #define DEFAULT_FEATURES 0
105 #endif
106 #ifndef DEFAULT_RX_FEATURE
107 #define DEFAULT_RX_FEATURE FEATURE_RX_PARALLEL_PWM
108 #endif
109 #ifndef RX_SPI_DEFAULT_PROTOCOL
110 #define RX_SPI_DEFAULT_PROTOCOL 0
111 #endif
113 PG_REGISTER_WITH_RESET_TEMPLATE(featureConfig_t, featureConfig, PG_FEATURE_CONFIG, 0);
115 PG_RESET_TEMPLATE(featureConfig_t, featureConfig,
116 .enabledFeatures = DEFAULT_FEATURES | DEFAULT_RX_FEATURE | FEATURE_FAILSAFE
119 PG_REGISTER_WITH_RESET_TEMPLATE(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
121 PG_RESET_TEMPLATE(systemConfig_t, systemConfig,
122 .pidProfileIndex = 0,
123 .activeRateProfile = 0,
124 .debug_mode = DEBUG_MODE,
125 .task_statistics = true,
126 .name = { 0 }
129 #ifdef BEEPER
130 PG_REGISTER(beeperConfig_t, beeperConfig, PG_BEEPER_CONFIG, 0);
131 #endif
132 #ifdef USE_ADC
133 PG_REGISTER_WITH_RESET_FN(adcConfig_t, adcConfig, PG_ADC_CONFIG, 0);
134 #endif
135 #ifdef USE_PWM
136 PG_REGISTER_WITH_RESET_FN(pwmConfig_t, pwmConfig, PG_PWM_CONFIG, 0);
137 #endif
138 #ifdef USE_PPM
139 PG_REGISTER_WITH_RESET_FN(ppmConfig_t, ppmConfig, PG_PPM_CONFIG, 0);
140 #endif
141 PG_REGISTER_WITH_RESET_FN(statusLedConfig_t, statusLedConfig, PG_STATUS_LED_CONFIG, 0);
142 PG_REGISTER_WITH_RESET_FN(serialPinConfig_t, serialPinConfig, PG_SERIAL_PIN_CONFIG, 0);
144 #ifdef USE_FLASHFS
145 PG_REGISTER_WITH_RESET_TEMPLATE(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
146 #ifdef M25P16_CS_PIN
147 #define FLASH_CONFIG_CSTAG IO_TAG(M25P16_CS_PIN)
148 #else
149 #define FLASH_CONFIG_CSTAG IO_TAG_NONE
150 #endif
152 PG_RESET_TEMPLATE(flashConfig_t, flashConfig,
153 .csTag = FLASH_CONFIG_CSTAG
155 #endif // USE_FLASH_FS
157 #ifdef USE_SDCARD
158 PG_REGISTER_WITH_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig, PG_SDCARD_CONFIG, 0);
159 #if defined(SDCARD_DMA_CHANNEL_TX)
160 #define SDCARD_CONFIG_USE_DMA true
161 #else
162 #define SDCARD_CONFIG_USE_DMA false
163 #endif
164 PG_RESET_TEMPLATE(sdcardConfig_t, sdcardConfig,
165 .useDma = SDCARD_CONFIG_USE_DMA
167 #endif
169 // no template required since defaults are zero
170 PG_REGISTER(vcdProfile_t, vcdProfile, PG_VCD_CONFIG, 0);
172 #ifdef SONAR
173 void resetSonarConfig(sonarConfig_t *sonarConfig)
175 #if defined(SONAR_TRIGGER_PIN) && defined(SONAR_ECHO_PIN)
176 sonarConfig->triggerTag = IO_TAG(SONAR_TRIGGER_PIN);
177 sonarConfig->echoTag = IO_TAG(SONAR_ECHO_PIN);
178 #else
179 #error Sonar not defined for target
180 #endif
182 #endif
184 #ifdef USE_ADC
185 void pgResetFn_adcConfig(adcConfig_t *adcConfig)
187 #ifdef VBAT_ADC_PIN
188 adcConfig->vbat.enabled = true;
189 adcConfig->vbat.ioTag = IO_TAG(VBAT_ADC_PIN);
190 #endif
192 #ifdef EXTERNAL1_ADC_PIN
193 adcConfig->external1.enabled = true;
194 adcConfig->external1.ioTag = IO_TAG(EXTERNAL1_ADC_PIN);
195 #endif
197 #ifdef CURRENT_METER_ADC_PIN
198 adcConfig->currentMeter.enabled = true;
199 adcConfig->currentMeter.ioTag = IO_TAG(CURRENT_METER_ADC_PIN);
200 #endif
202 #ifdef RSSI_ADC_PIN
203 adcConfig->rssi.enabled = true;
204 adcConfig->rssi.ioTag = IO_TAG(RSSI_ADC_PIN);
205 #endif
208 #endif // USE_ADC
211 #if defined(USE_PWM) || defined(USE_PPM)
212 void pgResetFn_ppmConfig(ppmConfig_t *ppmConfig)
214 #ifdef PPM_PIN
215 ppmConfig->ioTag = IO_TAG(PPM_PIN);
216 #else
217 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
218 if (timerHardware[i].usageFlags & TIM_USE_PPM) {
219 ppmConfig->ioTag = timerHardware[i].tag;
220 return;
224 ppmConfig->ioTag = IO_TAG_NONE;
225 #endif
228 void pgResetFn_pwmConfig(pwmConfig_t *pwmConfig)
230 pwmConfig->inputFilteringMode = INPUT_FILTERING_DISABLED;
231 int inputIndex = 0;
232 for (int i = 0; i < USABLE_TIMER_CHANNEL_COUNT && inputIndex < PWM_INPUT_PORT_COUNT; i++) {
233 if (timerHardware[i].usageFlags & TIM_USE_PWM) {
234 pwmConfig->ioTags[inputIndex] = timerHardware[i].tag;
235 inputIndex++;
239 #endif
244 // Default pin (NONE).
245 // XXX Does this mess belong here???
246 #ifdef USE_UART1
247 # if !defined(UART1_RX_PIN)
248 # define UART1_RX_PIN NONE
249 # endif
250 # if !defined(UART1_TX_PIN)
251 # define UART1_TX_PIN NONE
252 # endif
253 #endif
255 #ifdef USE_UART2
256 # if !defined(UART2_RX_PIN)
257 # define UART2_RX_PIN NONE
258 # endif
259 # if !defined(UART2_TX_PIN)
260 # define UART2_TX_PIN NONE
261 # endif
262 #endif
264 #ifdef USE_UART3
265 # if !defined(UART3_RX_PIN)
266 # define UART3_RX_PIN NONE
267 # endif
268 # if !defined(UART3_TX_PIN)
269 # define UART3_TX_PIN NONE
270 # endif
271 #endif
273 #ifdef USE_UART4
274 # if !defined(UART4_RX_PIN)
275 # define UART4_RX_PIN NONE
276 # endif
277 # if !defined(UART4_TX_PIN)
278 # define UART4_TX_PIN NONE
279 # endif
280 #endif
282 #ifdef USE_UART5
283 # if !defined(UART5_RX_PIN)
284 # define UART5_RX_PIN NONE
285 # endif
286 # if !defined(UART5_TX_PIN)
287 # define UART5_TX_PIN NONE
288 # endif
289 #endif
291 #ifdef USE_UART6
292 # if !defined(UART6_RX_PIN)
293 # define UART6_RX_PIN NONE
294 # endif
295 # if !defined(UART6_TX_PIN)
296 # define UART6_TX_PIN NONE
297 # endif
298 #endif
300 #ifdef USE_UART7
301 # if !defined(UART7_RX_PIN)
302 # define UART7_RX_PIN NONE
303 # endif
304 # if !defined(UART7_TX_PIN)
305 # define UART7_TX_PIN NONE
306 # endif
307 #endif
309 #ifdef USE_UART8
310 # if !defined(UART8_RX_PIN)
311 # define UART8_RX_PIN NONE
312 # endif
313 # if !defined(UART8_TX_PIN)
314 # define UART8_TX_PIN NONE
315 # endif
316 #endif
318 #ifdef USE_SOFTSERIAL1
319 # if !defined(SOFTSERIAL1_RX_PIN)
320 # define SOFTSERIAL1_RX_PIN NONE
321 # endif
322 # if !defined(SOFTSERIAL1_TX_PIN)
323 # define SOFTSERIAL1_TX_PIN NONE
324 # endif
325 #endif
327 #ifdef USE_SOFTSERIAL2
328 # if !defined(SOFTSERIAL2_RX_PIN)
329 # define SOFTSERIAL2_RX_PIN NONE
330 # endif
331 # if !defined(SOFTSERIAL2_TX_PIN)
332 # define SOFTSERIAL2_TX_PIN NONE
333 # endif
334 #endif
336 void pgResetFn_serialPinConfig(serialPinConfig_t *serialPinConfig)
338 for (int port = 0 ; port < SERIAL_PORT_MAX_INDEX ; port++) {
339 serialPinConfig->ioTagRx[port] = IO_TAG(NONE);
340 serialPinConfig->ioTagTx[port] = IO_TAG(NONE);
343 for (int index = 0 ; index < SERIAL_PORT_COUNT ; index++) {
344 switch (serialPortIdentifiers[index]) {
345 case SERIAL_PORT_USART1:
346 #ifdef USE_UART1
347 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_RX_PIN);
348 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART1)] = IO_TAG(UART1_TX_PIN);
349 #endif
350 break;
351 case SERIAL_PORT_USART2:
352 #ifdef USE_UART2
353 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_RX_PIN);
354 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART2)] = IO_TAG(UART2_TX_PIN);
355 #endif
356 break;
357 case SERIAL_PORT_USART3:
358 #ifdef USE_UART3
359 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_RX_PIN);
360 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART3)] = IO_TAG(UART3_TX_PIN);
361 #endif
362 break;
363 case SERIAL_PORT_UART4:
364 #ifdef USE_UART4
365 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_RX_PIN);
366 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_UART4)] = IO_TAG(UART4_TX_PIN);
367 #endif
368 break;
369 case SERIAL_PORT_UART5:
370 #ifdef USE_UART5
371 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_RX_PIN);
372 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_UART5)] = IO_TAG(UART5_TX_PIN);
373 #endif
374 break;
375 case SERIAL_PORT_USART6:
376 #ifdef USE_UART6
377 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_RX_PIN);
378 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART6)] = IO_TAG(UART6_TX_PIN);
379 #endif
380 break;
381 case SERIAL_PORT_USART7:
382 #ifdef USE_UART7
383 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_RX_PIN);
384 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART7)] = IO_TAG(UART7_TX_PIN);
385 #endif
386 break;
387 case SERIAL_PORT_USART8:
388 #ifdef USE_UART8
389 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_RX_PIN);
390 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_USART8)] = IO_TAG(UART8_TX_PIN);
391 #endif
392 break;
393 case SERIAL_PORT_SOFTSERIAL1:
394 #ifdef USE_SOFTSERIAL1
395 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_RX_PIN);
396 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_SOFTSERIAL1)] = IO_TAG(SOFTSERIAL1_TX_PIN);
397 #endif
398 break;
399 case SERIAL_PORT_SOFTSERIAL2:
400 #ifdef USE_SOFTSERIAL2
401 serialPinConfig->ioTagRx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_RX_PIN);
402 serialPinConfig->ioTagTx[SERIAL_PORT_IDENTIFIER_TO_RESOURCE_INDEX(SERIAL_PORT_SOFTSERIAL2)] = IO_TAG(SOFTSERIAL2_TX_PIN);
403 #endif
404 break;
405 case SERIAL_PORT_USB_VCP:
406 break;
407 case SERIAL_PORT_NONE:
408 break;
413 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
414 #define FIRST_PORT_INDEX 1
415 #define SECOND_PORT_INDEX 0
416 #else
417 #define FIRST_PORT_INDEX 0
418 #define SECOND_PORT_INDEX 1
419 #endif
421 void pgResetFn_statusLedConfig(statusLedConfig_t *statusLedConfig)
423 for (int i = 0; i < LED_NUMBER; i++) {
424 statusLedConfig->ledTags[i] = IO_TAG_NONE;
427 #ifdef LED0
428 statusLedConfig->ledTags[0] = IO_TAG(LED0);
429 #endif
430 #ifdef LED1
431 statusLedConfig->ledTags[1] = IO_TAG(LED1);
432 #endif
433 #ifdef LED2
434 statusLedConfig->ledTags[2] = IO_TAG(LED2);
435 #endif
437 statusLedConfig->polarity = 0
438 #ifdef LED0_INVERTED
439 | BIT(0)
440 #endif
441 #ifdef LED1_INVERTED
442 | BIT(1)
443 #endif
444 #ifdef LED2_INVERTED
445 | BIT(2)
446 #endif
450 uint8_t getCurrentPidProfileIndex(void)
452 return systemConfig()->pidProfileIndex;
455 static void setPidProfile(uint8_t pidProfileIndex)
457 if (pidProfileIndex < MAX_PROFILE_COUNT) {
458 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
459 currentPidProfile = pidProfilesMutable(pidProfileIndex);
460 pidInit(currentPidProfile); // re-initialise pid controller to re-initialise filters and config
464 uint8_t getCurrentControlRateProfileIndex(void)
466 return systemConfigMutable()->activeRateProfile;
469 uint16_t getCurrentMinthrottle(void)
471 return motorConfig()->minthrottle;
474 #ifndef USE_PARAMETER_GROUPS
475 void createDefaultConfig(master_t *config)
477 // Clear all configuration
478 memset(config, 0, sizeof(master_t));
480 uint32_t *featuresPtr = &config->featureConfig.enabledFeatures;
482 intFeatureClearAll(featuresPtr);
483 intFeatureSet(DEFAULT_RX_FEATURE | FEATURE_FAILSAFE , featuresPtr);
485 #ifdef DEFAULT_FEATURES
486 intFeatureSet(DEFAULT_FEATURES, featuresPtr);
487 #endif
489 #ifndef USE_PARAMETER_GROUPS
490 #ifdef USE_MSP_DISPLAYPORT
491 resetDisplayPortProfile(&config->displayPortProfileMsp);
492 #endif
493 #ifdef USE_MAX7456
494 resetDisplayPortProfile(&config->displayPortProfileMax7456);
495 #endif
497 #ifdef USE_MAX7456
498 resetMax7456Config(&config->vcdProfile);
499 #endif
501 #ifdef OSD
502 osdResetConfig(&config->osdConfig);
503 #endif
504 #endif // USE_PARAMETER_GROUPS
506 config->version = EEPROM_CONF_VERSION;
508 // global settings
509 #ifndef USE_PARAMETER_GROUPS
510 config->systemConfig.pidProfileIndex = 0; // default profile
511 config->systemConfig.debug_mode = DEBUG_MODE;
512 config->systemConfig.task_statistics = true;
513 #endif
516 #ifndef USE_PARAMETER_GROUPS
517 config->imuConfig.dcm_kp = 2500; // 1.0 * 10000
518 config->imuConfig.dcm_ki = 0; // 0.003 * 10000
519 config->imuConfig.small_angle = 25;
520 config->imuConfig.accDeadband.xy = 40;
521 config->imuConfig.accDeadband.z = 40;
522 config->imuConfig.acc_unarmedcal = 1;
523 #endif
524 #ifndef USE_PARAMETER_GROUPS
525 config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default
526 #ifdef STM32F10X
527 config->gyroConfig.gyro_sync_denom = 8;
528 config->pidConfig.pid_process_denom = 1;
529 #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689)
530 config->gyroConfig.gyro_sync_denom = 1;
531 config->pidConfig.pid_process_denom = 4;
532 #else
533 config->gyroConfig.gyro_sync_denom = 4;
534 config->pidConfig.pid_process_denom = 2;
535 #endif
536 config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1;
537 config->gyroConfig.gyro_soft_lpf_hz = 90;
538 config->gyroConfig.gyro_soft_notch_hz_1 = 400;
539 config->gyroConfig.gyro_soft_notch_cutoff_1 = 300;
540 config->gyroConfig.gyro_soft_notch_hz_2 = 200;
541 config->gyroConfig.gyro_soft_notch_cutoff_2 = 100;
542 config->gyroConfig.gyro_align = ALIGN_DEFAULT;
543 config->gyroConfig.gyroMovementCalibrationThreshold = 48;
544 #endif
546 #ifndef USE_PARAMETER_GROUPS
547 resetCompassConfig(&config->compassConfig);
548 #endif
550 #ifndef USE_PARAMETER_GROUPS
551 resetAccelerometerTrims(&config->accelerometerConfig.accZero);
552 config->accelerometerConfig.acc_align = ALIGN_DEFAULT;
553 config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
554 resetRollAndPitchTrims(&config->accelerometerConfig.accelerometerTrims);
555 config->accelerometerConfig.acc_lpf_hz = 10.0f;
556 #endif
557 #ifndef USE_PARAMETER_GROUPS
558 config->boardAlignment.rollDegrees = 0;
559 config->boardAlignment.pitchDegrees = 0;
560 config->boardAlignment.yawDegrees = 0;
561 #endif
562 config->rcControlsConfig.yaw_control_direction = 1;
564 // xxx_hardware: 0:default/autodetect, 1: disable
565 config->compassConfig.mag_hardware = 1;
567 config->barometerConfig.baro_hardware = 1;
569 #ifndef USE_PARAMETER_GROUPS
570 resetBatteryConfig(&config->batteryConfig);
572 #if defined(USE_PWM) || defined(USE_PPM)
573 resetPpmConfig(&config->ppmConfig);
574 resetPwmConfig(&config->pwmConfig);
575 #endif
576 #ifdef USE_PWM
577 config->pwmConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
578 #endif
580 #ifdef TELEMETRY
581 resetTelemetryConfig(&config->telemetryConfig);
582 #endif
583 #endif
585 #ifndef USE_PARAMETER_GROUPS
586 #ifdef USE_ADC
587 resetAdcConfig(&config->adcConfig);
588 #endif
590 #ifdef BEEPER
591 resetBeeperDevConfig(&config->beeperDevConfig);
592 #endif
593 #endif
595 #ifdef SONAR
596 resetSonarConfig(&config->sonarConfig);
597 #endif
599 #ifndef USE_PARAMETER_GROUPS
600 #ifdef USE_SDCARD
601 intFeatureSet(FEATURE_SDCARD, featuresPtr);
602 resetsdcardConfig(&config->sdcardConfig);
603 #endif
605 #ifdef SERIALRX_PROVIDER
606 config->rxConfig.serialrx_provider = SERIALRX_PROVIDER;
607 #else
608 config->rxConfig.serialrx_provider = 0;
609 #endif
610 config->rxConfig.halfDuplex = 0;
611 config->rxConfig.rx_spi_protocol = RX_SPI_DEFAULT_PROTOCOL;
612 config->rxConfig.sbus_inversion = 1;
613 config->rxConfig.spektrum_sat_bind = 0;
614 config->rxConfig.spektrum_sat_bind_autoreset = 1;
615 config->rxConfig.midrc = 1500;
616 config->rxConfig.mincheck = 1100;
617 config->rxConfig.maxcheck = 1900;
618 config->rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
619 config->rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
621 for (int i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
622 rxFailsafeChannelConfig_t *channelFailsafeConfig = &config->rxConfig.failsafe_channel_configurations[i];
623 channelFailsafeConfig->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
624 channelFailsafeConfig->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(config->rxConfig.midrc);
627 config->rxConfig.rssi_channel = 0;
628 config->rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
629 config->rxConfig.rssi_invert = 0;
630 config->rxConfig.rcInterpolation = RC_SMOOTHING_AUTO;
631 config->rxConfig.rcInterpolationChannels = 0;
632 config->rxConfig.rcInterpolationInterval = 19;
633 config->rxConfig.fpvCamAngleDegrees = 0;
634 config->rxConfig.max_aux_channel = DEFAULT_AUX_CHANNEL_COUNT;
635 config->rxConfig.airModeActivateThreshold = 1350;
637 resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges);
638 #endif
640 #ifndef USE_PARAMETER_GROUPS
641 config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
642 config->armingConfig.disarm_kill_switch = 1;
643 config->armingConfig.auto_disarm_delay = 5;
645 config->airplaneConfig.fixedwing_althold_dir = 1;
647 // Motor/ESC/Servo
648 resetMixerConfig(&config->mixerConfig);
649 resetMotorConfig(&config->motorConfig);
650 #ifdef USE_SERVOS
651 resetServoConfig(&config->servoConfig);
652 #endif
653 resetFlight3DConfig(&config->flight3DConfig);
655 #ifdef LED_STRIP
656 resetLedStripConfig(&config->ledStripConfig);
657 #endif
659 #ifdef GPS
660 // gps/nav stuff
661 config->gpsConfig.provider = GPS_NMEA;
662 config->gpsConfig.sbasMode = SBAS_AUTO;
663 config->gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
664 config->gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
665 #endif
667 resetSerialPinConfig(&config->serialPinConfig);
669 resetSerialConfig(&config->serialConfig);
671 for (int ii = 0; ii < MAX_PROFILE_COUNT; ++ii) {
672 resetProfile(&config->profile[ii]);
674 for (int ii = 0; ii < CONTROL_RATE_PROFILE_COUNT; ++ii) {
675 resetControlRateProfile(&config->controlRateProfile[ii]);
677 #endif
679 config->compassConfig.mag_declination = 0;
681 #ifdef BARO
682 #ifndef USE_PARAMETER_GROUPS
683 resetBarometerConfig(&config->barometerConfig);
684 #endif
685 #endif
687 // Radio
688 #ifdef RX_CHANNELS_TAER
689 parseRcChannels("TAER1234", &config->rxConfig);
690 #else
691 parseRcChannels("AETR1234", &config->rxConfig);
692 #endif
694 #ifndef USE_PARAMETER_GROUPS
695 resetRcControlsConfig(&config->rcControlsConfig);
697 config->throttleCorrectionConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
698 config->throttleCorrectionConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
700 // Failsafe Variables
701 config->failsafeConfig.failsafe_delay = 10; // 1sec
702 config->failsafeConfig.failsafe_off_delay = 10; // 1sec
703 config->failsafeConfig.failsafe_throttle = 1000; // default throttle off.
704 config->failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
705 config->failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
706 config->failsafeConfig.failsafe_procedure = FAILSAFE_PROCEDURE_DROP_IT;// default full failsafe procedure is 0: auto-landing
707 #endif
709 #ifdef USE_SERVOS
710 #ifndef USE_PARAMETER_GROUPS
711 // servos
712 for (int i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
713 config->servoProfile.servoConf[i].min = DEFAULT_SERVO_MIN;
714 config->servoProfile.servoConf[i].max = DEFAULT_SERVO_MAX;
715 config->servoProfile.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
716 config->servoProfile.servoConf[i].rate = 100;
717 config->servoProfile.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
718 config->servoProfile.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
719 config->servoProfile.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
722 // gimbal
723 config->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
724 #endif
726 // Channel forwarding;
727 config->servoConfig.channelForwardingStartChannel = AUX1;
728 #endif
730 #ifndef USE_PARAMETER_GROUPS
731 #ifdef GPS
732 resetNavigationConfig(&config->navigationConfig);
733 #endif
734 #endif
736 // custom mixer. clear by defaults.
737 for (int i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
738 config->customMotorMixer[i].throttle = 0.0f;
741 #ifndef USE_PARAMETER_GROUPS
742 #ifdef VTX
743 config->vtxConfig.vtx_band = 4; //Fatshark/Airwaves
744 config->vtxConfig.vtx_channel = 1; //CH1
745 config->vtxConfig.vtx_mode = 0; //CH+BAND mode
746 config->vtxConfig.vtx_mhz = 5740; //F0
747 #endif
748 #endif
750 #ifdef TRANSPONDER
751 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
753 memcpy(config->transponderConfig.data, &defaultTransponderData, sizeof(defaultTransponderData));
754 #endif
756 #ifndef USE_PARAMETER_GROUPS
757 #ifdef BLACKBOX
758 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
759 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
760 config->blackboxConfig.device = BLACKBOX_DEVICE_FLASH;
761 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
762 intFeatureSet(FEATURE_BLACKBOX, featuresPtr);
763 config->blackboxConfig.device = BLACKBOX_DEVICE_SDCARD;
764 #else
765 config->blackboxConfig.device = BLACKBOX_DEVICE_SERIAL;
766 #endif
767 config->blackboxConfig.rate_num = 1;
768 config->blackboxConfig.rate_denom = 1;
769 config->blackboxConfig.on_motor_test = 0; // default off
770 #endif // BLACKBOX
771 #endif
773 #ifdef SERIALRX_UART
774 if (featureConfigured(FEATURE_RX_SERIAL)) {
775 int serialIndex = findSerialPortIndexByIdentifier(SERIALRX_UART);
776 if (serialIndex >= 0) {
777 config->serialConfig.portConfigs[serialIndex].functionMask = FUNCTION_RX_SERIAL;
780 #endif
782 #ifndef USE_PARAMETER_GROUPS
783 #ifdef USE_FLASHFS
784 resetFlashConfig(&config->flashConfig);
785 #endif
787 resetStatusLedConfig(&config->statusLedConfig);
788 #endif
790 #if defined(TARGET_CONFIG)
791 targetConfiguration(config);
792 #endif
794 #endif
796 void resetConfigs(void)
798 #ifndef USE_PARAMETER_GROUPS
799 createDefaultConfig(&masterConfig);
800 #endif
801 pgResetAll(MAX_PROFILE_COUNT);
802 pgActivateProfile(0);
804 setPidProfile(0);
805 setControlRateProfile(0);
807 #ifdef LED_STRIP
808 reevaluateLedConfig();
809 #endif
812 void activateConfig(void)
814 generateThrottleCurve();
816 resetAdjustmentStates();
818 useRcControlsConfig(modeActivationConditions(0), currentPidProfile);
819 useAdjustmentConfig(currentPidProfile);
821 #ifdef GPS
822 gpsUsePIDs(currentPidProfile);
823 #endif
825 failsafeReset();
826 setAccelerationTrims(&accelerometerConfigMutable()->accZero);
827 setAccelerationFilter(accelerometerConfig()->acc_lpf_hz);
829 imuConfigure(throttleCorrectionConfig()->throttle_correction_angle);
831 configureAltitudeHold(currentPidProfile);
834 void validateAndFixConfig(void)
836 if((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_BRUSHED) && (motorConfig()->mincommand < 1000)){
837 motorConfigMutable()->mincommand = 1000;
840 if ((motorConfig()->dev.motorPwmProtocol == PWM_TYPE_STANDARD) && (motorConfig()->dev.motorPwmRate > BRUSHLESS_MOTORS_PWM_RATE)) {
841 motorConfigMutable()->dev.motorPwmRate = BRUSHLESS_MOTORS_PWM_RATE;
844 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP) || featureConfigured(FEATURE_RX_SPI))) {
845 featureSet(DEFAULT_RX_FEATURE);
848 if (featureConfigured(FEATURE_RX_PPM)) {
849 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_SPI);
852 if (featureConfigured(FEATURE_RX_MSP)) {
853 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_SPI);
856 if (featureConfigured(FEATURE_RX_SERIAL)) {
857 featureClear(FEATURE_RX_PARALLEL_PWM | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
860 if (featureConfigured(FEATURE_RX_SPI)) {
861 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_PARALLEL_PWM | FEATURE_RX_PPM | FEATURE_RX_MSP);
864 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
865 featureClear(FEATURE_RX_SERIAL | FEATURE_RX_MSP | FEATURE_RX_PPM | FEATURE_RX_SPI);
866 #if defined(STM32F10X)
867 // rssi adc needs the same ports
868 featureClear(FEATURE_RSSI_ADC);
869 // current meter needs the same ports
870 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
871 batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
873 #endif
874 // software serial needs free PWM ports
875 featureClear(FEATURE_SOFTSERIAL);
878 #ifdef USE_SOFTSPI
879 if (featureConfigured(FEATURE_SOFTSPI)) {
880 featureClear(FEATURE_RX_PPM | FEATURE_RX_PARALLEL_PWM | FEATURE_SOFTSERIAL);
881 batteryConfigMutable()->voltageMeterSource = VOLTAGE_METER_NONE;
882 #if defined(STM32F10X)
883 featureClear(FEATURE_LED_STRIP);
884 // rssi adc needs the same ports
885 featureClear(FEATURE_RSSI_ADC);
886 // current meter needs the same ports
887 if (batteryConfig()->currentMeterSource == CURRENT_METER_ADC) {
888 batteryConfigMutable()->currentMeterSource = CURRENT_METER_NONE;
890 #endif
892 #endif
894 #ifndef USE_PARAMETER_GROUPS
895 serialConfig_t *serialConfig = &masterConfig.serialConfig;
896 if (!isSerialConfigValid(serialConfig)) {
897 resetSerialConfig(serialConfig);
899 #else
900 if (!isSerialConfigValid(serialConfig())) {
901 pgResetFn_serialConfig(serialConfigMutable());
903 #endif
905 // Prevent invalid notch cutoff
906 if (currentPidProfile->dterm_notch_cutoff >= currentPidProfile->dterm_notch_hz) {
907 currentPidProfile->dterm_notch_hz = 0;
910 validateAndFixGyroConfig();
912 #if defined(TARGET_VALIDATECONFIG)
913 targetValidateConfiguration();
914 #endif
917 void validateAndFixGyroConfig(void)
919 // Prevent invalid notch cutoff
920 if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
921 gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
923 if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
924 gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
927 float samplingTime = 0.000125f;
929 if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) {
930 pidConfigMutable()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed
931 gyroConfigMutable()->gyro_sync_denom = 1;
932 gyroConfigMutable()->gyro_use_32khz = false;
933 samplingTime = 0.001f;
936 if (gyroConfig()->gyro_use_32khz) {
937 samplingTime = 0.00003125;
938 // F1 and F3 can't handle high sample speed.
939 #if defined(STM32F1)
940 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 16);
941 #elif defined(STM32F3)
942 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 4);
943 #endif
944 } else {
945 #if defined(STM32F1)
946 gyroConfigMutable()->gyro_sync_denom = MAX(gyroConfig()->gyro_sync_denom, 3);
947 #endif
950 #if !defined(GYRO_USES_SPI) || !defined(USE_MPU_DATA_READY_SIGNAL)
951 gyroConfigMutable()->gyro_isr_update = false;
952 #endif
954 // check for looptime restrictions based on motor protocol. Motor times have safety margin
955 const float pidLooptime = samplingTime * gyroConfig()->gyro_sync_denom * pidConfig()->pid_process_denom;
956 float motorUpdateRestriction;
957 switch(motorConfig()->dev.motorPwmProtocol) {
958 case (PWM_TYPE_STANDARD):
959 motorUpdateRestriction = 1.0f/BRUSHLESS_MOTORS_PWM_RATE;
960 break;
961 case (PWM_TYPE_ONESHOT125):
962 motorUpdateRestriction = 0.0005f;
963 break;
964 case (PWM_TYPE_ONESHOT42):
965 motorUpdateRestriction = 0.0001f;
966 break;
967 #ifdef USE_DSHOT
968 case (PWM_TYPE_DSHOT150):
969 motorUpdateRestriction = 0.000250f;
970 break;
971 case (PWM_TYPE_DSHOT300):
972 motorUpdateRestriction = 0.0001f;
973 break;
974 #endif
975 default:
976 motorUpdateRestriction = 0.00003125f;
979 if (pidLooptime < motorUpdateRestriction) {
980 const uint8_t maxPidProcessDenom = constrain(motorUpdateRestriction / (samplingTime * gyroConfig()->gyro_sync_denom), 1, MAX_PID_PROCESS_DENOM);
981 pidConfigMutable()->pid_process_denom = MIN(pidConfigMutable()->pid_process_denom, maxPidProcessDenom);
984 // Prevent overriding the max rate of motors
985 if (motorConfig()->dev.useUnsyncedPwm && (motorConfig()->dev.motorPwmProtocol <= PWM_TYPE_BRUSHED) && motorConfig()->dev.motorPwmProtocol != PWM_TYPE_STANDARD) {
986 uint32_t maxEscRate = lrintf(1.0f / motorUpdateRestriction);
988 if(motorConfig()->dev.motorPwmRate > maxEscRate)
989 motorConfigMutable()->dev.motorPwmRate = maxEscRate;
993 void readEEPROM(void)
995 suspendRxSignal();
997 // Sanity check, read flash
998 if (!loadEEPROM()) {
999 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
1002 if (systemConfig()->activeRateProfile >= CONTROL_RATE_PROFILE_COUNT) {// sanity check
1003 systemConfigMutable()->activeRateProfile = 0;
1005 setControlRateProfile(systemConfig()->activeRateProfile);
1007 if (systemConfig()->pidProfileIndex >= MAX_PROFILE_COUNT) {// sanity check
1008 systemConfigMutable()->pidProfileIndex = 0;
1010 setPidProfile(systemConfig()->pidProfileIndex);
1012 validateAndFixConfig();
1013 activateConfig();
1015 resumeRxSignal();
1018 void writeEEPROM(void)
1020 suspendRxSignal();
1022 writeConfigToEEPROM();
1024 resumeRxSignal();
1027 void resetEEPROM(void)
1029 resetConfigs();
1030 writeEEPROM();
1033 void ensureEEPROMContainsValidData(void)
1035 if (isEEPROMContentValid()) {
1036 return;
1038 resetEEPROM();
1041 void saveConfigAndNotify(void)
1043 writeEEPROM();
1044 readEEPROM();
1045 beeperConfirmationBeeps(1);
1048 void changePidProfile(uint8_t pidProfileIndex)
1050 if (pidProfileIndex >= MAX_PROFILE_COUNT) {
1051 pidProfileIndex = MAX_PROFILE_COUNT - 1;
1053 systemConfigMutable()->pidProfileIndex = pidProfileIndex;
1054 currentPidProfile = pidProfilesMutable(pidProfileIndex);
1055 beeperConfirmationBeeps(pidProfileIndex + 1);
1058 void beeperOffSet(uint32_t mask)
1060 beeperConfigMutable()->beeper_off_flags |= mask;
1063 void beeperOffSetAll(uint8_t beeperCount)
1065 beeperConfigMutable()->beeper_off_flags = (1 << beeperCount) -1;
1068 void beeperOffClear(uint32_t mask)
1070 beeperConfigMutable()->beeper_off_flags &= ~(mask);
1073 void beeperOffClearAll(void)
1075 beeperConfigMutable()->beeper_off_flags = 0;
1078 uint32_t getBeeperOffMask(void)
1080 return beeperConfig()->beeper_off_flags;
1083 void setBeeperOffMask(uint32_t mask)
1085 beeperConfigMutable()->beeper_off_flags = mask;
1088 uint32_t getPreferredBeeperOffMask(void)
1090 return beeperConfig()->preferred_beeper_off_flags;
1093 void setPreferredBeeperOffMask(uint32_t mask)
1095 beeperConfigMutable()->preferred_beeper_off_flags = mask;