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/>.
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"
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)"
85 #ifndef FLASH_PAGE_SIZE
87 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
91 #define FLASH_PAGE_SIZE ((uint16_t)0x400)
95 #define FLASH_PAGE_SIZE ((uint16_t)0x800)
99 #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT)
101 #define FLASH_PAGE_COUNT 128
105 #define FLASH_PAGE_COUNT 128
109 #if defined(FLASH_SIZE)
110 #define FLASH_PAGE_COUNT ((FLASH_SIZE * 0x400) / FLASH_PAGE_SIZE)
113 #if !defined(FLASH_PAGE_SIZE)
114 #error "Flash page size not defined for target."
117 #if !defined(FLASH_PAGE_COUNT)
118 #error "Flash page count not defined for target."
121 #if FLASH_SIZE <= 128
122 #define FLASH_TO_RESERVE_FOR_CONFIG 0x800
124 #define FLASH_TO_RESERVE_FOR_CONFIG 0x1000
127 // use the last flash pages for storage
128 #ifdef CUSTOM_FLASH_MEMORY_ADDRESS
129 size_t custom_flash_memory_address
= 0;
130 #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address)
132 // use the last flash pages for storage
133 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
136 master_t masterConfig
; // master config struct with data independent from profiles
137 profile_t
*currentProfile
;
138 static uint32_t activeFeaturesLatch
= 0;
140 static uint8_t currentControlRateProfileIndex
= 0;
141 controlRateConfig_t
*currentControlRateProfile
;
143 static const uint8_t EEPROM_CONF_VERSION
= 135;
145 static void resetAccelerometerTrims(flightDynamicsTrims_t
*accelerometerTrims
)
147 accelerometerTrims
->values
.pitch
= 0;
148 accelerometerTrims
->values
.roll
= 0;
149 accelerometerTrims
->values
.yaw
= 0;
152 static void resetPidProfile(pidProfile_t
*pidProfile
)
154 pidProfile
->pidController
= 1;
156 pidProfile
->P8
[ROLL
] = 45;
157 pidProfile
->I8
[ROLL
] = 35;
158 pidProfile
->D8
[ROLL
] = 18;
159 pidProfile
->P8
[PITCH
] = 45;
160 pidProfile
->I8
[PITCH
] = 35;
161 pidProfile
->D8
[PITCH
] = 18;
162 pidProfile
->P8
[YAW
] = 90;
163 pidProfile
->I8
[YAW
] = 40;
164 pidProfile
->D8
[YAW
] = 0;
165 pidProfile
->P8
[PIDALT
] = 50;
166 pidProfile
->I8
[PIDALT
] = 0;
167 pidProfile
->D8
[PIDALT
] = 0;
168 pidProfile
->P8
[PIDPOS
] = 15; // POSHOLD_P * 100;
169 pidProfile
->I8
[PIDPOS
] = 0; // POSHOLD_I * 100;
170 pidProfile
->D8
[PIDPOS
] = 0;
171 pidProfile
->P8
[PIDPOSR
] = 34; // POSHOLD_RATE_P * 10;
172 pidProfile
->I8
[PIDPOSR
] = 14; // POSHOLD_RATE_I * 100;
173 pidProfile
->D8
[PIDPOSR
] = 53; // POSHOLD_RATE_D * 1000;
174 pidProfile
->P8
[PIDNAVR
] = 25; // NAV_P * 10;
175 pidProfile
->I8
[PIDNAVR
] = 33; // NAV_I * 100;
176 pidProfile
->D8
[PIDNAVR
] = 83; // NAV_D * 1000;
177 pidProfile
->P8
[PIDLEVEL
] = 50;
178 pidProfile
->I8
[PIDLEVEL
] = 50;
179 pidProfile
->D8
[PIDLEVEL
] = 100;
180 pidProfile
->P8
[PIDMAG
] = 40;
181 pidProfile
->P8
[PIDVEL
] = 55;
182 pidProfile
->I8
[PIDVEL
] = 55;
183 pidProfile
->D8
[PIDVEL
] = 75;
185 pidProfile
->yaw_p_limit
= YAW_P_LIMIT_MAX
;
186 pidProfile
->yaw_lpf_hz
= 80;
187 pidProfile
->rollPitchItermResetRate
= 200;
188 pidProfile
->rollPitchItermResetAlways
= 0;
189 pidProfile
->yawItermResetRate
= 50;
190 pidProfile
->itermResetOffset
= 15;
191 pidProfile
->dterm_lpf_hz
= 110; // filtering ON by default
192 pidProfile
->dynamic_pterm
= 1;
195 pidProfile
->gtune_lolimP
[ROLL
] = 10; // [0..200] Lower limit of ROLL P during G tune.
196 pidProfile
->gtune_lolimP
[PITCH
] = 10; // [0..200] Lower limit of PITCH P during G tune.
197 pidProfile
->gtune_lolimP
[YAW
] = 10; // [0..200] Lower limit of YAW P during G tune.
198 pidProfile
->gtune_hilimP
[ROLL
] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
199 pidProfile
->gtune_hilimP
[PITCH
] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
200 pidProfile
->gtune_hilimP
[YAW
] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
201 pidProfile
->gtune_pwr
= 0; // [0..10] Strength of adjustment
202 pidProfile
->gtune_settle_time
= 450; // [200..1000] Settle time in ms
203 pidProfile
->gtune_average_cycles
= 16; // [8..128] Number of looptime cycles used for gyro average calculation
208 void resetGpsProfile(gpsProfile_t
*gpsProfile
)
210 gpsProfile
->gps_wp_radius
= 200;
211 gpsProfile
->gps_lpf
= 20;
212 gpsProfile
->nav_slew_rate
= 30;
213 gpsProfile
->nav_controls_heading
= 1;
214 gpsProfile
->nav_speed_min
= 100;
215 gpsProfile
->nav_speed_max
= 300;
216 gpsProfile
->ap_mode
= 40;
220 void resetBarometerConfig(barometerConfig_t
*barometerConfig
)
222 barometerConfig
->baro_sample_count
= 21;
223 barometerConfig
->baro_noise_lpf
= 0.6f
;
224 barometerConfig
->baro_cf_vel
= 0.985f
;
225 barometerConfig
->baro_cf_alt
= 0.965f
;
228 void resetSensorAlignment(sensorAlignmentConfig_t
*sensorAlignmentConfig
)
230 sensorAlignmentConfig
->gyro_align
= ALIGN_DEFAULT
;
231 sensorAlignmentConfig
->acc_align
= ALIGN_DEFAULT
;
232 sensorAlignmentConfig
->mag_align
= ALIGN_DEFAULT
;
235 void resetEscAndServoConfig(escAndServoConfig_t
*escAndServoConfig
)
237 escAndServoConfig
->minthrottle
= 1150;
238 escAndServoConfig
->maxthrottle
= 1850;
239 escAndServoConfig
->mincommand
= 1000;
240 escAndServoConfig
->servoCenterPulse
= 1500;
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
284 #define FIRST_PORT_INDEX 0
285 #define SECOND_PORT_INDEX 1
288 void resetSerialConfig(serialConfig_t
*serialConfig
)
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
;
304 // This allows MSP connection via USART & VCP so the board can be reconfigured.
305 serialConfig
->portConfigs
[1].functionMask
= FUNCTION_MSP
;
308 serialConfig
->reboot_character
= 'R';
311 static void resetControlRateConfig(controlRateConfig_t
*controlRateConfig
) {
312 controlRateConfig
->rcRate8
= 100;
313 controlRateConfig
->rcExpo8
= 60;
314 controlRateConfig
->thrMid8
= 50;
315 controlRateConfig
->thrExpo8
= 0;
316 controlRateConfig
->dynThrPID
= 20;
317 controlRateConfig
->rcYawExpo8
= 20;
318 controlRateConfig
->tpa_breakpoint
= 1650;
320 for (uint8_t axis
= 0; axis
< FLIGHT_DYNAMICS_INDEX_COUNT
; axis
++) {
321 controlRateConfig
->rates
[axis
] = 50;
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 mixerConfig
->yaw_jump_prevention_limit
= 200;
337 mixerConfig
->tri_unarmed_servo
= 1;
338 mixerConfig
->servo_lowpass_freq
= 400;
339 mixerConfig
->servo_lowpass_enable
= 0;
343 uint8_t getCurrentProfile(void)
345 return masterConfig
.current_profile_index
;
348 static void setProfile(uint8_t profileIndex
)
350 currentProfile
= &masterConfig
.profile
[profileIndex
];
351 currentControlRateProfileIndex
= currentProfile
->activeRateProfile
;
352 currentControlRateProfile
= ¤tProfile
->controlRateProfile
[currentControlRateProfileIndex
];
355 uint8_t getCurrentControlRateProfile(void)
357 return currentControlRateProfileIndex
;
360 static void setControlRateProfile(uint8_t profileIndex
) {
361 currentControlRateProfileIndex
= profileIndex
;
362 masterConfig
.profile
[getCurrentProfile()].activeRateProfile
= profileIndex
;
363 currentControlRateProfile
= &masterConfig
.profile
[getCurrentProfile()].controlRateProfile
[profileIndex
];
367 controlRateConfig_t
*getControlRateConfig(uint8_t profileIndex
) {
368 return &masterConfig
.profile
[profileIndex
].controlRateProfile
[masterConfig
.profile
[profileIndex
].activeRateProfile
];
371 uint16_t getCurrentMinthrottle(void)
373 return masterConfig
.escAndServoConfig
.minthrottle
;
377 static void resetConf(void)
381 // Clear all configuration
382 memset(&masterConfig
, 0, sizeof(master_t
));
385 masterConfig
.version
= EEPROM_CONF_VERSION
;
386 masterConfig
.mixerMode
= MIXER_QUADX
;
388 #if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE) || defined(DOGE)
389 featureSet(FEATURE_RX_PPM
);
392 //#if defined(SPRACINGF3MINI)
393 // featureSet(FEATURE_DISPLAY);
396 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
397 // only enable the VBAT feature by default if the board has a voltage divider otherwise
398 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
399 featureSet(FEATURE_VBAT
);
402 featureSet(FEATURE_FAILSAFE
);
403 featureSet(FEATURE_ONESHOT125
);
406 masterConfig
.current_profile_index
= 0; // default profile
407 masterConfig
.dcm_kp
= 2500; // 1.0 * 10000
408 masterConfig
.dcm_ki
= 0; // 0.003 * 10000
409 masterConfig
.gyro_lpf
= 0; // 256HZ default
411 masterConfig
.gyro_sync_denom
= 8;
413 masterConfig
.gyro_sync_denom
= 4;
415 masterConfig
.gyro_soft_lpf_hz
= 100;
417 masterConfig
.pid_process_denom
= 2;
419 masterConfig
.debug_mode
= 0;
421 resetAccelerometerTrims(&masterConfig
.accZero
);
423 resetSensorAlignment(&masterConfig
.sensorAlignmentConfig
);
425 masterConfig
.boardAlignment
.rollDegrees
= 0;
426 masterConfig
.boardAlignment
.pitchDegrees
= 0;
427 masterConfig
.boardAlignment
.yawDegrees
= 0;
428 masterConfig
.acc_hardware
= ACC_DEFAULT
; // default/autodetect
429 masterConfig
.max_angle_inclination
= 700; // 70 degrees
430 masterConfig
.yaw_control_direction
= 1;
431 masterConfig
.gyroConfig
.gyroMovementCalibrationThreshold
= 32;
433 // xxx_hardware: 0:default/autodetect, 1: disable
434 masterConfig
.mag_hardware
= 0;
436 masterConfig
.baro_hardware
= 0;
438 resetBatteryConfig(&masterConfig
.batteryConfig
);
440 resetTelemetryConfig(&masterConfig
.telemetryConfig
);
442 masterConfig
.rxConfig
.serialrx_provider
= 0;
443 masterConfig
.rxConfig
.sbus_inversion
= 1;
444 masterConfig
.rxConfig
.spektrum_sat_bind
= 0;
445 masterConfig
.rxConfig
.spektrum_sat_bind_autoreset
= 1;
446 masterConfig
.rxConfig
.midrc
= 1500;
447 masterConfig
.rxConfig
.mincheck
= 1100;
448 masterConfig
.rxConfig
.maxcheck
= 1900;
449 masterConfig
.rxConfig
.rx_min_usec
= 885; // any of first 4 channels below this value will trigger rx loss detection
450 masterConfig
.rxConfig
.rx_max_usec
= 2115; // any of first 4 channels above this value will trigger rx loss detection
452 for (i
= 0; i
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; i
++) {
453 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[i
];
454 channelFailsafeConfiguration
->mode
= (i
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_MODE_AUTO
: RX_FAILSAFE_MODE_HOLD
;
455 channelFailsafeConfiguration
->step
= (i
== THROTTLE
) ? CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig
.rxConfig
.rx_min_usec
) : CHANNEL_VALUE_TO_RXFAIL_STEP(masterConfig
.rxConfig
.midrc
);
458 masterConfig
.rxConfig
.rssi_channel
= 0;
459 masterConfig
.rxConfig
.rssi_scale
= RSSI_SCALE_DEFAULT
;
460 masterConfig
.rxConfig
.rssi_ppm_invert
= 0;
461 masterConfig
.rxConfig
.rcSmoothing
= 0;
462 masterConfig
.rxConfig
.fpvCamAngleDegrees
= 0;
463 masterConfig
.rxConfig
.max_aux_channel
= 6;
464 masterConfig
.rxConfig
.superExpoFactor
= 30;
465 masterConfig
.rxConfig
.superExpoFactorYaw
= 30;
466 masterConfig
.rxConfig
.superExpoYawMode
= 0;
468 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
470 masterConfig
.inputFilteringMode
= INPUT_FILTERING_DISABLED
;
472 masterConfig
.gyro_cal_on_first_arm
= 0; // TODO - Cleanup retarded arm support
473 masterConfig
.disarm_kill_switch
= 1;
474 masterConfig
.auto_disarm_delay
= 5;
475 masterConfig
.small_angle
= 25;
477 resetMixerConfig(&masterConfig
.mixerConfig
);
479 masterConfig
.airplaneConfig
.fixedwing_althold_dir
= 1;
482 resetEscAndServoConfig(&masterConfig
.escAndServoConfig
);
483 resetFlight3DConfig(&masterConfig
.flight3DConfig
);
485 #ifdef BRUSHED_MOTORS
486 masterConfig
.motor_pwm_rate
= BRUSHED_MOTORS_PWM_RATE
;
488 masterConfig
.motor_pwm_rate
= BRUSHLESS_MOTORS_PWM_RATE
;
490 masterConfig
.servo_pwm_rate
= 50;
491 masterConfig
.fast_pwm_protocol
= 0;
492 masterConfig
.use_unsyncedPwm
= 0;
494 masterConfig
.use_buzzer_p6
= 0;
499 masterConfig
.gpsConfig
.provider
= GPS_NMEA
;
500 masterConfig
.gpsConfig
.sbasMode
= SBAS_AUTO
;
501 masterConfig
.gpsConfig
.autoConfig
= GPS_AUTOCONFIG_ON
;
502 masterConfig
.gpsConfig
.autoBaud
= GPS_AUTOBAUD_OFF
;
505 resetSerialConfig(&masterConfig
.serialConfig
);
507 masterConfig
.emf_avoidance
= 0; // TODO - needs removal
509 resetPidProfile(¤tProfile
->pidProfile
);
512 for (rI
= 0; rI
<MAX_RATEPROFILES
; rI
++) {
513 resetControlRateConfig(&masterConfig
.profile
[0].controlRateProfile
[rI
]);
515 resetRollAndPitchTrims(&masterConfig
.accelerometerTrims
);
517 masterConfig
.mag_declination
= 0;
518 masterConfig
.acc_lpf_hz
= 10.0f
;
519 masterConfig
.accDeadband
.xy
= 40;
520 masterConfig
.accDeadband
.z
= 40;
521 masterConfig
.acc_unarmedcal
= 1;
523 resetBarometerConfig(&masterConfig
.barometerConfig
);
526 parseRcChannels("AETR1234", &masterConfig
.rxConfig
);
528 resetRcControlsConfig(&masterConfig
.rcControlsConfig
);
530 masterConfig
.throttle_correction_value
= 0; // could 10 with althold or 40 for fpv
531 masterConfig
.throttle_correction_angle
= 800; // could be 80.0 deg with atlhold or 45.0 for fpv
533 // Failsafe Variables
534 masterConfig
.failsafeConfig
.failsafe_delay
= 10; // 1sec
535 masterConfig
.failsafeConfig
.failsafe_off_delay
= 10; // 1sec
536 masterConfig
.failsafeConfig
.failsafe_throttle
= 1000; // default throttle off.
537 masterConfig
.failsafeConfig
.failsafe_kill_switch
= 0; // default failsafe switch action is identical to rc link loss
538 masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
= 100; // default throttle low delay for "just disarm" on failsafe condition
539 masterConfig
.failsafeConfig
.failsafe_procedure
= 0; // default full failsafe procedure is 0: auto-landing
543 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
544 masterConfig
.servoConf
[i
].min
= DEFAULT_SERVO_MIN
;
545 masterConfig
.servoConf
[i
].max
= DEFAULT_SERVO_MAX
;
546 masterConfig
.servoConf
[i
].middle
= DEFAULT_SERVO_MIDDLE
;
547 masterConfig
.servoConf
[i
].rate
= 100;
548 masterConfig
.servoConf
[i
].angleAtMin
= DEFAULT_SERVO_MIN_ANGLE
;
549 masterConfig
.servoConf
[i
].angleAtMax
= DEFAULT_SERVO_MAX_ANGLE
;
550 masterConfig
.servoConf
[i
].forwardFromChannel
= CHANNEL_FORWARDING_DISABLED
;
554 masterConfig
.gimbalConfig
.mode
= GIMBAL_MODE_NORMAL
;
558 resetGpsProfile(&masterConfig
.gpsProfile
);
561 // custom mixer. clear by defaults.
562 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
563 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
566 applyDefaultColors(masterConfig
.colors
, CONFIGURABLE_COLOR_COUNT
);
567 applyDefaultLedStripConfig(masterConfig
.ledConfigs
);
571 featureSet(FEATURE_BLACKBOX
);
572 masterConfig
.blackbox_device
= 1;
574 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
576 memcpy(masterConfig
.transponderData
, &defaultTransponderData
, sizeof(defaultTransponderData
));
579 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
580 featureSet(FEATURE_BLACKBOX
);
581 masterConfig
.blackbox_device
= BLACKBOX_DEVICE_FLASH
;
582 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
583 featureSet(FEATURE_BLACKBOX
);
584 masterConfig
.blackbox_device
= BLACKBOX_DEVICE_SDCARD
;
586 masterConfig
.blackbox_device
= 0;
589 masterConfig
.blackbox_rate_num
= 1;
590 masterConfig
.blackbox_rate_denom
= 1;
593 // alternative defaults settings for COLIBRI RACE targets
594 #if defined(COLIBRI_RACE)
595 masterConfig
.escAndServoConfig
.minthrottle
= 1025;
596 masterConfig
.escAndServoConfig
.maxthrottle
= 1980;
597 masterConfig
.batteryConfig
.vbatmaxcellvoltage
= 45;
598 masterConfig
.batteryConfig
.vbatmincellvoltage
= 30;
600 featureSet(FEATURE_VBAT
);
601 featureSet(FEATURE_FAILSAFE
);
605 featureSet(FEATURE_TRANSPONDER
);
606 featureSet(FEATURE_RSSI_ADC
);
607 featureSet(FEATURE_CURRENT_METER
);
608 featureSet(FEATURE_TELEMETRY
);
611 // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
613 featureSet(FEATURE_RX_SERIAL
);
614 featureSet(FEATURE_MOTOR_STOP
);
615 featureClear(FEATURE_ONESHOT125
);
617 masterConfig
.serialConfig
.portConfigs
[2].functionMask
= FUNCTION_RX_SERIAL
;
618 masterConfig
.batteryConfig
.vbatscale
= 20;
619 masterConfig
.mag_hardware
= MAG_NONE
; // disabled by default
621 masterConfig
.serialConfig
.portConfigs
[1].functionMask
= FUNCTION_RX_SERIAL
;
623 masterConfig
.rxConfig
.serialrx_provider
= 1;
624 masterConfig
.rxConfig
.spektrum_sat_bind
= 5;
625 masterConfig
.rxConfig
.spektrum_sat_bind_autoreset
= 1;
626 masterConfig
.escAndServoConfig
.minthrottle
= 1000;
627 masterConfig
.escAndServoConfig
.maxthrottle
= 2000;
628 masterConfig
.motor_pwm_rate
= 32000;
629 currentProfile
->pidProfile
.pidController
= 2;
630 masterConfig
.failsafeConfig
.failsafe_delay
= 2;
631 masterConfig
.failsafeConfig
.failsafe_off_delay
= 0;
632 masterConfig
.mixerConfig
.yaw_jump_prevention_limit
= 500;
633 currentControlRateProfile
->rcRate8
= 100;
634 currentControlRateProfile
->rates
[FD_PITCH
] = 20;
635 currentControlRateProfile
->rates
[FD_ROLL
] = 20;
636 currentControlRateProfile
->rates
[FD_YAW
] = 20;
637 parseRcChannels("TAER1234", &masterConfig
.rxConfig
);
639 // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
640 masterConfig
.customMotorMixer
[0].throttle
= 1.0f
;
641 masterConfig
.customMotorMixer
[0].roll
= -0.414178f
;
642 masterConfig
.customMotorMixer
[0].pitch
= 1.0f
;
643 masterConfig
.customMotorMixer
[0].yaw
= -1.0f
;
645 // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
646 masterConfig
.customMotorMixer
[1].throttle
= 1.0f
;
647 masterConfig
.customMotorMixer
[1].roll
= -0.414178f
;
648 masterConfig
.customMotorMixer
[1].pitch
= -1.0f
;
649 masterConfig
.customMotorMixer
[1].yaw
= 1.0f
;
651 // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
652 masterConfig
.customMotorMixer
[2].throttle
= 1.0f
;
653 masterConfig
.customMotorMixer
[2].roll
= 0.414178f
;
654 masterConfig
.customMotorMixer
[2].pitch
= 1.0f
;
655 masterConfig
.customMotorMixer
[2].yaw
= 1.0f
;
657 // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
658 masterConfig
.customMotorMixer
[3].throttle
= 1.0f
;
659 masterConfig
.customMotorMixer
[3].roll
= 0.414178f
;
660 masterConfig
.customMotorMixer
[3].pitch
= -1.0f
;
661 masterConfig
.customMotorMixer
[3].yaw
= -1.0f
;
663 // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
664 masterConfig
.customMotorMixer
[4].throttle
= 1.0f
;
665 masterConfig
.customMotorMixer
[4].roll
= -1.0f
;
666 masterConfig
.customMotorMixer
[4].pitch
= -0.414178f
;
667 masterConfig
.customMotorMixer
[4].yaw
= -1.0f
;
669 // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
670 masterConfig
.customMotorMixer
[5].throttle
= 1.0f
;
671 masterConfig
.customMotorMixer
[5].roll
= 1.0f
;
672 masterConfig
.customMotorMixer
[5].pitch
= -0.414178f
;
673 masterConfig
.customMotorMixer
[5].yaw
= 1.0f
;
675 // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
676 masterConfig
.customMotorMixer
[6].throttle
= 1.0f
;
677 masterConfig
.customMotorMixer
[6].roll
= -1.0f
;
678 masterConfig
.customMotorMixer
[6].pitch
= 0.414178f
;
679 masterConfig
.customMotorMixer
[6].yaw
= 1.0f
;
681 // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
682 masterConfig
.customMotorMixer
[7].throttle
= 1.0f
;
683 masterConfig
.customMotorMixer
[7].roll
= 1.0f
;
684 masterConfig
.customMotorMixer
[7].pitch
= 0.414178f
;
685 masterConfig
.customMotorMixer
[7].yaw
= -1.0f
;
688 // copy first profile into remaining profile
689 for (i
= 1; i
< MAX_PROFILE_COUNT
; i
++) {
690 memcpy(&masterConfig
.profile
[i
], currentProfile
, sizeof(profile_t
));
695 static uint8_t calculateChecksum(const uint8_t *data
, uint32_t length
)
697 uint8_t checksum
= 0;
698 const uint8_t *byteOffset
;
700 for (byteOffset
= data
; byteOffset
< (data
+ length
); byteOffset
++)
701 checksum
^= *byteOffset
;
705 static bool isEEPROMContentValid(void)
707 const master_t
*temp
= (const master_t
*) CONFIG_START_FLASH_ADDRESS
;
708 uint8_t checksum
= 0;
710 // check version number
711 if (EEPROM_CONF_VERSION
!= temp
->version
)
714 // check size and magic numbers
715 if (temp
->size
!= sizeof(master_t
) || temp
->magic_be
!= 0xBE || temp
->magic_ef
!= 0xEF)
718 // verify integrity of temporary copy
719 checksum
= calculateChecksum((const uint8_t *) temp
, sizeof(master_t
));
723 // looks good, let's roll!
727 void activateControlRateConfig(void)
729 generatePitchRollCurve(currentControlRateProfile
);
730 generateYawCurve(currentControlRateProfile
);
731 generateThrottleCurve(currentControlRateProfile
, &masterConfig
.escAndServoConfig
);
734 void activateConfig(void)
736 static imuRuntimeConfig_t imuRuntimeConfig
;
738 activateControlRateConfig();
740 resetAdjustmentStates();
743 masterConfig
.modeActivationConditions
,
744 &masterConfig
.escAndServoConfig
,
745 ¤tProfile
->pidProfile
748 useGyroConfig(&masterConfig
.gyroConfig
, masterConfig
.gyro_soft_lpf_hz
);
751 telemetryUseConfig(&masterConfig
.telemetryConfig
);
753 pidSetController(currentProfile
->pidProfile
.pidController
);
756 gpsUseProfile(&masterConfig
.gpsProfile
);
757 gpsUsePIDs(¤tProfile
->pidProfile
);
760 useFailsafeConfig(&masterConfig
.failsafeConfig
);
761 setAccelerationTrims(&masterConfig
.accZero
);
762 setAccelerationFilter(masterConfig
.acc_lpf_hz
);
766 masterConfig
.servoConf
,
767 &masterConfig
.gimbalConfig
,
769 &masterConfig
.flight3DConfig
,
770 &masterConfig
.escAndServoConfig
,
771 &masterConfig
.mixerConfig
,
772 &masterConfig
.airplaneConfig
,
773 &masterConfig
.rxConfig
776 imuRuntimeConfig
.dcm_kp
= masterConfig
.dcm_kp
/ 10000.0f
;
777 imuRuntimeConfig
.dcm_ki
= masterConfig
.dcm_ki
/ 10000.0f
;
778 imuRuntimeConfig
.acc_unarmedcal
= masterConfig
.acc_unarmedcal
;
779 imuRuntimeConfig
.small_angle
= masterConfig
.small_angle
;
783 ¤tProfile
->pidProfile
,
784 &masterConfig
.accDeadband
,
785 masterConfig
.throttle_correction_angle
788 configureAltitudeHold(
789 ¤tProfile
->pidProfile
,
790 &masterConfig
.barometerConfig
,
791 &masterConfig
.rcControlsConfig
,
792 &masterConfig
.escAndServoConfig
796 useBarometerConfig(&masterConfig
.barometerConfig
);
800 void validateAndFixConfig(void)
802 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM
) || featureConfigured(FEATURE_RX_PPM
) || featureConfigured(FEATURE_RX_SERIAL
) || featureConfigured(FEATURE_RX_MSP
))) {
803 featureSet(FEATURE_RX_PARALLEL_PWM
); // Consider changing the default to PPM
806 if (featureConfigured(FEATURE_RX_PPM
)) {
807 featureClear(FEATURE_RX_PARALLEL_PWM
);
810 if (featureConfigured(FEATURE_RX_MSP
)) {
811 featureClear(FEATURE_RX_SERIAL
);
812 featureClear(FEATURE_RX_PARALLEL_PWM
);
813 featureClear(FEATURE_RX_PPM
);
816 if (featureConfigured(FEATURE_RX_SERIAL
)) {
817 featureClear(FEATURE_RX_PARALLEL_PWM
);
818 featureClear(FEATURE_RX_PPM
);
821 if (featureConfigured(FEATURE_RX_PARALLEL_PWM
)) {
822 #if defined(STM32F10X)
823 // rssi adc needs the same ports
824 featureClear(FEATURE_RSSI_ADC
);
825 // current meter needs the same ports
826 if (masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
827 featureClear(FEATURE_CURRENT_METER
);
831 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
832 // led strip needs the same ports
833 featureClear(FEATURE_LED_STRIP
);
836 // software serial needs free PWM ports
837 featureClear(FEATURE_SOFTSERIAL
);
841 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
842 if (featureConfigured(FEATURE_SOFTSERIAL
) && (
844 #ifdef USE_SOFTSERIAL1
845 || (LED_STRIP_TIMER
== SOFTSERIAL_1_TIMER
)
847 #ifdef USE_SOFTSERIAL2
848 || (LED_STRIP_TIMER
== SOFTSERIAL_2_TIMER
)
851 // led strip needs the same timer as softserial
852 featureClear(FEATURE_LED_STRIP
);
856 #if defined(NAZE) && defined(SONAR)
857 if (featureConfigured(FEATURE_RX_PARALLEL_PWM
) && featureConfigured(FEATURE_SONAR
) && featureConfigured(FEATURE_CURRENT_METER
) && masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
858 featureClear(FEATURE_CURRENT_METER
);
862 #if defined(OLIMEXINO) && defined(SONAR)
863 if (feature(FEATURE_SONAR
) && feature(FEATURE_CURRENT_METER
) && masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
864 featureClear(FEATURE_CURRENT_METER
);
868 #if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
869 if (doesConfigurationUsePort(SERIAL_PORT_USART3
) && feature(FEATURE_DISPLAY
)) {
870 featureClear(FEATURE_DISPLAY
);
875 // hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
876 masterConfig
.telemetryConfig
.telemetry_inversion
= 1;
880 /*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
881 if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
882 featureClear(FEATURE_LED_STRIP);
887 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
889 if ((featureConfigured(FEATURE_SONAR
) + featureConfigured(FEATURE_SOFTSERIAL
) + featureConfigured(FEATURE_RSSI_ADC
)) > 1) {
890 featureClear(FEATURE_SONAR
);
891 featureClear(FEATURE_SOFTSERIAL
);
892 featureClear(FEATURE_RSSI_ADC
);
896 #if defined(COLIBRI_RACE)
897 masterConfig
.serialConfig
.portConfigs
[0].functionMask
= FUNCTION_MSP
;
898 if(featureConfigured(FEATURE_RX_PARALLEL_PWM
) || featureConfigured(FEATURE_RX_MSP
)) {
899 featureClear(FEATURE_RX_PARALLEL_PWM
);
900 featureClear(FEATURE_RX_MSP
);
901 featureSet(FEATURE_RX_PPM
);
903 if(featureConfigured(FEATURE_RX_SERIAL
)) {
904 masterConfig
.serialConfig
.portConfigs
[2].functionMask
= FUNCTION_RX_SERIAL
;
905 //masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
909 useRxConfig(&masterConfig
.rxConfig
);
911 serialConfig_t
*serialConfig
= &masterConfig
.serialConfig
;
913 if (!isSerialConfigValid(serialConfig
)) {
914 resetSerialConfig(serialConfig
);
918 void initEEPROM(void)
922 void readEEPROM(void)
925 if (!isEEPROMContentValid())
926 failureMode(FAILURE_INVALID_EEPROM_CONTENTS
);
931 memcpy(&masterConfig
, (char *) CONFIG_START_FLASH_ADDRESS
, sizeof(master_t
));
933 if (masterConfig
.current_profile_index
> MAX_PROFILE_COUNT
- 1) // sanity check
934 masterConfig
.current_profile_index
= 0;
936 setProfile(masterConfig
.current_profile_index
);
938 validateAndFixConfig();
944 void readEEPROMAndNotify(void)
946 // re-read written data
948 beeperConfirmationBeeps(1);
951 void writeEEPROM(void)
953 // Generate compile time error if the config does not fit in the reserved area of flash.
954 BUILD_BUG_ON(sizeof(master_t
) > FLASH_TO_RESERVE_FOR_CONFIG
);
956 FLASH_Status status
= 0;
958 int8_t attemptsRemaining
= 3;
962 // prepare checksum/version constants
963 masterConfig
.version
= EEPROM_CONF_VERSION
;
964 masterConfig
.size
= sizeof(master_t
);
965 masterConfig
.magic_be
= 0xBE;
966 masterConfig
.magic_ef
= 0xEF;
967 masterConfig
.chk
= 0; // erase checksum before recalculating
968 masterConfig
.chk
= calculateChecksum((const uint8_t *) &masterConfig
, sizeof(master_t
));
972 while (attemptsRemaining
--) {
974 FLASH_ClearFlag(FLASH_FLAG_EOP
| FLASH_FLAG_PGERR
| FLASH_FLAG_WRPERR
);
977 FLASH_ClearFlag(FLASH_FLAG_EOP
| FLASH_FLAG_PGERR
| FLASH_FLAG_WRPRTERR
);
979 for (wordOffset
= 0; wordOffset
< sizeof(master_t
); wordOffset
+= 4) {
980 if (wordOffset
% FLASH_PAGE_SIZE
== 0) {
981 status
= FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS
+ wordOffset
);
982 if (status
!= FLASH_COMPLETE
) {
987 status
= FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS
+ wordOffset
,
988 *(uint32_t *) ((char *) &masterConfig
+ wordOffset
));
989 if (status
!= FLASH_COMPLETE
) {
993 if (status
== FLASH_COMPLETE
) {
999 // Flash write failed - just die now
1000 if (status
!= FLASH_COMPLETE
|| !isEEPROMContentValid()) {
1001 failureMode(FAILURE_FLASH_WRITE_FAILED
);
1007 void ensureEEPROMContainsValidData(void)
1009 if (isEEPROMContentValid()) {
1016 void resetEEPROM(void)
1022 void saveConfigAndNotify(void)
1025 readEEPROMAndNotify();
1028 void changeProfile(uint8_t profileIndex
)
1030 masterConfig
.current_profile_index
= profileIndex
;
1033 beeperConfirmationBeeps(profileIndex
+ 1);
1036 void changeControlRateProfile(uint8_t profileIndex
) {
1037 if (profileIndex
> MAX_RATEPROFILES
) {
1038 profileIndex
= MAX_RATEPROFILES
- 1;
1040 setControlRateProfile(profileIndex
);
1041 activateControlRateConfig();
1044 void handleOneshotFeatureChangeOnRestart(void)
1046 // Shutdown PWM on all motors prior to soft restart
1049 // Apply additional delay when OneShot125 feature changed from on to off state
1050 if (feature(FEATURE_ONESHOT125
) && !featureConfigured(FEATURE_ONESHOT125
)) {
1051 delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS
);
1055 void latchActiveFeatures()
1057 activeFeaturesLatch
= masterConfig
.enabledFeatures
;
1060 bool featureConfigured(uint32_t mask
)
1062 return masterConfig
.enabledFeatures
& mask
;
1065 bool feature(uint32_t mask
)
1067 return activeFeaturesLatch
& mask
;
1070 void featureSet(uint32_t mask
)
1072 masterConfig
.enabledFeatures
|= mask
;
1075 void featureClear(uint32_t mask
)
1077 masterConfig
.enabledFeatures
&= ~(mask
);
1080 void featureClearAll()
1082 masterConfig
.enabledFeatures
= 0;
1085 uint32_t featureMask(void)
1087 return masterConfig
.enabledFeatures
;
1090 void beeperOffSet(uint32_t mask
)
1092 masterConfig
.beeper_off_flags
|= mask
;
1095 void beeperOffSetAll(uint8_t beeperCount
)
1097 masterConfig
.beeper_off_flags
= (1 << beeperCount
) -1;
1100 void beeperOffClear(uint32_t mask
)
1102 masterConfig
.beeper_off_flags
&= ~(mask
);
1105 void beeperOffClearAll(void)
1107 masterConfig
.beeper_off_flags
= 0;
1110 uint32_t getBeeperOffMask(void)
1112 return masterConfig
.beeper_off_flags
;
1115 void setBeeperOffMask(uint32_t mask
)
1117 masterConfig
.beeper_off_flags
= mask
;
1120 uint32_t getPreferedBeeperOffMask(void)
1122 return masterConfig
.prefered_beeper_off_flags
;
1125 void setPreferedBeeperOffMask(uint32_t mask
)
1127 masterConfig
.prefered_beeper_off_flags
= mask
;