Optional SUPER EXPO for yaw // Optional always Iterm reset // Rework Iterm reset
[betaflight.git] / src / main / config / config.c
blob822e95515fc00b95ceb2edf52fcccdb1a99b339c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <string.h>
22 #include "platform.h"
24 #include "build_config.h"
26 #include "common/color.h"
27 #include "common/axis.h"
28 #include "common/maths.h"
29 #include "common/filter.h"
31 #include "drivers/sensor.h"
32 #include "drivers/accgyro.h"
33 #include "drivers/compass.h"
34 #include "drivers/system.h"
35 #include "drivers/gpio.h"
36 #include "drivers/timer.h"
37 #include "drivers/pwm_rx.h"
38 #include "drivers/serial.h"
39 #include "drivers/gyro_sync.h"
41 #include "sensors/sensors.h"
42 #include "sensors/gyro.h"
43 #include "sensors/compass.h"
44 #include "sensors/acceleration.h"
45 #include "sensors/barometer.h"
46 #include "sensors/boardalignment.h"
47 #include "sensors/battery.h"
49 #include "io/beeper.h"
50 #include "io/serial.h"
51 #include "io/gimbal.h"
52 #include "io/escservo.h"
53 #include "io/rc_controls.h"
54 #include "io/rc_curves.h"
55 #include "io/ledstrip.h"
56 #include "io/gps.h"
58 #include "rx/rx.h"
60 #include "telemetry/telemetry.h"
62 #include "flight/mixer.h"
63 #include "flight/pid.h"
64 #include "flight/imu.h"
65 #include "flight/failsafe.h"
66 #include "flight/altitudehold.h"
67 #include "flight/navigation.h"
69 #include "config/runtime_config.h"
70 #include "config/config.h"
72 #include "config/config_profile.h"
73 #include "config/config_master.h"
75 #define BRUSHED_MOTORS_PWM_RATE 16000
76 #define BRUSHLESS_MOTORS_PWM_RATE 400
78 void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
80 #if !defined(FLASH_SIZE)
81 #error "Flash size not defined for target. (specify in KB)"
82 #endif
85 #ifndef FLASH_PAGE_SIZE
86 #ifdef STM32F303xC
87 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
88 #endif
90 #ifdef STM32F10X_MD
91 #define FLASH_PAGE_SIZE ((uint16_t)0x400)
92 #endif
94 #ifdef STM32F10X_HD
95 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
96 #endif
97 #endif
99 #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
100 #ifdef STM32F10X_MD
101 #define FLASH_PAGE_COUNT 128
102 #endif
104 #ifdef STM32F10X_HD
105 #define FLASH_PAGE_COUNT 128
106 #endif
107 #endif
109 #if defined(FLASH_SIZE)
110 #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
111 #endif
113 #if !defined(FLASH_PAGE_SIZE)
114 #error "Flash page size not defined for target."
115 #endif
117 #if !defined(FLASH_PAGE_COUNT)
118 #error "Flash page count not defined for target."
119 #endif
121 #if FLASH_SIZE <= 128
122 #define FLASH_TO_RESERVE_FOR_CONFIG 0x800
123 #else
124 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
125 #endif
127 // use the last flash pages for storage
128 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
130 master_t masterConfig; // master config struct with data independent from profiles
131 profile_t *currentProfile;
132 static uint32_t activeFeaturesLatch = 0;
134 static uint8_t currentControlRateProfileIndex = 0;
135 controlRateConfig_t *currentControlRateProfile;
137 static const uint8_t EEPROM_CONF_VERSION = 133;
139 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
141 accelerometerTrims->values.pitch = 0;
142 accelerometerTrims->values.roll = 0;
143 accelerometerTrims->values.yaw = 0;
146 static void resetPidProfile(pidProfile_t *pidProfile)
148 pidProfile->pidController = 1;
150 pidProfile->P8[ROLL] = 45;
151 pidProfile->I8[ROLL] = 30;
152 pidProfile->D8[ROLL] = 18;
153 pidProfile->P8[PITCH] = 45;
154 pidProfile->I8[PITCH] = 30;
155 pidProfile->D8[PITCH] = 18;
156 pidProfile->P8[YAW] = 90;
157 pidProfile->I8[YAW] = 40;
158 pidProfile->D8[YAW] = 0;
159 pidProfile->P8[PIDALT] = 50;
160 pidProfile->I8[PIDALT] = 0;
161 pidProfile->D8[PIDALT] = 0;
162 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
163 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
164 pidProfile->D8[PIDPOS] = 0;
165 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
166 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
167 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
168 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
169 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
170 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
171 pidProfile->P8[PIDLEVEL] = 50;
172 pidProfile->I8[PIDLEVEL] = 50;
173 pidProfile->D8[PIDLEVEL] = 100;
174 pidProfile->P8[PIDMAG] = 40;
175 pidProfile->P8[PIDVEL] = 55;
176 pidProfile->I8[PIDVEL] = 55;
177 pidProfile->D8[PIDVEL] = 75;
179 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
180 pidProfile->yaw_lpf_hz = 70.0f;
181 pidProfile->dterm_differentiator = 1;
182 pidProfile->rollPitchItermResetRate = 200;
183 pidProfile->rollPitchItermResetAlways = 0;
184 pidProfile->yawItermResetRate = 50;
185 pidProfile->dterm_lpf_hz = 70.0f; // filtering ON by default
186 pidProfile->deltaMethod = DELTA_FROM_MEASUREMENT;
188 pidProfile->H_sensitivity = 75; // TODO - Cleanup during next EEPROM changes
190 #ifdef GTUNE
191 pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
192 pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
193 pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
194 pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
195 pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
196 pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
197 pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
198 pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
199 pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
200 #endif
203 #ifdef GPS
204 void resetGpsProfile(gpsProfile_t *gpsProfile)
206 gpsProfile->gps_wp_radius = 200;
207 gpsProfile->gps_lpf = 20;
208 gpsProfile->nav_slew_rate = 30;
209 gpsProfile->nav_controls_heading = 1;
210 gpsProfile->nav_speed_min = 100;
211 gpsProfile->nav_speed_max = 300;
212 gpsProfile->ap_mode = 40;
214 #endif
216 void resetBarometerConfig(barometerConfig_t *barometerConfig)
218 barometerConfig->baro_sample_count = 21;
219 barometerConfig->baro_noise_lpf = 0.6f;
220 barometerConfig->baro_cf_vel = 0.985f;
221 barometerConfig->baro_cf_alt = 0.965f;
224 void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
226 sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
227 sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
228 sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
231 void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
233 escAndServoConfig->minthrottle = 1150;
234 escAndServoConfig->maxthrottle = 1850;
235 escAndServoConfig->mincommand = 1000;
236 escAndServoConfig->servoCenterPulse = 1500;
239 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
241 flight3DConfig->deadband3d_low = 1406;
242 flight3DConfig->deadband3d_high = 1514;
243 flight3DConfig->neutral3d = 1460;
244 flight3DConfig->deadband3d_throttle = 50;
247 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
249 telemetryConfig->telemetry_inversion = 0;
250 telemetryConfig->telemetry_switch = 0;
251 telemetryConfig->gpsNoFixLatitude = 0;
252 telemetryConfig->gpsNoFixLongitude = 0;
253 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
254 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
255 telemetryConfig->frsky_vfas_precision = 0;
256 telemetryConfig->frsky_vfas_cell_voltage = 0;
257 telemetryConfig->hottAlarmSoundInterval = 5;
260 void resetBatteryConfig(batteryConfig_t *batteryConfig)
262 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
263 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
264 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
265 batteryConfig->vbatmaxcellvoltage = 43;
266 batteryConfig->vbatmincellvoltage = 33;
267 batteryConfig->vbatwarningcellvoltage = 35;
268 batteryConfig->vbathysteresis = 1;
269 batteryConfig->vbatPidCompensation = 0;
270 batteryConfig->currentMeterOffset = 0;
271 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
272 batteryConfig->batteryCapacity = 0;
273 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
276 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
277 #define FIRST_PORT_INDEX 1
278 #define SECOND_PORT_INDEX 0
279 #else
280 #define FIRST_PORT_INDEX 0
281 #define SECOND_PORT_INDEX 1
282 #endif
284 void resetSerialConfig(serialConfig_t *serialConfig)
286 uint8_t index;
287 memset(serialConfig, 0, sizeof(serialConfig_t));
289 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
290 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
291 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
292 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
293 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
294 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
297 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
299 #if defined(USE_VCP)
300 // This allows MSP connection via USART & VCP so the board can be reconfigured.
301 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
302 #endif
304 serialConfig->reboot_character = 'R';
307 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
308 controlRateConfig->rcRate8 = 100;
309 controlRateConfig->rcExpo8 = 60;
310 controlRateConfig->thrMid8 = 50;
311 controlRateConfig->thrExpo8 = 0;
312 controlRateConfig->dynThrPID = 0;
313 controlRateConfig->rcYawExpo8 = 20;
314 controlRateConfig->tpa_breakpoint = 1500;
316 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
317 controlRateConfig->rates[axis] = 50;
322 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
323 rcControlsConfig->deadband = 0;
324 rcControlsConfig->yaw_deadband = 0;
325 rcControlsConfig->alt_hold_deadband = 40;
326 rcControlsConfig->alt_hold_fast_change = 1;
329 void resetMixerConfig(mixerConfig_t *mixerConfig) {
330 mixerConfig->yaw_motor_direction = 1;
331 mixerConfig->yaw_jump_prevention_limit = 200;
332 #ifdef USE_SERVOS
333 mixerConfig->tri_unarmed_servo = 1;
334 mixerConfig->servo_lowpass_freq = 400;
335 mixerConfig->servo_lowpass_enable = 0;
336 #endif
339 uint8_t getCurrentProfile(void)
341 return masterConfig.current_profile_index;
344 static void setProfile(uint8_t profileIndex)
346 currentProfile = &masterConfig.profile[profileIndex];
347 currentControlRateProfileIndex = currentProfile->activeRateProfile;
348 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
351 uint8_t getCurrentControlRateProfile(void)
353 return currentControlRateProfileIndex;
356 static void setControlRateProfile(uint8_t profileIndex) {
357 currentControlRateProfileIndex = profileIndex;
358 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
359 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
363 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
364 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
367 uint16_t getCurrentMinthrottle(void)
369 return masterConfig.escAndServoConfig.minthrottle;
372 // Default settings
373 static void resetConf(void)
375 int i;
377 // Clear all configuration
378 memset(&masterConfig, 0, sizeof(master_t));
379 setProfile(0);
381 masterConfig.version = EEPROM_CONF_VERSION;
382 masterConfig.mixerMode = MIXER_QUADX;
383 featureClearAll();
384 #if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE)
385 featureSet(FEATURE_RX_PPM);
386 #endif
388 //#if defined(SPRACINGF3MINI)
389 // featureSet(FEATURE_DISPLAY);
390 //#endif
392 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
393 // only enable the VBAT feature by default if the board has a voltage divider otherwise
394 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
395 featureSet(FEATURE_VBAT);
396 #endif
398 featureSet(FEATURE_FAILSAFE);
399 featureSet(FEATURE_ONESHOT125);
401 // global settings
402 masterConfig.current_profile_index = 0; // default profile
403 masterConfig.dcm_kp = 2500; // 1.0 * 10000
404 masterConfig.dcm_ki = 0; // 0.003 * 10000
405 masterConfig.gyro_lpf = 0; // 256HZ default
406 masterConfig.gyro_sync_denom = 8;
407 masterConfig.gyro_soft_lpf_hz = 80.0f;
409 masterConfig.pid_process_denom = 1;
411 masterConfig.debug_mode = 0;
413 resetAccelerometerTrims(&masterConfig.accZero);
415 resetSensorAlignment(&masterConfig.sensorAlignmentConfig);
417 masterConfig.boardAlignment.rollDegrees = 0;
418 masterConfig.boardAlignment.pitchDegrees = 0;
419 masterConfig.boardAlignment.yawDegrees = 0;
420 masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
421 masterConfig.max_angle_inclination = 700; // 70 degrees
422 masterConfig.yaw_control_direction = 1;
423 masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
425 // xxx_hardware: 0:default/autodetect, 1: disable
426 masterConfig.mag_hardware = 0;
428 masterConfig.baro_hardware = 0;
430 resetBatteryConfig(&masterConfig.batteryConfig);
432 resetTelemetryConfig(&masterConfig.telemetryConfig);
434 masterConfig.rxConfig.serialrx_provider = 0;
435 masterConfig.rxConfig.sbus_inversion = 1;
436 masterConfig.rxConfig.spektrum_sat_bind = 0;
437 masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
438 masterConfig.rxConfig.midrc = 1500;
439 masterConfig.rxConfig.mincheck = 1040;
440 masterConfig.rxConfig.maxcheck = 1900;
441 masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
442 masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
444 for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
445 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
446 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
447 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
450 masterConfig.rxConfig.rssi_channel = 0;
451 masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
452 masterConfig.rxConfig.rssi_ppm_invert = 0;
453 masterConfig.rxConfig.rcSmoothing = 0;
454 masterConfig.rxConfig.fpvCamAngleDegrees = 0;
455 masterConfig.rxConfig.max_aux_channel = 6;
456 masterConfig.rxConfig.superExpoFactor = 30;
457 masterConfig.rxConfig.superExpoFactorYaw = 30;
458 masterConfig.rxConfig.superExpoYawMode = 0;
460 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
462 masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
464 masterConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
465 masterConfig.disarm_kill_switch = 1;
466 masterConfig.auto_disarm_delay = 5;
467 masterConfig.small_angle = 25;
469 resetMixerConfig(&masterConfig.mixerConfig);
471 masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
473 // Motor/ESC/Servo
474 resetEscAndServoConfig(&masterConfig.escAndServoConfig);
475 resetFlight3DConfig(&masterConfig.flight3DConfig);
477 #ifdef BRUSHED_MOTORS
478 masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
479 #else
480 masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
481 #endif
482 masterConfig.servo_pwm_rate = 50;
483 masterConfig.use_oneshot42 = 0;
484 #ifdef CC3D
485 masterConfig.use_buzzer_p6 = 0;
486 #endif
488 #ifdef GPS
489 // gps/nav stuff
490 masterConfig.gpsConfig.provider = GPS_NMEA;
491 masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
492 masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
493 masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
494 #endif
496 resetSerialConfig(&masterConfig.serialConfig);
498 #if defined(STM32F10X) && !defined(CC3D)
499 masterConfig.emf_avoidance = 1;
500 #else
501 masterConfig.emf_avoidance = 0;
502 #endif
504 resetPidProfile(&currentProfile->pidProfile);
506 uint8_t rI;
507 for (rI = 0; rI<MAX_RATEPROFILES; rI++) {
508 resetControlRateConfig(&masterConfig.profile[0].controlRateProfile[rI]);
510 resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
512 masterConfig.mag_declination = 0;
513 masterConfig.acc_lpf_hz = 10.0f;
514 masterConfig.accDeadband.xy = 40;
515 masterConfig.accDeadband.z = 40;
516 masterConfig.acc_unarmedcal = 1;
518 resetBarometerConfig(&masterConfig.barometerConfig);
520 // Radio
521 parseRcChannels("AETR1234", &masterConfig.rxConfig);
523 resetRcControlsConfig(&masterConfig.rcControlsConfig);
525 masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
526 masterConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
528 // Failsafe Variables
529 masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
530 masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec
531 masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
532 masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
533 masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
534 masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
536 #ifdef USE_SERVOS
537 // servos
538 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
539 masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
540 masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
541 masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
542 masterConfig.servoConf[i].rate = 100;
543 masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
544 masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
545 masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
548 // gimbal
549 masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL;
550 #endif
552 #ifdef GPS
553 resetGpsProfile(&masterConfig.gpsProfile);
554 #endif
556 // custom mixer. clear by defaults.
557 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
558 masterConfig.customMotorMixer[i].throttle = 0.0f;
560 #ifdef LED_STRIP
561 applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT);
562 applyDefaultLedStripConfig(masterConfig.ledConfigs);
563 #endif
565 #ifdef SPRACINGF3
566 featureSet(FEATURE_BLACKBOX);
567 masterConfig.blackbox_device = 1;
568 #ifdef TRANSPONDER
569 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
571 memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
572 #endif
574 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
575 featureSet(FEATURE_BLACKBOX);
576 masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
577 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
578 featureSet(FEATURE_BLACKBOX);
579 masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
580 #else
581 masterConfig.blackbox_device = 0;
582 #endif
584 masterConfig.blackbox_rate_num = 1;
585 masterConfig.blackbox_rate_denom = 1;
586 #endif
588 // alternative defaults settings for COLIBRI RACE targets
589 #if defined(COLIBRI_RACE)
590 masterConfig.escAndServoConfig.minthrottle = 1025;
591 masterConfig.escAndServoConfig.maxthrottle = 1980;
592 masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
593 masterConfig.batteryConfig.vbatmincellvoltage = 30;
595 featureSet(FEATURE_VBAT);
596 featureSet(FEATURE_FAILSAFE);
597 #endif
599 #ifdef SPRACINGF3EVO
600 featureSet(FEATURE_TRANSPONDER);
601 featureSet(FEATURE_RSSI_ADC);
602 featureSet(FEATURE_CURRENT_METER);
603 featureSet(FEATURE_TELEMETRY);
604 #endif
606 // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
607 #ifdef ALIENFLIGHT
608 featureSet(FEATURE_RX_SERIAL);
609 featureSet(FEATURE_MOTOR_STOP);
610 featureClear(FEATURE_ONESHOT125);
611 #ifdef ALIENFLIGHTF3
612 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
613 masterConfig.batteryConfig.vbatscale = 20;
614 masterConfig.mag_hardware = MAG_NONE; // disabled by default
615 #else
616 masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
617 #endif
618 masterConfig.rxConfig.serialrx_provider = 1;
619 masterConfig.rxConfig.spektrum_sat_bind = 5;
620 masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
621 masterConfig.escAndServoConfig.minthrottle = 1000;
622 masterConfig.escAndServoConfig.maxthrottle = 2000;
623 masterConfig.motor_pwm_rate = 32000;
624 currentProfile->pidProfile.pidController = 2;
625 masterConfig.failsafeConfig.failsafe_delay = 2;
626 masterConfig.failsafeConfig.failsafe_off_delay = 0;
627 masterConfig.mixerConfig.yaw_jump_prevention_limit = 500;
628 currentControlRateProfile->rcRate8 = 100;
629 currentControlRateProfile->rates[FD_PITCH] = 20;
630 currentControlRateProfile->rates[FD_ROLL] = 20;
631 currentControlRateProfile->rates[FD_YAW] = 20;
632 parseRcChannels("TAER1234", &masterConfig.rxConfig);
634 // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
635 masterConfig.customMotorMixer[0].throttle = 1.0f;
636 masterConfig.customMotorMixer[0].roll = -0.414178f;
637 masterConfig.customMotorMixer[0].pitch = 1.0f;
638 masterConfig.customMotorMixer[0].yaw = -1.0f;
640 // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
641 masterConfig.customMotorMixer[1].throttle = 1.0f;
642 masterConfig.customMotorMixer[1].roll = -0.414178f;
643 masterConfig.customMotorMixer[1].pitch = -1.0f;
644 masterConfig.customMotorMixer[1].yaw = 1.0f;
646 // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
647 masterConfig.customMotorMixer[2].throttle = 1.0f;
648 masterConfig.customMotorMixer[2].roll = 0.414178f;
649 masterConfig.customMotorMixer[2].pitch = 1.0f;
650 masterConfig.customMotorMixer[2].yaw = 1.0f;
652 // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
653 masterConfig.customMotorMixer[3].throttle = 1.0f;
654 masterConfig.customMotorMixer[3].roll = 0.414178f;
655 masterConfig.customMotorMixer[3].pitch = -1.0f;
656 masterConfig.customMotorMixer[3].yaw = -1.0f;
658 // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
659 masterConfig.customMotorMixer[4].throttle = 1.0f;
660 masterConfig.customMotorMixer[4].roll = -1.0f;
661 masterConfig.customMotorMixer[4].pitch = -0.414178f;
662 masterConfig.customMotorMixer[4].yaw = -1.0f;
664 // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
665 masterConfig.customMotorMixer[5].throttle = 1.0f;
666 masterConfig.customMotorMixer[5].roll = 1.0f;
667 masterConfig.customMotorMixer[5].pitch = -0.414178f;
668 masterConfig.customMotorMixer[5].yaw = 1.0f;
670 // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
671 masterConfig.customMotorMixer[6].throttle = 1.0f;
672 masterConfig.customMotorMixer[6].roll = -1.0f;
673 masterConfig.customMotorMixer[6].pitch = 0.414178f;
674 masterConfig.customMotorMixer[6].yaw = 1.0f;
676 // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
677 masterConfig.customMotorMixer[7].throttle = 1.0f;
678 masterConfig.customMotorMixer[7].roll = 1.0f;
679 masterConfig.customMotorMixer[7].pitch = 0.414178f;
680 masterConfig.customMotorMixer[7].yaw = -1.0f;
681 #endif
683 // copy first profile into remaining profile
684 for (i = 1; i < MAX_PROFILE_COUNT; i++) {
685 memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
690 static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
692 uint8_t checksum = 0;
693 const uint8_t *byteOffset;
695 for (byteOffset = data; byteOffset < (data + length); byteOffset++)
696 checksum ^= *byteOffset;
697 return checksum;
700 static bool isEEPROMContentValid(void)
702 const master_t *temp = (const master_t *) CONFIG_START_FLASH_ADDRESS;
703 uint8_t checksum = 0;
705 // check version number
706 if (EEPROM_CONF_VERSION != temp->version)
707 return false;
709 // check size and magic numbers
710 if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
711 return false;
713 // verify integrity of temporary copy
714 checksum = calculateChecksum((const uint8_t *) temp, sizeof(master_t));
715 if (checksum != 0)
716 return false;
718 // looks good, let's roll!
719 return true;
722 void activateControlRateConfig(void)
724 generatePitchRollCurve(currentControlRateProfile);
725 generateYawCurve(currentControlRateProfile);
726 generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig);
729 void activateConfig(void)
731 static imuRuntimeConfig_t imuRuntimeConfig;
733 activateControlRateConfig();
735 resetAdjustmentStates();
737 useRcControlsConfig(
738 masterConfig.modeActivationConditions,
739 &masterConfig.escAndServoConfig,
740 &currentProfile->pidProfile
743 useGyroConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
745 #ifdef TELEMETRY
746 telemetryUseConfig(&masterConfig.telemetryConfig);
747 #endif
748 pidSetController(currentProfile->pidProfile.pidController);
750 #ifdef GPS
751 gpsUseProfile(&masterConfig.gpsProfile);
752 gpsUsePIDs(&currentProfile->pidProfile);
753 #endif
755 useFailsafeConfig(&masterConfig.failsafeConfig);
756 setAccelerationTrims(&masterConfig.accZero);
757 setAccelerationFilter(masterConfig.acc_lpf_hz);
759 mixerUseConfigs(
760 #ifdef USE_SERVOS
761 masterConfig.servoConf,
762 &masterConfig.gimbalConfig,
763 #endif
764 &masterConfig.flight3DConfig,
765 &masterConfig.escAndServoConfig,
766 &masterConfig.mixerConfig,
767 &masterConfig.airplaneConfig,
768 &masterConfig.rxConfig
771 imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
772 imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
773 imuRuntimeConfig.acc_unarmedcal = masterConfig.acc_unarmedcal;
774 imuRuntimeConfig.small_angle = masterConfig.small_angle;
776 imuConfigure(
777 &imuRuntimeConfig,
778 &currentProfile->pidProfile,
779 &masterConfig.accDeadband,
780 masterConfig.throttle_correction_angle
783 configureAltitudeHold(
784 &currentProfile->pidProfile,
785 &masterConfig.barometerConfig,
786 &masterConfig.rcControlsConfig,
787 &masterConfig.escAndServoConfig
790 #ifdef BARO
791 useBarometerConfig(&masterConfig.barometerConfig);
792 #endif
795 void validateAndFixConfig(void)
797 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
798 featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
801 if (featureConfigured(FEATURE_RX_PPM)) {
802 featureClear(FEATURE_RX_PARALLEL_PWM);
805 if (featureConfigured(FEATURE_RX_MSP)) {
806 featureClear(FEATURE_RX_SERIAL);
807 featureClear(FEATURE_RX_PARALLEL_PWM);
808 featureClear(FEATURE_RX_PPM);
811 if (featureConfigured(FEATURE_RX_SERIAL)) {
812 featureClear(FEATURE_RX_PARALLEL_PWM);
813 featureClear(FEATURE_RX_PPM);
816 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
817 #if defined(STM32F10X)
818 // rssi adc needs the same ports
819 featureClear(FEATURE_RSSI_ADC);
820 // current meter needs the same ports
821 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
822 featureClear(FEATURE_CURRENT_METER);
824 #endif
826 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
827 // led strip needs the same ports
828 featureClear(FEATURE_LED_STRIP);
829 #endif
831 // software serial needs free PWM ports
832 featureClear(FEATURE_SOFTSERIAL);
836 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
837 if (featureConfigured(FEATURE_SOFTSERIAL) && (
839 #ifdef USE_SOFTSERIAL1
840 || (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
841 #endif
842 #ifdef USE_SOFTSERIAL2
843 || (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
844 #endif
845 )) {
846 // led strip needs the same timer as softserial
847 featureClear(FEATURE_LED_STRIP);
849 #endif
851 #if defined(NAZE) && defined(SONAR)
852 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
853 featureClear(FEATURE_CURRENT_METER);
855 #endif
857 #if defined(OLIMEXINO) && defined(SONAR)
858 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
859 featureClear(FEATURE_CURRENT_METER);
861 #endif
863 #if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
864 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
865 featureClear(FEATURE_DISPLAY);
867 #endif
869 #ifdef STM32F303xC
870 // hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
871 masterConfig.telemetryConfig.telemetry_inversion = 1;
872 #endif
875 /*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
876 if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
877 featureClear(FEATURE_LED_STRIP);
879 #endif
882 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
883 // shared pin
884 if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
885 featureClear(FEATURE_SONAR);
886 featureClear(FEATURE_SOFTSERIAL);
887 featureClear(FEATURE_RSSI_ADC);
889 #endif
891 #if defined(COLIBRI_RACE)
892 masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
893 if(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
894 featureClear(FEATURE_RX_PARALLEL_PWM);
895 featureClear(FEATURE_RX_MSP);
896 featureSet(FEATURE_RX_PPM);
898 if(featureConfigured(FEATURE_RX_SERIAL)) {
899 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
900 //masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
902 #endif
904 useRxConfig(&masterConfig.rxConfig);
906 serialConfig_t *serialConfig = &masterConfig.serialConfig;
908 if (!isSerialConfigValid(serialConfig)) {
909 resetSerialConfig(serialConfig);
913 void initEEPROM(void)
917 void readEEPROM(void)
919 // Sanity check
920 if (!isEEPROMContentValid())
921 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
923 suspendRxSignal();
925 // Read flash
926 memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
928 if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) // sanity check
929 masterConfig.current_profile_index = 0;
931 setProfile(masterConfig.current_profile_index);
933 validateAndFixConfig();
934 activateConfig();
936 resumeRxSignal();
939 void readEEPROMAndNotify(void)
941 // re-read written data
942 readEEPROM();
943 beeperConfirmationBeeps(1);
946 void writeEEPROM(void)
948 // Generate compile time error if the config does not fit in the reserved area of flash.
949 BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
951 FLASH_Status status = 0;
952 uint32_t wordOffset;
953 int8_t attemptsRemaining = 3;
955 suspendRxSignal();
957 // prepare checksum/version constants
958 masterConfig.version = EEPROM_CONF_VERSION;
959 masterConfig.size = sizeof(master_t);
960 masterConfig.magic_be = 0xBE;
961 masterConfig.magic_ef = 0xEF;
962 masterConfig.chk = 0; // erase checksum before recalculating
963 masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
965 // write it
966 FLASH_Unlock();
967 while (attemptsRemaining--) {
968 #ifdef STM32F303
969 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
970 #endif
971 #ifdef STM32F10X
972 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
973 #endif
974 for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
975 if (wordOffset % FLASH_PAGE_SIZE == 0) {
976 status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
977 if (status != FLASH_COMPLETE) {
978 break;
982 status = FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS + wordOffset,
983 *(uint32_t *) ((char *) &masterConfig + wordOffset));
984 if (status != FLASH_COMPLETE) {
985 break;
988 if (status == FLASH_COMPLETE) {
989 break;
992 FLASH_Lock();
994 // Flash write failed - just die now
995 if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
996 failureMode(FAILURE_FLASH_WRITE_FAILED);
999 resumeRxSignal();
1002 void ensureEEPROMContainsValidData(void)
1004 if (isEEPROMContentValid()) {
1005 return;
1008 resetEEPROM();
1011 void resetEEPROM(void)
1013 resetConf();
1014 writeEEPROM();
1017 void saveConfigAndNotify(void)
1019 writeEEPROM();
1020 readEEPROMAndNotify();
1023 void changeProfile(uint8_t profileIndex)
1025 masterConfig.current_profile_index = profileIndex;
1026 writeEEPROM();
1027 readEEPROM();
1028 beeperConfirmationBeeps(profileIndex + 1);
1031 void changeControlRateProfile(uint8_t profileIndex) {
1032 if (profileIndex > MAX_RATEPROFILES) {
1033 profileIndex = MAX_RATEPROFILES - 1;
1035 setControlRateProfile(profileIndex);
1036 activateControlRateConfig();
1039 void handleOneshotFeatureChangeOnRestart(void)
1041 // Shutdown PWM on all motors prior to soft restart
1042 StopPwmAllMotors();
1043 delay(50);
1044 // Apply additional delay when OneShot125 feature changed from on to off state
1045 if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
1046 delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
1050 void latchActiveFeatures()
1052 activeFeaturesLatch = masterConfig.enabledFeatures;
1055 bool featureConfigured(uint32_t mask)
1057 return masterConfig.enabledFeatures & mask;
1060 bool feature(uint32_t mask)
1062 return activeFeaturesLatch & mask;
1065 void featureSet(uint32_t mask)
1067 masterConfig.enabledFeatures |= mask;
1070 void featureClear(uint32_t mask)
1072 masterConfig.enabledFeatures &= ~(mask);
1075 void featureClearAll()
1077 masterConfig.enabledFeatures = 0;
1080 uint32_t featureMask(void)
1082 return masterConfig.enabledFeatures;
1085 void beeperOffSet(uint32_t mask)
1087 masterConfig.beeper_off_flags |= mask;
1090 void beeperOffSetAll(uint8_t beeperCount)
1092 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1095 void beeperOffClear(uint32_t mask)
1097 masterConfig.beeper_off_flags &= ~(mask);
1100 void beeperOffClearAll(void)
1102 masterConfig.beeper_off_flags = 0;
1105 uint32_t getBeeperOffMask(void)
1107 return masterConfig.beeper_off_flags;
1110 void setBeeperOffMask(uint32_t mask)
1112 masterConfig.beeper_off_flags = mask;
1115 uint32_t getPreferedBeeperOffMask(void)
1117 return masterConfig.prefered_beeper_off_flags;
1120 void setPreferedBeeperOffMask(uint32_t mask)
1122 masterConfig.prefered_beeper_off_flags = mask;