Change dcm_kp default to 25000
[betaflight.git] / src / main / config / config.c
blob5b8ea71853b267fd7b1f1df87a8013758d31ccae
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"
30 #include "drivers/sensor.h"
31 #include "drivers/accgyro.h"
32 #include "drivers/compass.h"
33 #include "drivers/system.h"
34 #include "drivers/gpio.h"
35 #include "drivers/timer.h"
36 #include "drivers/pwm_rx.h"
37 #include "drivers/serial.h"
39 #include "sensors/sensors.h"
40 #include "sensors/gyro.h"
41 #include "sensors/compass.h"
42 #include "sensors/acceleration.h"
43 #include "sensors/barometer.h"
44 #include "sensors/boardalignment.h"
45 #include "sensors/battery.h"
47 #include "io/beeper.h"
48 #include "io/serial.h"
49 #include "io/gimbal.h"
50 #include "io/escservo.h"
51 #include "io/rc_controls.h"
52 #include "io/rc_curves.h"
53 #include "io/ledstrip.h"
54 #include "io/gps.h"
56 #include "rx/rx.h"
58 #include "telemetry/telemetry.h"
60 #include "flight/mixer.h"
61 #include "flight/pid.h"
62 #include "flight/imu.h"
63 #include "flight/failsafe.h"
64 #include "flight/altitudehold.h"
65 #include "flight/navigation.h"
67 #include "config/runtime_config.h"
68 #include "config/config.h"
70 #include "config/config_profile.h"
71 #include "config/config_master.h"
73 #define BRUSHED_MOTORS_PWM_RATE 16000
74 #define BRUSHLESS_MOTORS_PWM_RATE 400
76 void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse);
78 #if !defined(FLASH_SIZE)
79 #error "Flash size not defined for target. (specify in KB)"
80 #endif
83 #ifndef FLASH_PAGE_SIZE
84 #ifdef STM32F303xC
85 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
86 #endif
88 #ifdef STM32F10X_MD
89 #define FLASH_PAGE_SIZE ((uint16_t)0x400)
90 #endif
92 #ifdef STM32F10X_HD
93 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
94 #endif
95 #endif
97 #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
98 #ifdef STM32F10X_MD
99 #define FLASH_PAGE_COUNT 128
100 #endif
102 #ifdef STM32F10X_HD
103 #define FLASH_PAGE_COUNT 128
104 #endif
105 #endif
107 #if defined(FLASH_SIZE)
108 #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
109 #endif
111 #if !defined(FLASH_PAGE_SIZE)
112 #error "Flash page size not defined for target."
113 #endif
115 #if !defined(FLASH_PAGE_COUNT)
116 #error "Flash page count not defined for target."
117 #endif
119 #if FLASH_SIZE <= 128
120 #define FLASH_TO_RESERVE_FOR_CONFIG 0x800
121 #else
122 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
123 #endif
125 // use the last flash pages for storage
126 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
128 master_t masterConfig; // master config struct with data independent from profiles
129 profile_t *currentProfile;
130 static uint32_t activeFeaturesLatch = 0;
132 static uint8_t currentControlRateProfileIndex = 0;
133 controlRateConfig_t *currentControlRateProfile;
135 static const uint8_t EEPROM_CONF_VERSION = 112;
137 static void resetAccelerometerTrims(flightDynamicsTrims_t *accelerometerTrims)
139 accelerometerTrims->values.pitch = 0;
140 accelerometerTrims->values.roll = 0;
141 accelerometerTrims->values.yaw = 0;
144 static void resetPidProfile(pidProfile_t *pidProfile)
146 pidProfile->pidController = 1;
148 pidProfile->P8[ROLL] = 40;
149 pidProfile->I8[ROLL] = 30;
150 pidProfile->D8[ROLL] = 18;
151 pidProfile->P8[PITCH] = 40;
152 pidProfile->I8[PITCH] = 30;
153 pidProfile->D8[PITCH] = 18;
154 pidProfile->P8[YAW] = 95;
155 pidProfile->I8[YAW] = 50;
156 pidProfile->D8[YAW] = 10;
157 pidProfile->P8[PIDALT] = 50;
158 pidProfile->I8[PIDALT] = 0;
159 pidProfile->D8[PIDALT] = 0;
160 pidProfile->P8[PIDPOS] = 15; // POSHOLD_P * 100;
161 pidProfile->I8[PIDPOS] = 0; // POSHOLD_I * 100;
162 pidProfile->D8[PIDPOS] = 0;
163 pidProfile->P8[PIDPOSR] = 34; // POSHOLD_RATE_P * 10;
164 pidProfile->I8[PIDPOSR] = 14; // POSHOLD_RATE_I * 100;
165 pidProfile->D8[PIDPOSR] = 53; // POSHOLD_RATE_D * 1000;
166 pidProfile->P8[PIDNAVR] = 25; // NAV_P * 10;
167 pidProfile->I8[PIDNAVR] = 33; // NAV_I * 100;
168 pidProfile->D8[PIDNAVR] = 83; // NAV_D * 1000;
169 pidProfile->P8[PIDLEVEL] = 90;
170 pidProfile->I8[PIDLEVEL] = 10;
171 pidProfile->D8[PIDLEVEL] = 100;
172 pidProfile->P8[PIDMAG] = 40;
173 pidProfile->P8[PIDVEL] = 120;
174 pidProfile->I8[PIDVEL] = 45;
175 pidProfile->D8[PIDVEL] = 1;
177 pidProfile->dterm_cut_hz = 40;
179 pidProfile->P_f[ROLL] = 1.5f; // new PID with preliminary defaults test carefully
180 pidProfile->I_f[ROLL] = 0.4f;
181 pidProfile->D_f[ROLL] = 0.02f;
182 pidProfile->P_f[PITCH] = 1.5f;
183 pidProfile->I_f[PITCH] = 0.4f;
184 pidProfile->D_f[PITCH] = 0.02f;
185 pidProfile->P_f[YAW] = 4.0f;
186 pidProfile->I_f[YAW] = 0.7f;
187 pidProfile->D_f[YAW] = 0.00f;
188 pidProfile->A_level = 6.0f;
189 pidProfile->H_level = 6.0f;
190 pidProfile->H_sensitivity = 75;
192 #ifdef GTUNE
193 pidProfile->gtune_lolimP[ROLL] = 10; // [0..200] Lower limit of ROLL P during G tune.
194 pidProfile->gtune_lolimP[PITCH] = 10; // [0..200] Lower limit of PITCH P during G tune.
195 pidProfile->gtune_lolimP[YAW] = 10; // [0..200] Lower limit of YAW P during G tune.
196 pidProfile->gtune_hilimP[ROLL] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
197 pidProfile->gtune_hilimP[PITCH] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
198 pidProfile->gtune_hilimP[YAW] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
199 pidProfile->gtune_pwr = 0; // [0..10] Strength of adjustment
200 pidProfile->gtune_settle_time = 450; // [200..1000] Settle time in ms
201 pidProfile->gtune_average_cycles = 16; // [8..128] Number of looptime cycles used for gyro average calculation
202 #endif
205 #ifdef GPS
206 void resetGpsProfile(gpsProfile_t *gpsProfile)
208 gpsProfile->gps_wp_radius = 200;
209 gpsProfile->gps_lpf = 20;
210 gpsProfile->nav_slew_rate = 30;
211 gpsProfile->nav_controls_heading = 1;
212 gpsProfile->nav_speed_min = 100;
213 gpsProfile->nav_speed_max = 300;
214 gpsProfile->ap_mode = 40;
216 #endif
218 void resetBarometerConfig(barometerConfig_t *barometerConfig)
220 barometerConfig->baro_sample_count = 21;
221 barometerConfig->baro_noise_lpf = 0.6f;
222 barometerConfig->baro_cf_vel = 0.985f;
223 barometerConfig->baro_cf_alt = 0.965f;
226 void resetSensorAlignment(sensorAlignmentConfig_t *sensorAlignmentConfig)
228 sensorAlignmentConfig->gyro_align = ALIGN_DEFAULT;
229 sensorAlignmentConfig->acc_align = ALIGN_DEFAULT;
230 sensorAlignmentConfig->mag_align = ALIGN_DEFAULT;
233 void resetEscAndServoConfig(escAndServoConfig_t *escAndServoConfig)
235 escAndServoConfig->minthrottle = 1150;
236 escAndServoConfig->maxthrottle = 1850;
237 escAndServoConfig->mincommand = 1000;
238 escAndServoConfig->servoCenterPulse = 1500;
241 void resetFlight3DConfig(flight3DConfig_t *flight3DConfig)
243 flight3DConfig->deadband3d_low = 1406;
244 flight3DConfig->deadband3d_high = 1514;
245 flight3DConfig->neutral3d = 1460;
246 flight3DConfig->deadband3d_throttle = 50;
249 void resetTelemetryConfig(telemetryConfig_t *telemetryConfig)
251 telemetryConfig->telemetry_inversion = 0;
252 telemetryConfig->telemetry_switch = 0;
253 telemetryConfig->gpsNoFixLatitude = 0;
254 telemetryConfig->gpsNoFixLongitude = 0;
255 telemetryConfig->frsky_coordinate_format = FRSKY_FORMAT_DMS;
256 telemetryConfig->frsky_unit = FRSKY_UNIT_METRICS;
257 telemetryConfig->frsky_vfas_precision = 0;
258 telemetryConfig->hottAlarmSoundInterval = 5;
261 void resetBatteryConfig(batteryConfig_t *batteryConfig)
263 batteryConfig->vbatscale = VBAT_SCALE_DEFAULT;
264 batteryConfig->vbatresdivval = VBAT_RESDIVVAL_DEFAULT;
265 batteryConfig->vbatresdivmultiplier = VBAT_RESDIVMULTIPLIER_DEFAULT;
266 batteryConfig->vbatmaxcellvoltage = 43;
267 batteryConfig->vbatmincellvoltage = 33;
268 batteryConfig->vbatwarningcellvoltage = 35;
269 batteryConfig->currentMeterOffset = 0;
270 batteryConfig->currentMeterScale = 400; // for Allegro ACS758LCB-100U (40mV/A)
271 batteryConfig->batteryCapacity = 0;
272 batteryConfig->currentMeterType = CURRENT_SENSOR_ADC;
275 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
276 #define FIRST_PORT_INDEX 1
277 #define SECOND_PORT_INDEX 0
278 #else
279 #define FIRST_PORT_INDEX 0
280 #define SECOND_PORT_INDEX 1
281 #endif
283 void resetSerialConfig(serialConfig_t *serialConfig)
285 uint8_t index;
286 memset(serialConfig, 0, sizeof(serialConfig_t));
288 for (index = 0; index < SERIAL_PORT_COUNT; index++) {
289 serialConfig->portConfigs[index].identifier = serialPortIdentifiers[index];
290 serialConfig->portConfigs[index].msp_baudrateIndex = BAUD_115200;
291 serialConfig->portConfigs[index].gps_baudrateIndex = BAUD_57600;
292 serialConfig->portConfigs[index].telemetry_baudrateIndex = BAUD_AUTO;
293 serialConfig->portConfigs[index].blackbox_baudrateIndex = BAUD_115200;
296 serialConfig->portConfigs[0].functionMask = FUNCTION_MSP;
298 #ifdef CC3D
299 // This allows MSP connection via USART & VCP so the board can be reconfigured.
300 serialConfig->portConfigs[1].functionMask = FUNCTION_MSP;
301 #endif
303 serialConfig->reboot_character = 'R';
306 static void resetControlRateConfig(controlRateConfig_t *controlRateConfig) {
307 controlRateConfig->rcRate8 = 100;
308 controlRateConfig->rcExpo8 = 70;
309 controlRateConfig->thrMid8 = 50;
310 controlRateConfig->thrExpo8 = 0;
311 controlRateConfig->dynThrPID = 0;
312 controlRateConfig->rcYawExpo8 = 20;
313 controlRateConfig->tpa_breakpoint = 1500;
315 for (uint8_t axis = 0; axis < FLIGHT_DYNAMICS_INDEX_COUNT; axis++) {
316 controlRateConfig->rates[axis] = 0;
321 void resetRcControlsConfig(rcControlsConfig_t *rcControlsConfig) {
322 rcControlsConfig->deadband = 0;
323 rcControlsConfig->yaw_deadband = 0;
324 rcControlsConfig->alt_hold_deadband = 40;
325 rcControlsConfig->alt_hold_fast_change = 1;
328 void resetMixerConfig(mixerConfig_t *mixerConfig) {
329 mixerConfig->pid_at_min_throttle = 1;
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];
349 uint8_t getCurrentControlRateProfile(void)
351 return currentControlRateProfileIndex;
354 controlRateConfig_t *getControlRateConfig(uint8_t profileIndex) {
355 return &masterConfig.controlRateProfiles[profileIndex];
358 static void setControlRateProfile(uint8_t profileIndex)
360 currentControlRateProfileIndex = profileIndex;
361 currentControlRateProfile = &masterConfig.controlRateProfiles[profileIndex];
364 uint16_t getCurrentMinthrottle(void)
366 return masterConfig.escAndServoConfig.minthrottle;
369 // Default settings
370 static void resetConf(void)
372 int i;
374 // Clear all configuration
375 memset(&masterConfig, 0, sizeof(master_t));
376 setProfile(0);
377 setControlRateProfile(0);
379 masterConfig.beeper_off.flags = BEEPER_OFF_FLAGS_MIN;
380 masterConfig.version = EEPROM_CONF_VERSION;
381 masterConfig.mixerMode = MIXER_QUADX;
382 featureClearAll();
383 #if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB)
384 featureSet(FEATURE_RX_PPM);
385 #endif
387 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
388 // only enable the VBAT feature by default if the board has a voltage divider otherwise
389 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
390 featureSet(FEATURE_VBAT);
391 #endif
393 featureSet(FEATURE_FAILSAFE);
394 featureSet(FEATURE_ONESHOT125);
396 // global settings
397 masterConfig.current_profile_index = 0; // default profile
398 masterConfig.dcm_kp = 25000; // 1.0 * 10000
399 masterConfig.dcm_ki = 0; // 0.003 * 10000
401 resetAccelerometerTrims(&masterConfig.accZero);
403 resetSensorAlignment(&masterConfig.sensorAlignmentConfig);
405 masterConfig.boardAlignment.rollDegrees = 0;
406 masterConfig.boardAlignment.pitchDegrees = 0;
407 masterConfig.boardAlignment.yawDegrees = 0;
408 masterConfig.acc_hardware = ACC_DEFAULT; // default/autodetect
409 masterConfig.max_angle_inclination = 600; // 50 degrees
410 masterConfig.yaw_control_direction = 1;
411 masterConfig.gyroConfig.gyroMovementCalibrationThreshold = 32;
413 // xxx_hardware: 0:default/autodetect, 1: disable
414 masterConfig.mag_hardware = 0;
416 masterConfig.baro_hardware = 0;
418 resetBatteryConfig(&masterConfig.batteryConfig);
420 resetTelemetryConfig(&masterConfig.telemetryConfig);
422 masterConfig.rxConfig.serialrx_provider = 0;
423 masterConfig.rxConfig.spektrum_sat_bind = 0;
424 masterConfig.rxConfig.midrc = 1500;
425 masterConfig.rxConfig.mincheck = 1100;
426 masterConfig.rxConfig.maxcheck = 1900;
427 masterConfig.rxConfig.rx_min_usec = 885; // any of first 4 channels below this value will trigger rx loss detection
428 masterConfig.rxConfig.rx_max_usec = 2115; // any of first 4 channels above this value will trigger rx loss detection
430 for (i = 0; i < MAX_SUPPORTED_RC_CHANNEL_COUNT; i++) {
431 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[i];
432 channelFailsafeConfiguration->mode = (i < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_MODE_AUTO : RX_FAILSAFE_MODE_HOLD;
433 channelFailsafeConfiguration->step = (i == THROTTLE) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.rx_min_usec) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig.rxConfig.midrc);
436 masterConfig.rxConfig.rssi_channel = 0;
437 masterConfig.rxConfig.rssi_scale = RSSI_SCALE_DEFAULT;
438 masterConfig.rxConfig.rssi_ppm_invert = 0;
440 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
442 masterConfig.inputFilteringMode = INPUT_FILTERING_DISABLED;
444 masterConfig.retarded_arm = 0;
445 masterConfig.disarm_kill_switch = 1;
446 masterConfig.auto_disarm_delay = 5;
447 masterConfig.small_angle = 25;
449 resetMixerConfig(&masterConfig.mixerConfig);
451 masterConfig.airplaneConfig.fixedwing_althold_dir = 1;
453 // Motor/ESC/Servo
454 resetEscAndServoConfig(&masterConfig.escAndServoConfig);
455 resetFlight3DConfig(&masterConfig.flight3DConfig);
457 #ifdef BRUSHED_MOTORS
458 masterConfig.motor_pwm_rate = BRUSHED_MOTORS_PWM_RATE;
459 #else
460 masterConfig.motor_pwm_rate = BRUSHLESS_MOTORS_PWM_RATE;
461 #endif
462 masterConfig.servo_pwm_rate = 50;
463 masterConfig.use_fast_pwm = 0;
465 #ifdef GPS
466 // gps/nav stuff
467 masterConfig.gpsConfig.provider = GPS_NMEA;
468 masterConfig.gpsConfig.sbasMode = SBAS_AUTO;
469 masterConfig.gpsConfig.autoConfig = GPS_AUTOCONFIG_ON;
470 masterConfig.gpsConfig.autoBaud = GPS_AUTOBAUD_OFF;
471 #endif
473 resetSerialConfig(&masterConfig.serialConfig);
475 masterConfig.emf_avoidance = 0;
477 resetPidProfile(&currentProfile->pidProfile);
479 resetControlRateConfig(&masterConfig.controlRateProfiles[0]);
481 // for (i = 0; i < CHECKBOXITEMS; i++)
482 // cfg.activate[i] = 0;
484 resetRollAndPitchTrims(&currentProfile->accelerometerTrims);
486 currentProfile->mag_declination = 0;
487 currentProfile->acc_cut_hz = 15;
488 currentProfile->accz_lpf_cutoff = 5.0f;
489 currentProfile->accDeadband.xy = 40;
490 currentProfile->accDeadband.z = 40;
491 currentProfile->acc_unarmedcal = 1;
493 resetBarometerConfig(&currentProfile->barometerConfig);
495 // Radio
496 parseRcChannels("AETR1234", &masterConfig.rxConfig);
498 resetRcControlsConfig(&currentProfile->rcControlsConfig);
500 currentProfile->throttle_correction_value = 0; // could 10 with althold or 40 for fpv
501 currentProfile->throttle_correction_angle = 800; // could be 80.0 deg with atlhold or 45.0 for fpv
503 // Failsafe Variables
504 masterConfig.failsafeConfig.failsafe_delay = 10; // 1sec
505 masterConfig.failsafeConfig.failsafe_off_delay = 10; // 1sec
506 masterConfig.failsafeConfig.failsafe_throttle = 1000; // default throttle off.
507 masterConfig.failsafeConfig.failsafe_kill_switch = 0; // default failsafe switch action is identical to rc link loss
508 masterConfig.failsafeConfig.failsafe_throttle_low_delay = 100; // default throttle low delay for "just disarm" on failsafe condition
510 #ifdef USE_SERVOS
511 // servos
512 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
513 currentProfile->servoConf[i].min = DEFAULT_SERVO_MIN;
514 currentProfile->servoConf[i].max = DEFAULT_SERVO_MAX;
515 currentProfile->servoConf[i].middle = DEFAULT_SERVO_MIDDLE;
516 currentProfile->servoConf[i].rate = 100;
517 currentProfile->servoConf[i].angleAtMin = DEFAULT_SERVO_MIN_ANGLE;
518 currentProfile->servoConf[i].angleAtMax = DEFAULT_SERVO_MAX_ANGLE;
519 currentProfile->servoConf[i].forwardFromChannel = CHANNEL_FORWARDING_DISABLED;
522 // gimbal
523 currentProfile->gimbalConfig.mode = GIMBAL_MODE_NORMAL;
524 #endif
526 #ifdef GPS
527 resetGpsProfile(&currentProfile->gpsProfile);
528 #endif
530 // custom mixer. clear by defaults.
531 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
532 masterConfig.customMotorMixer[i].throttle = 0.0f;
534 #ifdef LED_STRIP
535 applyDefaultColors(masterConfig.colors, CONFIGURABLE_COLOR_COUNT);
536 applyDefaultLedStripConfig(masterConfig.ledConfigs);
537 #endif
539 #ifdef BLACKBOX
540 #ifdef SPRACINGF3
541 featureSet(FEATURE_BLACKBOX);
542 masterConfig.blackbox_device = 1;
543 #else
544 masterConfig.blackbox_device = 0;
545 #endif
546 masterConfig.blackbox_rate_num = 1;
547 masterConfig.blackbox_rate_denom = 1;
548 #endif
550 // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets
551 #ifdef ALIENWII32
552 featureSet(FEATURE_RX_SERIAL);
553 featureSet(FEATURE_MOTOR_STOP);
554 #ifdef ALIENWIIF3
555 masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
556 masterConfig.batteryConfig.vbatscale = 20;
557 #else
558 masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_RX_SERIAL;
559 #endif
560 masterConfig.rxConfig.serialrx_provider = 1;
561 masterConfig.rxConfig.spektrum_sat_bind = 5;
562 masterConfig.escAndServoConfig.minthrottle = 1000;
563 masterConfig.escAndServoConfig.maxthrottle = 2000;
564 masterConfig.motor_pwm_rate = 32000;
565 currentProfile->pidProfile.pidController = 3;
566 currentProfile->pidProfile.P8[ROLL] = 36;
567 currentProfile->pidProfile.P8[PITCH] = 36;
568 masterConfig.failsafeConfig.failsafe_delay = 2;
569 masterConfig.failsafeConfig.failsafe_off_delay = 0;
570 currentControlRateProfile->rcRate8 = 130;
571 currentControlRateProfile->rates[FD_PITCH] = 20;
572 currentControlRateProfile->rates[FD_ROLL] = 20;
573 currentControlRateProfile->rates[FD_YAW] = 100;
574 parseRcChannels("TAER1234", &masterConfig.rxConfig);
576 // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
577 masterConfig.customMotorMixer[0].throttle = 1.0f;
578 masterConfig.customMotorMixer[0].roll = -0.414178f;
579 masterConfig.customMotorMixer[0].pitch = 1.0f;
580 masterConfig.customMotorMixer[0].yaw = -1.0f;
582 // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
583 masterConfig.customMotorMixer[1].throttle = 1.0f;
584 masterConfig.customMotorMixer[1].roll = -0.414178f;
585 masterConfig.customMotorMixer[1].pitch = -1.0f;
586 masterConfig.customMotorMixer[1].yaw = 1.0f;
588 // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
589 masterConfig.customMotorMixer[2].throttle = 1.0f;
590 masterConfig.customMotorMixer[2].roll = 0.414178f;
591 masterConfig.customMotorMixer[2].pitch = 1.0f;
592 masterConfig.customMotorMixer[2].yaw = 1.0f;
594 // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
595 masterConfig.customMotorMixer[3].throttle = 1.0f;
596 masterConfig.customMotorMixer[3].roll = 0.414178f;
597 masterConfig.customMotorMixer[3].pitch = -1.0f;
598 masterConfig.customMotorMixer[3].yaw = -1.0f;
600 // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
601 masterConfig.customMotorMixer[4].throttle = 1.0f;
602 masterConfig.customMotorMixer[4].roll = -1.0f;
603 masterConfig.customMotorMixer[4].pitch = -0.414178f;
604 masterConfig.customMotorMixer[4].yaw = -1.0f;
606 // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
607 masterConfig.customMotorMixer[5].throttle = 1.0f;
608 masterConfig.customMotorMixer[5].roll = 1.0f;
609 masterConfig.customMotorMixer[5].pitch = -0.414178f;
610 masterConfig.customMotorMixer[5].yaw = 1.0f;
612 // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
613 masterConfig.customMotorMixer[6].throttle = 1.0f;
614 masterConfig.customMotorMixer[6].roll = -1.0f;
615 masterConfig.customMotorMixer[6].pitch = 0.414178f;
616 masterConfig.customMotorMixer[6].yaw = 1.0f;
618 // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
619 masterConfig.customMotorMixer[7].throttle = 1.0f;
620 masterConfig.customMotorMixer[7].roll = 1.0f;
621 masterConfig.customMotorMixer[7].pitch = 0.414178f;
622 masterConfig.customMotorMixer[7].yaw = -1.0f;
623 #endif
625 // copy first profile into remaining profile
626 for (i = 1; i < MAX_PROFILE_COUNT; i++) {
627 memcpy(&masterConfig.profile[i], currentProfile, sizeof(profile_t));
630 // copy first control rate config into remaining profile
631 for (i = 1; i < MAX_CONTROL_RATE_PROFILE_COUNT; i++) {
632 memcpy(&masterConfig.controlRateProfiles[i], currentControlRateProfile, sizeof(controlRateConfig_t));
635 for (i = 1; i < MAX_PROFILE_COUNT; i++) {
636 masterConfig.profile[i].defaultRateProfileIndex = i % MAX_CONTROL_RATE_PROFILE_COUNT;
640 static uint8_t calculateChecksum(const uint8_t *data, uint32_t length)
642 uint8_t checksum = 0;
643 const uint8_t *byteOffset;
645 for (byteOffset = data; byteOffset < (data + length); byteOffset++)
646 checksum ^= *byteOffset;
647 return checksum;
650 static bool isEEPROMContentValid(void)
652 const master_t *temp = (const master_t *) CONFIG_START_FLASH_ADDRESS;
653 uint8_t checksum = 0;
655 // check version number
656 if (EEPROM_CONF_VERSION != temp->version)
657 return false;
659 // check size and magic numbers
660 if (temp->size != sizeof(master_t) || temp->magic_be != 0xBE || temp->magic_ef != 0xEF)
661 return false;
663 // verify integrity of temporary copy
664 checksum = calculateChecksum((const uint8_t *) temp, sizeof(master_t));
665 if (checksum != 0)
666 return false;
668 // looks good, let's roll!
669 return true;
672 void activateControlRateConfig(void)
674 generatePitchRollCurve(currentControlRateProfile);
675 generateYawCurve(currentControlRateProfile);
676 generateThrottleCurve(currentControlRateProfile, &masterConfig.escAndServoConfig);
679 void activateConfig(void)
681 static imuRuntimeConfig_t imuRuntimeConfig;
683 activateControlRateConfig();
685 resetAdjustmentStates();
687 useRcControlsConfig(
688 currentProfile->modeActivationConditions,
689 &masterConfig.escAndServoConfig,
690 &currentProfile->pidProfile
693 useGyroConfig(&masterConfig.gyroConfig);
695 #ifdef TELEMETRY
696 telemetryUseConfig(&masterConfig.telemetryConfig);
697 #endif
699 pidSetController(currentProfile->pidProfile.pidController);
701 #ifdef GPS
702 gpsUseProfile(&currentProfile->gpsProfile);
703 gpsUsePIDs(&currentProfile->pidProfile);
704 #endif
706 useFailsafeConfig(&masterConfig.failsafeConfig);
707 setAccelerationTrims(&masterConfig.accZero);
709 mixerUseConfigs(
710 #ifdef USE_SERVOS
711 currentProfile->servoConf,
712 &currentProfile->gimbalConfig,
713 #endif
714 &masterConfig.flight3DConfig,
715 &masterConfig.escAndServoConfig,
716 &masterConfig.mixerConfig,
717 &masterConfig.airplaneConfig,
718 &masterConfig.rxConfig
721 imuRuntimeConfig.dcm_kp = masterConfig.dcm_kp / 10000.0f;
722 imuRuntimeConfig.dcm_ki = masterConfig.dcm_ki / 10000.0f;
723 imuRuntimeConfig.acc_cut_hz = currentProfile->acc_cut_hz;
724 imuRuntimeConfig.acc_unarmedcal = currentProfile->acc_unarmedcal;
725 imuRuntimeConfig.small_angle = masterConfig.small_angle;
727 imuConfigure(
728 &imuRuntimeConfig,
729 &currentProfile->pidProfile,
730 &currentProfile->accDeadband,
731 currentProfile->accz_lpf_cutoff,
732 currentProfile->throttle_correction_angle
735 configureAltitudeHold(
736 &currentProfile->pidProfile,
737 &currentProfile->barometerConfig,
738 &currentProfile->rcControlsConfig,
739 &masterConfig.escAndServoConfig
742 #ifdef BARO
743 useBarometerConfig(&currentProfile->barometerConfig);
744 #endif
747 void validateAndFixConfig(void)
749 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM) || featureConfigured(FEATURE_RX_PPM) || featureConfigured(FEATURE_RX_SERIAL) || featureConfigured(FEATURE_RX_MSP))) {
750 featureSet(FEATURE_RX_PARALLEL_PWM); // Consider changing the default to PPM
753 if (featureConfigured(FEATURE_RX_PPM)) {
754 featureClear(FEATURE_RX_PARALLEL_PWM);
757 if (featureConfigured(FEATURE_RX_MSP)) {
758 featureClear(FEATURE_RX_SERIAL);
759 featureClear(FEATURE_RX_PARALLEL_PWM);
760 featureClear(FEATURE_RX_PPM);
763 if (featureConfigured(FEATURE_RX_SERIAL)) {
764 featureClear(FEATURE_RX_PARALLEL_PWM);
765 featureClear(FEATURE_RX_PPM);
768 if (featureConfigured(FEATURE_RX_PARALLEL_PWM)) {
769 #if defined(STM32F10X)
770 // rssi adc needs the same ports
771 featureClear(FEATURE_RSSI_ADC);
772 // current meter needs the same ports
773 if (masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
774 featureClear(FEATURE_CURRENT_METER);
776 #endif
778 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
779 // led strip needs the same ports
780 featureClear(FEATURE_LED_STRIP);
781 #endif
783 // software serial needs free PWM ports
784 featureClear(FEATURE_SOFTSERIAL);
788 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
789 if (featureConfigured(FEATURE_SOFTSERIAL) && (
791 #ifdef USE_SOFTSERIAL1
792 || (LED_STRIP_TIMER == SOFTSERIAL_1_TIMER)
793 #endif
794 #ifdef USE_SOFTSERIAL2
795 || (LED_STRIP_TIMER == SOFTSERIAL_2_TIMER)
796 #endif
797 )) {
798 // led strip needs the same timer as softserial
799 featureClear(FEATURE_LED_STRIP);
801 #endif
803 #if defined(NAZE) && defined(SONAR)
804 if (featureConfigured(FEATURE_RX_PARALLEL_PWM) && featureConfigured(FEATURE_SONAR) && featureConfigured(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
805 featureClear(FEATURE_CURRENT_METER);
807 #endif
809 #if defined(OLIMEXINO) && defined(SONAR)
810 if (feature(FEATURE_SONAR) && feature(FEATURE_CURRENT_METER) && masterConfig.batteryConfig.currentMeterType == CURRENT_SENSOR_ADC) {
811 featureClear(FEATURE_CURRENT_METER);
813 #endif
815 #if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
816 if (doesConfigurationUsePort(SERIAL_PORT_USART3) && feature(FEATURE_DISPLAY)) {
817 featureClear(FEATURE_DISPLAY);
819 #endif
821 #ifdef STM32F303xC
822 // hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
823 masterConfig.telemetryConfig.telemetry_inversion = 1;
824 #endif
827 * The retarded_arm setting is incompatible with pid_at_min_throttle because full roll causes the craft to roll over on the ground.
828 * The pid_at_min_throttle implementation ignores yaw on the ground, but doesn't currently ignore roll when retarded_arm is enabled.
830 if (masterConfig.retarded_arm && masterConfig.mixerConfig.pid_at_min_throttle) {
831 masterConfig.mixerConfig.pid_at_min_throttle = 0;
834 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1)
835 if (feature(FEATURE_SONAR) && feature(FEATURE_SOFTSERIAL)) {
836 featureClear(FEATURE_SONAR);
838 #endif
840 useRxConfig(&masterConfig.rxConfig);
842 serialConfig_t *serialConfig = &masterConfig.serialConfig;
844 if (!isSerialConfigValid(serialConfig)) {
845 resetSerialConfig(serialConfig);
849 void initEEPROM(void)
853 void readEEPROM(void)
855 // Sanity check
856 if (!isEEPROMContentValid())
857 failureMode(FAILURE_INVALID_EEPROM_CONTENTS);
859 suspendRxSignal();
861 // Read flash
862 memcpy(&masterConfig, (char *) CONFIG_START_FLASH_ADDRESS, sizeof(master_t));
864 if (masterConfig.current_profile_index > MAX_PROFILE_COUNT - 1) // sanity check
865 masterConfig.current_profile_index = 0;
867 setProfile(masterConfig.current_profile_index);
869 if (currentProfile->defaultRateProfileIndex > MAX_CONTROL_RATE_PROFILE_COUNT - 1) // sanity check
870 currentProfile->defaultRateProfileIndex = 0;
872 setControlRateProfile(currentProfile->defaultRateProfileIndex);
874 validateAndFixConfig();
875 activateConfig();
877 resumeRxSignal();
880 void readEEPROMAndNotify(void)
882 // re-read written data
883 readEEPROM();
884 beeperConfirmationBeeps(1);
887 void writeEEPROM(void)
889 // Generate compile time error if the config does not fit in the reserved area of flash.
890 BUILD_BUG_ON(sizeof(master_t) > FLASH_TO_RESERVE_FOR_CONFIG);
892 FLASH_Status status = 0;
893 uint32_t wordOffset;
894 int8_t attemptsRemaining = 3;
896 suspendRxSignal();
898 // prepare checksum/version constants
899 masterConfig.version = EEPROM_CONF_VERSION;
900 masterConfig.size = sizeof(master_t);
901 masterConfig.magic_be = 0xBE;
902 masterConfig.magic_ef = 0xEF;
903 masterConfig.chk = 0; // erase checksum before recalculating
904 masterConfig.chk = calculateChecksum((const uint8_t *) &masterConfig, sizeof(master_t));
906 // write it
907 FLASH_Unlock();
908 while (attemptsRemaining--) {
909 #ifdef STM32F303
910 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPERR);
911 #endif
912 #ifdef STM32F10X
913 FLASH_ClearFlag(FLASH_FLAG_EOP | FLASH_FLAG_PGERR | FLASH_FLAG_WRPRTERR);
914 #endif
915 for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) {
916 if (wordOffset % FLASH_PAGE_SIZE == 0) {
917 status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset);
918 if (status != FLASH_COMPLETE) {
919 break;
923 status = FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS + wordOffset,
924 *(uint32_t *) ((char *) &masterConfig + wordOffset));
925 if (status != FLASH_COMPLETE) {
926 break;
929 if (status == FLASH_COMPLETE) {
930 break;
933 FLASH_Lock();
935 // Flash write failed - just die now
936 if (status != FLASH_COMPLETE || !isEEPROMContentValid()) {
937 failureMode(FAILURE_FLASH_WRITE_FAILED);
940 resumeRxSignal();
943 void ensureEEPROMContainsValidData(void)
945 if (isEEPROMContentValid()) {
946 return;
949 resetEEPROM();
952 void resetEEPROM(void)
954 resetConf();
955 writeEEPROM();
958 void saveConfigAndNotify(void)
960 writeEEPROM();
961 readEEPROMAndNotify();
964 void changeProfile(uint8_t profileIndex)
966 masterConfig.current_profile_index = profileIndex;
967 writeEEPROM();
968 readEEPROM();
969 beeperConfirmationBeeps(profileIndex + 1);
972 void changeControlRateProfile(uint8_t profileIndex)
974 if (profileIndex > MAX_CONTROL_RATE_PROFILE_COUNT) {
975 profileIndex = MAX_CONTROL_RATE_PROFILE_COUNT - 1;
977 setControlRateProfile(profileIndex);
978 activateControlRateConfig();
981 void handleOneshotFeatureChangeOnRestart(void)
983 // Shutdown PWM on all motors prior to soft restart
984 StopPwmAllMotors();
985 delay(50);
986 // Apply additional delay when OneShot125 feature changed from on to off state
987 if (feature(FEATURE_ONESHOT125) && !featureConfigured(FEATURE_ONESHOT125)) {
988 delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS);
992 void latchActiveFeatures()
994 activeFeaturesLatch = masterConfig.enabledFeatures;
997 bool featureConfigured(uint32_t mask)
999 return masterConfig.enabledFeatures & mask;
1002 bool feature(uint32_t mask)
1004 return activeFeaturesLatch & mask;
1007 void featureSet(uint32_t mask)
1009 masterConfig.enabledFeatures |= mask;
1012 void featureClear(uint32_t mask)
1014 masterConfig.enabledFeatures &= ~(mask);
1017 void featureClearAll()
1019 masterConfig.enabledFeatures = 0;
1022 uint32_t featureMask(void)
1024 return masterConfig.enabledFeatures;