Rework Super Expo Rate Implementation // On the fly Rc Expo
[betaflight.git] / src / main / config / config.c
blob88fd4905920ea7ca367ba62e54d714a48830fda9
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"
57 #include "io/vtx.h"
59 #include "rx/rx.h"
61 #include "telemetry/telemetry.h"
63 #include "flight/mixer.h"
64 #include "flight/pid.h"
65 #include "flight/imu.h"
66 #include "flight/failsafe.h"
67 #include "flight/altitudehold.h"
68 #include "flight/navigation.h"
70 #include "config/runtime_config.h"
71 #include "config/config.h"
73 #include "config/config_profile.h"
74 #include "config/config_master.h"
76 #define BRUSHED_MOTORS_PWM_RATE 16000
77 #define BRUSHLESS_MOTORS_PWM_RATE 400
79 void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
81 #if !defined(FLASH_SIZE)
82 #error "Flash size not defined for target. (specify in KB)"
83 #endif
86 #ifndef FLASH_PAGE_SIZE
87 #ifdef STM32F303xC
88 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
89 #endif
91 #ifdef STM32F10X_MD
92 #define FLASH_PAGE_SIZE ((uint16_t)0x400)
93 #endif
95 #ifdef STM32F10X_HD
96 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
97 #endif
98 #endif
100 #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
101 #ifdef STM32F10X_MD
102 #define FLASH_PAGE_COUNT 128
103 #endif
105 #ifdef STM32F10X_HD
106 #define FLASH_PAGE_COUNT 128
107 #endif
108 #endif
110 #if defined(FLASH_SIZE)
111 #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
112 #endif
114 #if !defined(FLASH_PAGE_SIZE)
115 #error "Flash page size not defined for target."
116 #endif
118 #if !defined(FLASH_PAGE_COUNT)
119 #error "Flash page count not defined for target."
120 #endif
122 #if FLASH_SIZE <= 128
123 #define FLASH_TO_RESERVE_FOR_CONFIG 0x800
124 #else
125 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
126 #endif
128 // use the last flash pages for storage
129 #ifdef CUSTOM_FLASH_MEMORY_ADDRESS
130 size_t custom_flash_memory_address = 0;
131 #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
132 #else
133 // use the last flash pages for storage
134 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
135 #endif
137 master_t masterConfig; // master config struct with data independent from profiles
138 profile_t *currentProfile;
139 static uint32_t activeFeaturesLatch = 0;
141 static uint8_t currentControlRateProfileIndex = 0;
142 controlRateConfig_t *currentControlRateProfile;
144 static const uint8_t EEPROM_CONF_VERSION = 139;
146 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
148 accelerometerTrims->values.pitch = 0;
149 accelerometerTrims->values.roll = 0;
150 accelerometerTrims->values.yaw = 0;
153 static void resetPidProfile(pidProfile_t *pidProfile)
155 pidProfile->pidController = 1;
157 pidProfile->P8[ROLL] = 45;
158 pidProfile->I8[ROLL] = 40;
159 pidProfile->D8[ROLL] = 15;
160 pidProfile->P8[PITCH] = 45;
161 pidProfile->I8[PITCH] = 40;
162 pidProfile->D8[PITCH] = 15;
163 pidProfile->P8[YAW] = 90;
164 pidProfile->I8[YAW] = 45;
165 pidProfile->D8[YAW] = 20;
166 pidProfile->P8[PIDALT] = 50;
167 pidProfile->I8[PIDALT] = 0;
168 pidProfile->D8[PIDALT] = 0;
169 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
170 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
171 pidProfile->D8[PIDPOS] = 0;
172 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
173 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
174 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
175 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
176 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
177 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
178 pidProfile->P8[PIDLEVEL] = 50;
179 pidProfile->I8[PIDLEVEL] = 50;
180 pidProfile->D8[PIDLEVEL] = 100;
181 pidProfile->P8[PIDMAG] = 40;
182 pidProfile->P8[PIDVEL] = 55;
183 pidProfile->I8[PIDVEL] = 55;
184 pidProfile->D8[PIDVEL] = 75;
186 pidProfile->yaw_p_limit = YAW_P_LIMIT_MAX;
187 pidProfile->yaw_lpf_hz = 80;
188 pidProfile->rollPitchItermIgnoreRate = 200;
189 pidProfile->yawItermIgnoreRate = 45;
190 pidProfile->dterm_lpf_hz = 110; // filtering ON by default
191 pidProfile->dynamic_pid = 1;
193 #ifdef GTUNE
194 pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
195 pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
196 pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
197 pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
198 pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
199 pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
200 pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
201 pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
202 pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
203 #endif
206 #ifdef GPS
207 void resetGpsProfile(gpsProfile_t *gpsProfile)
209 gpsProfile->gps_wp_radius = 200;
210 gpsProfile->gps_lpf = 20;
211 gpsProfile->nav_slew_rate = 30;
212 gpsProfile->nav_controls_heading = 1;
213 gpsProfile->nav_speed_min = 100;
214 gpsProfile->nav_speed_max = 300;
215 gpsProfile->ap_mode = 40;
217 #endif
219 void resetBarometerConfig(barometerConfig_t *barometerConfig)
221 barometerConfig->baro_sample_count = 21;
222 barometerConfig->baro_noise_lpf = 0.6f;
223 barometerConfig->baro_cf_vel = 0.985f;
224 barometerConfig->baro_cf_alt = 0.965f;
227 void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
229 sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
230 sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
231 sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
234 void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
236 escAndServoConfig->minthrottle = 1150;
237 escAndServoConfig->maxthrottle = 1850;
238 escAndServoConfig->mincommand = 1000;
239 escAndServoConfig->servoCenterPulse = 1500;
240 escAndServoConfig->escDesyncProtection = 0;
243 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
245 flight3DConfig->deadband3d_low = 1406;
246 flight3DConfig->deadband3d_high = 1514;
247 flight3DConfig->neutral3d = 1460;
248 flight3DConfig->deadband3d_throttle = 50;
251 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
253 telemetryConfig->telemetry_inversion = 0;
254 telemetryConfig->telemetry_switch = 0;
255 telemetryConfig->gpsNoFixLatitude = 0;
256 telemetryConfig->gpsNoFixLongitude = 0;
257 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
258 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
259 telemetryConfig->frsky_vfas_precision = 0;
260 telemetryConfig->frsky_vfas_cell_voltage = 0;
261 telemetryConfig->hottAlarmSoundInterval = 5;
264 void resetBatteryConfig(batteryConfig_t *batteryConfig)
266 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
267 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
268 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
269 batteryConfig->vbatmaxcellvoltage = 43;
270 batteryConfig->vbatmincellvoltage = 33;
271 batteryConfig->vbatwarningcellvoltage = 35;
272 batteryConfig->vbathysteresis = 1;
273 batteryConfig->vbatPidCompensation = 0;
274 batteryConfig->currentMeterOffset = 0;
275 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
276 batteryConfig->batteryCapacity = 0;
277 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
280 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
281 #define FIRST_PORT_INDEX 1
282 #define SECOND_PORT_INDEX 0
283 #else
284 #define FIRST_PORT_INDEX 0
285 #define SECOND_PORT_INDEX 1
286 #endif
288 void resetSerialConfig(serialConfig_t *serialConfig)
290 uint8_t index;
291 memset(serialConfig, 0, sizeof(serialConfig_t));
293 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
294 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
295 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
296 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
297 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
298 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
301 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
303 #if defined(USE_VCP)
304 // This allows MSP connection via USART & VCP so the board can be reconfigured.
305 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
306 #endif
308 serialConfig->reboot_character = 'R';
311 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
312 controlRateConfig->rcRate8 = 100;
313 controlRateConfig->rcExpo8 = 10;
314 controlRateConfig->thrMid8 = 50;
315 controlRateConfig->thrExpo8 = 0;
316 controlRateConfig->dynThrPID = 20;
317 controlRateConfig->rcYawExpo8 = 10;
318 controlRateConfig->tpa_breakpoint = 1650;
320 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
321 controlRateConfig->rates[axis] = 70;
326 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
327 rcControlsConfig->deadband = 0;
328 rcControlsConfig->yaw_deadband = 0;
329 rcControlsConfig->alt_hold_deadband = 40;
330 rcControlsConfig->alt_hold_fast_change = 1;
333 void resetMixerConfig(mixerConfig_t *mixerConfig) {
334 mixerConfig->yaw_motor_direction = 1;
335 #ifdef USE_SERVOS
336 mixerConfig->tri_unarmed_servo = 1;
337 mixerConfig->servo_lowpass_freq = 400;
338 mixerConfig->servo_lowpass_enable = 0;
339 #endif
342 uint8_t getCurrentProfile(void)
344 return masterConfig.current_profile_index;
347 static void setProfile(uint8_t profileIndex)
349 currentProfile = &masterConfig.profile[profileIndex];
350 currentControlRateProfileIndex = currentProfile->activeRateProfile;
351 currentControlRateProfile = &currentProfile->controlRateProfile[currentControlRateProfileIndex];
354 uint8_t getCurrentControlRateProfile(void)
356 return currentControlRateProfileIndex;
359 static void setControlRateProfile(uint8_t profileIndex) {
360 currentControlRateProfileIndex = profileIndex;
361 masterConfig.profile[getCurrentProfile()].activeRateProfile = profileIndex;
362 currentControlRateProfile = &masterConfig.profile[getCurrentProfile()].controlRateProfile[profileIndex];
366 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
367 return &masterConfig.profile[profileIndex].controlRateProfile[masterConfig.profile[profileIndex].activeRateProfile];
370 uint16_t getCurrentMinthrottle(void)
372 return masterConfig.escAndServoConfig.minthrottle;
375 // Default settings
376 static void resetConf(void)
378 int i;
380 // Clear all configuration
381 memset(&masterConfig, 0, sizeof(master_t));
382 setProfile(0);
384 masterConfig.version = EEPROM_CONF_VERSION;
385 masterConfig.mixerMode = MIXER_QUADX;
386 featureClearAll();
387 #if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE) || defined(SINGULARITY)
388 featureSet(FEATURE_RX_PPM);
389 #endif
391 //#if defined(SPRACINGF3MINI)
392 // featureSet(FEATURE_DISPLAY);
393 //#endif
395 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
396 // only enable the VBAT feature by default if the board has a voltage divider otherwise
397 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
398 featureSet(FEATURE_VBAT);
399 #endif
401 featureSet(FEATURE_FAILSAFE);
402 featureSet(FEATURE_SUPEREXPO);
404 // global settings
405 masterConfig.current_profile_index = 0; // default profile
406 masterConfig.dcm_kp = 2500; // 1.0 * 10000
407 masterConfig.dcm_ki = 0; // 0.003 * 10000
408 masterConfig.gyro_lpf = 0; // 256HZ default
409 #ifdef STM32F10X
410 masterConfig.gyro_sync_denom = 8;
411 #else
412 masterConfig.gyro_sync_denom = 4;
413 #endif
414 masterConfig.gyro_soft_lpf_hz = 100;
416 masterConfig.pid_process_denom = 2;
418 masterConfig.debug_mode = 0;
420 resetAccelerometerTrims(&masterConfig.accZero);
422 resetSensorAlignment(&masterConfig.sensorAlignmentConfig);
424 masterConfig.boardAlignment.rollDegrees = 0;
425 masterConfig.boardAlignment.pitchDegrees = 0;
426 masterConfig.boardAlignment.yawDegrees = 0;
427 masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
428 masterConfig.max_angle_inclination = 700; // 70 degrees
429 masterConfig.yaw_control_direction = 1;
430 masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
432 // xxx_hardware: 0:default/autodetect, 1: disable
433 masterConfig.mag_hardware = 0;
435 masterConfig.baro_hardware = 0;
437 resetBatteryConfig(&masterConfig.batteryConfig);
439 resetTelemetryConfig(&masterConfig.telemetryConfig);
441 masterConfig.rxConfig.serialrx_provider = 0;
442 masterConfig.rxConfig.sbus_inversion = 1;
443 masterConfig.rxConfig.spektrum_sat_bind = 0;
444 masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
445 masterConfig.rxConfig.midrc = 1500;
446 masterConfig.rxConfig.mincheck = 1100;
447 masterConfig.rxConfig.maxcheck = 1900;
448 masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
449 masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
451 for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
452 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
453 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
454 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
457 masterConfig.rxConfig.rssi_channel = 0;
458 masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
459 masterConfig.rxConfig.rssi_ppm_invert = 0;
460 masterConfig.rxConfig.rcSmoothing = 0;
461 masterConfig.rxConfig.fpvCamAngleDegrees = 0;
462 masterConfig.rxConfig.max_aux_channel = 6;
463 masterConfig.rxConfig.airModeActivateThreshold = 1350;
465 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
467 masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
469 masterConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support
470 masterConfig.disarm_kill_switch = 1;
471 masterConfig.auto_disarm_delay = 5;
472 masterConfig.small_angle = 25;
474 resetMixerConfig(&masterConfig.mixerConfig);
476 masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
478 // Motor/ESC/Servo
479 resetEscAndServoConfig(&masterConfig.escAndServoConfig);
480 resetFlight3DConfig(&masterConfig.flight3DConfig);
482 #ifdef BRUSHED_MOTORS
483 masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
484 #else
485 masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
486 #endif
487 masterConfig.servo_pwm_rate = 50;
488 masterConfig.fast_pwm_protocol = 1;
489 masterConfig.use_unsyncedPwm = 0;
490 #ifdef CC3D
491 masterConfig.use_buzzer_p6 = 0;
492 #endif
494 #ifdef GPS
495 // gps/nav stuff
496 masterConfig.gpsConfig.provider = GPS_NMEA;
497 masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
498 masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
499 masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
500 #endif
502 resetSerialConfig(&masterConfig.serialConfig);
504 masterConfig.emf_avoidance = 0; // TODO - needs removal
506 resetPidProfile(&currentProfile->pidProfile);
508 uint8_t rI;
509 for (rI = 0; rI<MAX_RATEPROFILES; rI++) {
510 resetControlRateConfig(&masterConfig.profile[0].controlRateProfile[rI]);
512 resetRollAndPitchTrims(&masterConfig.accelerometerTrims);
514 masterConfig.mag_declination = 0;
515 masterConfig.acc_lpf_hz = 10.0f;
516 masterConfig.accDeadband.xy = 40;
517 masterConfig.accDeadband.z = 40;
518 masterConfig.acc_unarmedcal = 1;
520 resetBarometerConfig(&masterConfig.barometerConfig);
522 // Radio
523 parseRcChannels("AETR1234", &masterConfig.rxConfig);
525 resetRcControlsConfig(&masterConfig.rcControlsConfig);
527 masterConfig.throttle_correction_value = 0; // could 10 with althold or 40 for fpv
528 masterConfig.throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
530 // Failsafe Variables
531 masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
532 masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec
533 masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
534 masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
535 masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
536 masterConfig.failsafeConfig.failsafe_procedure = 0; // default full failsafe procedure is 0: auto-landing
538 #ifdef USE_SERVOS
539 // servos
540 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
541 masterConfig.servoConf[i].min = DEFAULT_SERVO_MIN;
542 masterConfig.servoConf[i].max = DEFAULT_SERVO_MAX;
543 masterConfig.servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
544 masterConfig.servoConf[i].rate = 100;
545 masterConfig.servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
546 masterConfig.servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
547 masterConfig.servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
550 // gimbal
551 masterConfig.gimbalConfig.mode = GIMBAL_MODE_NORMAL;
552 #endif
554 #ifdef GPS
555 resetGpsProfile(&masterConfig.gpsProfile);
556 #endif
558 // custom mixer. clear by defaults.
559 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
560 masterConfig.customMotorMixer[i].throttle = 0.0f;
562 #ifdef LED_STRIP
563 applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT);
564 applyDefaultLedStripConfig(masterConfig.ledConfigs);
565 masterConfig.ledstrip_visual_beeper = 0;
566 #endif
568 #ifdef VTX
569 masterConfig.vtx_band = 4; //Fatshark/Airwaves
570 masterConfig.vtx_channel = 1; //CH1
571 masterConfig.vtx_mode = 0; //CH+BAND mode
572 masterConfig.vtx_mhz = 5740; //F0
573 #endif
575 #ifdef SPRACINGF3
576 featureSet(FEATURE_BLACKBOX);
577 masterConfig.blackbox_device = 1;
578 #ifdef TRANSPONDER
579 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
581 memcpy(masterConfig.transponderData, &defaultTransponderData, sizeof(defaultTransponderData));
582 #endif
584 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
585 featureSet(FEATURE_BLACKBOX);
586 masterConfig.blackbox_device = BLACKBOX_DEVICE_FLASH;
587 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
588 featureSet(FEATURE_BLACKBOX);
589 masterConfig.blackbox_device = BLACKBOX_DEVICE_SDCARD;
590 #else
591 masterConfig.blackbox_device = 0;
592 #endif
594 masterConfig.blackbox_rate_num = 1;
595 masterConfig.blackbox_rate_denom = 1;
596 #endif
598 // alternative defaults settings for COLIBRI RACE targets
599 #if defined(COLIBRI_RACE)
600 masterConfig.escAndServoConfig.minthrottle = 1025;
601 masterConfig.escAndServoConfig.maxthrottle = 1980;
602 masterConfig.batteryConfig.vbatmaxcellvoltage = 45;
603 masterConfig.batteryConfig.vbatmincellvoltage = 30;
605 featureSet(FEATURE_VBAT);
606 featureSet(FEATURE_FAILSAFE);
607 #endif
609 #ifdef SPRACINGF3EVO
610 featureSet(FEATURE_TRANSPONDER);
611 featureSet(FEATURE_RSSI_ADC);
612 featureSet(FEATURE_CURRENT_METER);
613 featureSet(FEATURE_TELEMETRY);
614 #endif
616 // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
617 #ifdef ALIENFLIGHT
618 featureSet(FEATURE_RX_SERIAL);
619 featureSet(FEATURE_MOTOR_STOP);
620 featureClear(FEATURE_ONESHOT125);
621 #ifdef ALIENFLIGHTF3
622 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
623 masterConfig.batteryConfig.vbatscale = 20;
624 masterConfig.mag_hardware = MAG_NONE; // disabled by default
625 #else
626 masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
627 #endif
628 masterConfig.rxConfig.serialrx_provider = 1;
629 masterConfig.rxConfig.spektrum_sat_bind = 5;
630 masterConfig.rxConfig.spektrum_sat_bind_autoreset = 1;
631 masterConfig.escAndServoConfig.minthrottle = 1000;
632 masterConfig.escAndServoConfig.maxthrottle = 2000;
633 masterConfig.motor_pwm_rate = 32000;
634 currentProfile->pidProfile.pidController = 2;
635 masterConfig.failsafeConfig.failsafe_delay = 2;
636 masterConfig.failsafeConfig.failsafe_off_delay = 0;
637 currentControlRateProfile->rcRate8 = 100;
638 currentControlRateProfile->rates[FD_PITCH] = 20;
639 currentControlRateProfile->rates[FD_ROLL] = 20;
640 currentControlRateProfile->rates[FD_YAW] = 20;
641 parseRcChannels("TAER1234", &masterConfig.rxConfig);
643 // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
644 masterConfig.customMotorMixer[0].throttle = 1.0f;
645 masterConfig.customMotorMixer[0].roll = -0.414178f;
646 masterConfig.customMotorMixer[0].pitch = 1.0f;
647 masterConfig.customMotorMixer[0].yaw = -1.0f;
649 // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
650 masterConfig.customMotorMixer[1].throttle = 1.0f;
651 masterConfig.customMotorMixer[1].roll = -0.414178f;
652 masterConfig.customMotorMixer[1].pitch = -1.0f;
653 masterConfig.customMotorMixer[1].yaw = 1.0f;
655 // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
656 masterConfig.customMotorMixer[2].throttle = 1.0f;
657 masterConfig.customMotorMixer[2].roll = 0.414178f;
658 masterConfig.customMotorMixer[2].pitch = 1.0f;
659 masterConfig.customMotorMixer[2].yaw = 1.0f;
661 // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
662 masterConfig.customMotorMixer[3].throttle = 1.0f;
663 masterConfig.customMotorMixer[3].roll = 0.414178f;
664 masterConfig.customMotorMixer[3].pitch = -1.0f;
665 masterConfig.customMotorMixer[3].yaw = -1.0f;
667 // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
668 masterConfig.customMotorMixer[4].throttle = 1.0f;
669 masterConfig.customMotorMixer[4].roll = -1.0f;
670 masterConfig.customMotorMixer[4].pitch = -0.414178f;
671 masterConfig.customMotorMixer[4].yaw = -1.0f;
673 // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
674 masterConfig.customMotorMixer[5].throttle = 1.0f;
675 masterConfig.customMotorMixer[5].roll = 1.0f;
676 masterConfig.customMotorMixer[5].pitch = -0.414178f;
677 masterConfig.customMotorMixer[5].yaw = 1.0f;
679 // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
680 masterConfig.customMotorMixer[6].throttle = 1.0f;
681 masterConfig.customMotorMixer[6].roll = -1.0f;
682 masterConfig.customMotorMixer[6].pitch = 0.414178f;
683 masterConfig.customMotorMixer[6].yaw = 1.0f;
685 // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
686 masterConfig.customMotorMixer[7].throttle = 1.0f;
687 masterConfig.customMotorMixer[7].roll = 1.0f;
688 masterConfig.customMotorMixer[7].pitch = 0.414178f;
689 masterConfig.customMotorMixer[7].yaw = -1.0f;
690 #endif
692 // alternative defaults settings for SINGULARITY target
693 #if defined(SINGULARITY)
694 featureSet(FEATURE_BLACKBOX);
695 masterConfig.blackbox_device = 1;
696 masterConfig.blackbox_rate_num = 1;
697 masterConfig.blackbox_rate_denom = 1;
699 masterConfig.batteryConfig.vbatscale = 77;
701 featureSet(FEATURE_RX_SERIAL);
702 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
703 #endif
705 // copy first profile into remaining profile
706 for (i = 1; i < MAX_PROFILE_COUNT; i++) {
707 memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
712 static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
714 uint8_t checksum = 0;
715 const uint8_t *byteOffset;
717 for (byteOffset = data; byteOffset < (data + length); byteOffset++)
718 checksum ^= *byteOffset;
719 return checksum;
722 static bool isEEPROMContentValid(void)
724 const master_t *temp = (const master_t *) CONFIG_START_FLASH_ADDRESS;
725 uint8_t checksum = 0;
727 // check version number
728 if (EEPROM_CONF_VERSION != temp->version)
729 return false;
731 // check size and magic numbers
732 if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
733 return false;
735 // verify integrity of temporary copy
736 checksum = calculateChecksum((const uint8_t *) temp, sizeof(master_t));
737 if (checksum != 0)
738 return false;
740 // looks good, let's roll!
741 return true;
744 void activateControlRateConfig(void)
746 generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig);
749 void activateConfig(void)
751 static imuRuntimeConfig_t imuRuntimeConfig;
753 activateControlRateConfig();
755 resetAdjustmentStates();
757 useRcControlsConfig(
758 masterConfig.modeActivationConditions,
759 &masterConfig.escAndServoConfig,
760 &currentProfile->pidProfile
763 useGyroConfig(&masterConfig.gyroConfig, masterConfig.gyro_soft_lpf_hz);
765 #ifdef TELEMETRY
766 telemetryUseConfig(&masterConfig.telemetryConfig);
767 #endif
768 pidSetController(currentProfile->pidProfile.pidController);
770 #ifdef GPS
771 gpsUseProfile(&masterConfig.gpsProfile);
772 gpsUsePIDs(&currentProfile->pidProfile);
773 #endif
775 useFailsafeConfig(&masterConfig.failsafeConfig);
776 setAccelerationTrims(&masterConfig.accZero);
777 setAccelerationFilter(masterConfig.acc_lpf_hz);
779 mixerUseConfigs(
780 #ifdef USE_SERVOS
781 masterConfig.servoConf,
782 &masterConfig.gimbalConfig,
783 #endif
784 &masterConfig.flight3DConfig,
785 &masterConfig.escAndServoConfig,
786 &masterConfig.mixerConfig,
787 &masterConfig.airplaneConfig,
788 &masterConfig.rxConfig
791 imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
792 imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
793 imuRuntimeConfig.acc_unarmedcal = masterConfig.acc_unarmedcal;
794 imuRuntimeConfig.small_angle = masterConfig.small_angle;
796 imuConfigure(
797 &imuRuntimeConfig,
798 &currentProfile->pidProfile,
799 &masterConfig.accDeadband,
800 masterConfig.throttle_correction_angle
803 configureAltitudeHold(
804 &currentProfile->pidProfile,
805 &masterConfig.barometerConfig,
806 &masterConfig.rcControlsConfig,
807 &masterConfig.escAndServoConfig
810 #ifdef BARO
811 useBarometerConfig(&masterConfig.barometerConfig);
812 #endif
815 void validateAndFixConfig(void)
817 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
818 featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
821 if (featureConfigured(FEATURE_RX_PPM)) {
822 featureClear(FEATURE_RX_PARALLEL_PWM);
825 if (featureConfigured(FEATURE_RX_MSP)) {
826 featureClear(FEATURE_RX_SERIAL);
827 featureClear(FEATURE_RX_PARALLEL_PWM);
828 featureClear(FEATURE_RX_PPM);
831 if (featureConfigured(FEATURE_RX_SERIAL)) {
832 featureClear(FEATURE_RX_PARALLEL_PWM);
833 featureClear(FEATURE_RX_PPM);
836 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
837 #if defined(STM32F10X)
838 // rssi adc needs the same ports
839 featureClear(FEATURE_RSSI_ADC);
840 // current meter needs the same ports
841 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
842 featureClear(FEATURE_CURRENT_METER);
844 #endif
846 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
847 // led strip needs the same ports
848 featureClear(FEATURE_LED_STRIP);
849 #endif
851 // software serial needs free PWM ports
852 featureClear(FEATURE_SOFTSERIAL);
856 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
857 if (featureConfigured(FEATURE_SOFTSERIAL) && (
859 #ifdef USE_SOFTSERIAL1
860 || (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
861 #endif
862 #ifdef USE_SOFTSERIAL2
863 || (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
864 #endif
865 )) {
866 // led strip needs the same timer as softserial
867 featureClear(FEATURE_LED_STRIP);
869 #endif
871 #if defined(NAZE) && defined(SONAR)
872 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
873 featureClear(FEATURE_CURRENT_METER);
875 #endif
877 #if defined(OLIMEXINO) && defined(SONAR)
878 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
879 featureClear(FEATURE_CURRENT_METER);
881 #endif
883 #if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
884 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
885 featureClear(FEATURE_DISPLAY);
887 #endif
889 #ifdef STM32F303xC
890 // hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
891 masterConfig.telemetryConfig.telemetry_inversion = 1;
892 #endif
895 /*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
896 if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
897 featureClear(FEATURE_LED_STRIP);
899 #endif
902 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
903 // shared pin
904 if ((featureConfigured(FEATURE_SONAR) + featureConfigured(FEATURE_SOFTSERIAL) + featureConfigured(FEATURE_RSSI_ADC)) > 1) {
905 featureClear(FEATURE_SONAR);
906 featureClear(FEATURE_SOFTSERIAL);
907 featureClear(FEATURE_RSSI_ADC);
909 #endif
911 #if defined(COLIBRI_RACE)
912 masterConfig.serialConfig.portConfigs[0].functionMask = FUNCTION_MSP;
913 if(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_MSP)) {
914 featureClear(FEATURE_RX_PARALLEL_PWM);
915 featureClear(FEATURE_RX_MSP);
916 featureSet(FEATURE_RX_PPM);
918 if(featureConfigured(FEATURE_RX_SERIAL)) {
919 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
920 //masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
922 #endif
924 useRxConfig(&masterConfig.rxConfig);
926 serialConfig_t *serialConfig = &masterConfig.serialConfig;
928 if (!isSerialConfigValid(serialConfig)) {
929 resetSerialConfig(serialConfig);
933 void initEEPROM(void)
937 void readEEPROM(void)
939 // Sanity check
940 if (!isEEPROMContentValid())
941 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
943 suspendRxSignal();
945 // Read flash
946 memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
948 if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) // sanity check
949 masterConfig.current_profile_index = 0;
951 setProfile(masterConfig.current_profile_index);
953 validateAndFixConfig();
954 activateConfig();
956 resumeRxSignal();
959 void readEEPROMAndNotify(void)
961 // re-read written data
962 readEEPROM();
963 beeperConfirmationBeeps(1);
966 void writeEEPROM(void)
968 // Generate compile time error if the config does not fit in the reserved area of flash.
969 BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
971 FLASH_Status status = 0;
972 uint32_t wordOffset;
973 int8_t attemptsRemaining = 3;
975 suspendRxSignal();
977 // prepare checksum/version constants
978 masterConfig.version = EEPROM_CONF_VERSION;
979 masterConfig.size = sizeof(master_t);
980 masterConfig.magic_be = 0xBE;
981 masterConfig.magic_ef = 0xEF;
982 masterConfig.chk = 0; // erase checksum before recalculating
983 masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
985 // write it
986 FLASH_Unlock();
987 while (attemptsRemaining--) {
988 #ifdef STM32F303
989 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
990 #endif
991 #ifdef STM32F10X
992 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
993 #endif
994 for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
995 if (wordOffset % FLASH_PAGE_SIZE == 0) {
996 status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
997 if (status != FLASH_COMPLETE) {
998 break;
1002 status = FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS + wordOffset,
1003 *(uint32_t *) ((char *) &masterConfig + wordOffset));
1004 if (status != FLASH_COMPLETE) {
1005 break;
1008 if (status == FLASH_COMPLETE) {
1009 break;
1012 FLASH_Lock();
1014 // Flash write failed - just die now
1015 if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
1016 failureMode(FAILURE_FLASH_WRITE_FAILED);
1019 resumeRxSignal();
1022 void ensureEEPROMContainsValidData(void)
1024 if (isEEPROMContentValid()) {
1025 return;
1028 resetEEPROM();
1031 void resetEEPROM(void)
1033 resetConf();
1034 writeEEPROM();
1037 void saveConfigAndNotify(void)
1039 writeEEPROM();
1040 readEEPROMAndNotify();
1043 void changeProfile(uint8_t profileIndex)
1045 masterConfig.current_profile_index = profileIndex;
1046 writeEEPROM();
1047 readEEPROM();
1048 beeperConfirmationBeeps(profileIndex + 1);
1051 void changeControlRateProfile(uint8_t profileIndex) {
1052 if (profileIndex > MAX_RATEPROFILES) {
1053 profileIndex = MAX_RATEPROFILES - 1;
1055 setControlRateProfile(profileIndex);
1056 activateControlRateConfig();
1059 void handleOneshotFeatureChangeOnRestart(void)
1061 // Shutdown PWM on all motors prior to soft restart
1062 StopPwmAllMotors();
1063 delay(50);
1064 // Apply additional delay when OneShot125 feature changed from on to off state
1065 if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
1066 delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
1070 void latchActiveFeatures()
1072 activeFeaturesLatch = masterConfig.enabledFeatures;
1075 bool featureConfigured(uint32_t mask)
1077 return masterConfig.enabledFeatures & mask;
1080 bool feature(uint32_t mask)
1082 return activeFeaturesLatch & mask;
1085 void featureSet(uint32_t mask)
1087 masterConfig.enabledFeatures |= mask;
1090 void featureClear(uint32_t mask)
1092 masterConfig.enabledFeatures &= ~(mask);
1095 void featureClearAll()
1097 masterConfig.enabledFeatures = 0;
1100 uint32_t featureMask(void)
1102 return masterConfig.enabledFeatures;
1105 void beeperOffSet(uint32_t mask)
1107 masterConfig.beeper_off_flags |= mask;
1110 void beeperOffSetAll(uint8_t beeperCount)
1112 masterConfig.beeper_off_flags = (1 << beeperCount) -1;
1115 void beeperOffClear(uint32_t mask)
1117 masterConfig.beeper_off_flags &= ~(mask);
1120 void beeperOffClearAll(void)
1122 masterConfig.beeper_off_flags = 0;
1125 uint32_t getBeeperOffMask(void)
1127 return masterConfig.beeper_off_flags;
1130 void setBeeperOffMask(uint32_t mask)
1132 masterConfig.beeper_off_flags = mask;
1135 uint32_t getPreferredBeeperOffMask(void)
1137 return masterConfig.preferred_beeper_off_flags;
1140 void setPreferredBeeperOffMask(uint32_t mask)
1142 masterConfig.preferred_beeper_off_flags = mask;