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 #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG))
130 master_t masterConfig
; // master config struct with data independent from profiles
131 profile_t
*currentProfile
;
132 static uint32_t activeFeaturesLatch
= 0;
134 static uint8_t currentControlRateProfileIndex
= 0;
135 controlRateConfig_t
*currentControlRateProfile
;
137 static const uint8_t EEPROM_CONF_VERSION
= 129;
139 static void resetAccelerometerTrims(flightDynamicsTrims_t
*accelerometerTrims
)
141 accelerometerTrims
->values
.pitch
= 0;
142 accelerometerTrims
->values
.roll
= 0;
143 accelerometerTrims
->values
.yaw
= 0;
146 static void resetPidProfile(pidProfile_t
*pidProfile
)
148 pidProfile
->pidController
= 1;
150 pidProfile
->P8
[ROLL
] = 42;
151 pidProfile
->I8
[ROLL
] = 40;
152 pidProfile
->D8
[ROLL
] = 18;
153 pidProfile
->P8
[PITCH
] = 54;
154 pidProfile
->I8
[PITCH
] = 40;
155 pidProfile
->D8
[PITCH
] = 22;
156 pidProfile
->P8
[YAW
] = 90;
157 pidProfile
->I8
[YAW
] = 50;
158 pidProfile
->D8
[YAW
] = 0;
159 pidProfile
->P8
[PIDALT
] = 50;
160 pidProfile
->I8
[PIDALT
] = 0;
161 pidProfile
->D8
[PIDALT
] = 0;
162 pidProfile
->P8
[PIDPOS
] = 15; // POSHOLD_P * 100;
163 pidProfile
->I8
[PIDPOS
] = 0; // POSHOLD_I * 100;
164 pidProfile
->D8
[PIDPOS
] = 0;
165 pidProfile
->P8
[PIDPOSR
] = 34; // POSHOLD_RATE_P * 10;
166 pidProfile
->I8
[PIDPOSR
] = 14; // POSHOLD_RATE_I * 100;
167 pidProfile
->D8
[PIDPOSR
] = 53; // POSHOLD_RATE_D * 1000;
168 pidProfile
->P8
[PIDNAVR
] = 25; // NAV_P * 10;
169 pidProfile
->I8
[PIDNAVR
] = 33; // NAV_I * 100;
170 pidProfile
->D8
[PIDNAVR
] = 83; // NAV_D * 1000;
171 pidProfile
->P8
[PIDLEVEL
] = 30;
172 pidProfile
->I8
[PIDLEVEL
] = 30;
173 pidProfile
->D8
[PIDLEVEL
] = 100;
174 pidProfile
->P8
[PIDMAG
] = 40;
175 pidProfile
->P8
[PIDVEL
] = 120;
176 pidProfile
->I8
[PIDVEL
] = 45;
177 pidProfile
->D8
[PIDVEL
] = 1;
179 pidProfile
->yaw_p_limit
= YAW_P_LIMIT_MAX
;
180 pidProfile
->dterm_average_count
= 4;
181 pidProfile
->dterm_lpf_hz
= 0; // filtering ON by default
182 pidProfile
->deltaMethod
= DELTA_FROM_MEASUREMENT
;
184 pidProfile
->P_f
[ROLL
] = 1.1f
;
185 pidProfile
->I_f
[ROLL
] = 0.4f
;
186 pidProfile
->D_f
[ROLL
] = 0.01f
;
187 pidProfile
->P_f
[PITCH
] = 1.4f
;
188 pidProfile
->I_f
[PITCH
] = 0.4f
;
189 pidProfile
->D_f
[PITCH
] = 0.01f
;
190 pidProfile
->P_f
[YAW
] = 4.0f
;
191 pidProfile
->I_f
[YAW
] = 0.4f
;
192 pidProfile
->D_f
[YAW
] = 0.00f
;
193 pidProfile
->A_level
= 4.0f
;
194 pidProfile
->H_level
= 4.0f
;
195 pidProfile
->H_sensitivity
= 75;
198 pidProfile
->gtune_lolimP
[ROLL
] = 10; // [0..200] Lower limit of ROLL P during G tune.
199 pidProfile
->gtune_lolimP
[PITCH
] = 10; // [0..200] Lower limit of PITCH P during G tune.
200 pidProfile
->gtune_lolimP
[YAW
] = 10; // [0..200] Lower limit of YAW P during G tune.
201 pidProfile
->gtune_hilimP
[ROLL
] = 100; // [0..200] Higher limit of ROLL P during G tune. 0 Disables tuning for that axis.
202 pidProfile
->gtune_hilimP
[PITCH
] = 100; // [0..200] Higher limit of PITCH P during G tune. 0 Disables tuning for that axis.
203 pidProfile
->gtune_hilimP
[YAW
] = 100; // [0..200] Higher limit of YAW P during G tune. 0 Disables tuning for that axis.
204 pidProfile
->gtune_pwr
= 0; // [0..10] Strength of adjustment
205 pidProfile
->gtune_settle_time
= 450; // [200..1000] Settle time in ms
206 pidProfile
->gtune_average_cycles
= 16; // [8..128] Number of looptime cycles used for gyro average calculation
211 void resetGpsProfile(gpsProfile_t
*gpsProfile
)
213 gpsProfile
->gps_wp_radius
= 200;
214 gpsProfile
->gps_lpf
= 20;
215 gpsProfile
->nav_slew_rate
= 30;
216 gpsProfile
->nav_controls_heading
= 1;
217 gpsProfile
->nav_speed_min
= 100;
218 gpsProfile
->nav_speed_max
= 300;
219 gpsProfile
->ap_mode
= 40;
223 void resetBarometerConfig(barometerConfig_t
*barometerConfig
)
225 barometerConfig
->baro_sample_count
= 21;
226 barometerConfig
->baro_noise_lpf
= 0.6f
;
227 barometerConfig
->baro_cf_vel
= 0.985f
;
228 barometerConfig
->baro_cf_alt
= 0.965f
;
231 void resetSensorAlignment(sensorAlignmentConfig_t
*sensorAlignmentConfig
)
233 sensorAlignmentConfig
->gyro_align
= ALIGN_DEFAULT
;
234 sensorAlignmentConfig
->acc_align
= ALIGN_DEFAULT
;
235 sensorAlignmentConfig
->mag_align
= ALIGN_DEFAULT
;
238 void resetEscAndServoConfig(escAndServoConfig_t
*escAndServoConfig
)
240 escAndServoConfig
->minthrottle
= 1150;
241 escAndServoConfig
->maxthrottle
= 1850;
242 escAndServoConfig
->mincommand
= 1000;
243 escAndServoConfig
->servoCenterPulse
= 1500;
246 void resetFlight3DConfig(flight3DConfig_t
*flight3DConfig
)
248 flight3DConfig
->deadband3d_low
= 1406;
249 flight3DConfig
->deadband3d_high
= 1514;
250 flight3DConfig
->neutral3d
= 1460;
251 flight3DConfig
->deadband3d_throttle
= 50;
254 void resetTelemetryConfig(telemetryConfig_t
*telemetryConfig
)
256 telemetryConfig
->telemetry_inversion
= 0;
257 telemetryConfig
->telemetry_switch
= 0;
258 telemetryConfig
->gpsNoFixLatitude
= 0;
259 telemetryConfig
->gpsNoFixLongitude
= 0;
260 telemetryConfig
->frsky_coordinate_format
= FRSKY_FORMAT_DMS
;
261 telemetryConfig
->frsky_unit
= FRSKY_UNIT_METRICS
;
262 telemetryConfig
->frsky_vfas_precision
= 0;
263 telemetryConfig
->frsky_vfas_cell_voltage
= 0;
264 telemetryConfig
->hottAlarmSoundInterval
= 5;
267 void resetBatteryConfig(batteryConfig_t
*batteryConfig
)
269 batteryConfig
->vbatscale
= VBAT_SCALE_DEFAULT
;
270 batteryConfig
->vbatresdivval
= VBAT_RESDIVVAL_DEFAULT
;
271 batteryConfig
->vbatresdivmultiplier
= VBAT_RESDIVMULTIPLIER_DEFAULT
;
272 batteryConfig
->vbatmaxcellvoltage
= 43;
273 batteryConfig
->vbatmincellvoltage
= 33;
274 batteryConfig
->vbatwarningcellvoltage
= 35;
275 batteryConfig
->vbatPidCompensation
= 0;
276 batteryConfig
->currentMeterOffset
= 0;
277 batteryConfig
->currentMeterScale
= 400; // for Allegro ACS758LCB-100U (40mV/A)
278 batteryConfig
->batteryCapacity
= 0;
279 batteryConfig
->currentMeterType
= CURRENT_SENSOR_ADC
;
282 #ifdef SWAP_SERIAL_PORT_0_AND_1_DEFAULTS
283 #define FIRST_PORT_INDEX 1
284 #define SECOND_PORT_INDEX 0
286 #define FIRST_PORT_INDEX 0
287 #define SECOND_PORT_INDEX 1
290 void resetSerialConfig(serialConfig_t
*serialConfig
)
293 memset(serialConfig
, 0, sizeof(serialConfig_t
));
295 for (index
= 0; index
< SERIAL_PORT_COUNT
; index
++) {
296 serialConfig
->portConfigs
[index
].identifier
= serialPortIdentifiers
[index
];
297 serialConfig
->portConfigs
[index
].msp_baudrateIndex
= BAUD_115200
;
298 serialConfig
->portConfigs
[index
].gps_baudrateIndex
= BAUD_57600
;
299 serialConfig
->portConfigs
[index
].telemetry_baudrateIndex
= BAUD_AUTO
;
300 serialConfig
->portConfigs
[index
].blackbox_baudrateIndex
= BAUD_115200
;
303 serialConfig
->portConfigs
[0].functionMask
= FUNCTION_MSP
;
306 // This allows MSP connection via USART & VCP so the board can be reconfigured.
307 serialConfig
->portConfigs
[1].functionMask
= FUNCTION_MSP
;
310 serialConfig
->reboot_character
= 'R';
313 static void resetControlRateConfig(controlRateConfig_t
*controlRateConfig
) {
314 controlRateConfig
->rcRate8
= 100;
315 controlRateConfig
->rcExpo8
= 70;
316 controlRateConfig
->thrMid8
= 50;
317 controlRateConfig
->thrExpo8
= 0;
318 controlRateConfig
->dynThrPID
= 0;
319 controlRateConfig
->rcYawExpo8
= 20;
320 controlRateConfig
->tpa_breakpoint
= 1500;
322 for (uint8_t axis
= 0; axis
< FLIGHT_DYNAMICS_INDEX_COUNT
; axis
++) {
323 controlRateConfig
->rates
[axis
] = 0;
328 void resetRcControlsConfig(rcControlsConfig_t
*rcControlsConfig
) {
329 rcControlsConfig
->deadband
= 0;
330 rcControlsConfig
->yaw_deadband
= 0;
331 rcControlsConfig
->alt_hold_deadband
= 40;
332 rcControlsConfig
->alt_hold_fast_change
= 1;
335 void resetMixerConfig(mixerConfig_t
*mixerConfig
) {
336 mixerConfig
->yaw_motor_direction
= 1;
337 mixerConfig
->yaw_jump_prevention_limit
= 200;
339 mixerConfig
->tri_unarmed_servo
= 1;
340 mixerConfig
->servo_lowpass_freq
= 400;
341 mixerConfig
->servo_lowpass_enable
= 0;
345 uint8_t getCurrentProfile(void)
347 return masterConfig
.current_profile_index
;
350 static void setProfile(uint8_t profileIndex
)
352 currentProfile
= &masterConfig
.profile
[profileIndex
];
353 currentControlRateProfileIndex
= currentProfile
->activeRateProfile
;
354 currentControlRateProfile
= ¤tProfile
->controlRateProfile
[currentControlRateProfileIndex
];
357 uint8_t getCurrentControlRateProfile(void)
359 return currentControlRateProfileIndex
;
362 static void setControlRateProfile(uint8_t profileIndex
) {
363 currentControlRateProfileIndex
= profileIndex
;
364 masterConfig
.profile
[getCurrentProfile()].activeRateProfile
= profileIndex
;
365 currentControlRateProfile
= &masterConfig
.profile
[getCurrentProfile()].controlRateProfile
[profileIndex
];
369 controlRateConfig_t
*getControlRateConfig(uint8_t profileIndex
) {
370 return &masterConfig
.profile
[profileIndex
].controlRateProfile
[masterConfig
.profile
[profileIndex
].activeRateProfile
];
373 uint16_t getCurrentMinthrottle(void)
375 return masterConfig
.escAndServoConfig
.minthrottle
;
379 static void resetConf(void)
383 // Clear all configuration
384 memset(&masterConfig
, 0, sizeof(master_t
));
387 masterConfig
.beeper_off
.flags
= BEEPER_OFF_FLAGS_MIN
;
388 masterConfig
.version
= EEPROM_CONF_VERSION
;
389 masterConfig
.mixerMode
= MIXER_QUADX
;
391 #if defined(CJMCU) || defined(SPARKY) || defined(COLIBRI_RACE) || defined(MOTOLAB) || defined(SPRACINGF3MINI) || defined(LUX_RACE)
392 featureSet(FEATURE_RX_PPM
);
395 //#if defined(SPRACINGF3MINI)
396 // featureSet(FEATURE_DISPLAY);
399 #ifdef BOARD_HAS_VOLTAGE_DIVIDER
400 // only enable the VBAT feature by default if the board has a voltage divider otherwise
401 // the user may see incorrect readings and unexpected issues with pin mappings may occur.
402 featureSet(FEATURE_VBAT
);
405 featureSet(FEATURE_FAILSAFE
);
406 featureSet(FEATURE_ONESHOT125
);
409 masterConfig
.current_profile_index
= 0; // default profile
410 masterConfig
.dcm_kp
= 2500; // 1.0 * 10000
411 masterConfig
.dcm_ki
= 0; // 0.003 * 10000
412 masterConfig
.gyro_lpf
= 1; // 188HZ
413 masterConfig
.gyro_sync_denom
= 4;
414 masterConfig
.gyro_soft_lpf_hz
= 60;
416 masterConfig
.pid_process_denom
= 1;
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
.acroPlusFactor
= 30;
464 masterConfig
.rxConfig
.acroPlusOffset
= 40;
466 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
468 masterConfig
.inputFilteringMode
= INPUT_FILTERING_DISABLED
;
470 masterConfig
.retarded_arm
= 0; // TODO - Cleanup retarded arm support
471 masterConfig
.disarm_kill_switch
= 1;
472 masterConfig
.auto_disarm_delay
= 5;
473 masterConfig
.small_angle
= 25;
475 resetMixerConfig(&masterConfig
.mixerConfig
);
477 masterConfig
.airplaneConfig
.fixedwing_althold_dir
= 1;
480 resetEscAndServoConfig(&masterConfig
.escAndServoConfig
);
481 resetFlight3DConfig(&masterConfig
.flight3DConfig
);
483 #ifdef BRUSHED_MOTORS
484 masterConfig
.motor_pwm_rate
= BRUSHED_MOTORS_PWM_RATE
;
486 masterConfig
.motor_pwm_rate
= BRUSHLESS_MOTORS_PWM_RATE
;
488 masterConfig
.servo_pwm_rate
= 50;
489 masterConfig
.use_oneshot42
= 0;
491 masterConfig
.use_buzzer_p6
= 0;
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
;
502 resetSerialConfig(&masterConfig
.serialConfig
);
504 #if defined(STM32F10X) && !defined(CC3D)
505 masterConfig
.emf_avoidance
= 1;
507 masterConfig
.emf_avoidance
= 0;
510 resetPidProfile(¤tProfile
->pidProfile
);
513 for (rI
= 0; rI
<MAX_RATEPROFILES
; rI
++) {
514 resetControlRateConfig(&masterConfig
.profile
[0].controlRateProfile
[rI
]);
516 resetRollAndPitchTrims(&masterConfig
.accelerometerTrims
);
518 masterConfig
.mag_declination
= 0;
519 masterConfig
.acc_lpf_hz
= 10.0f
;
520 masterConfig
.accDeadband
.xy
= 40;
521 masterConfig
.accDeadband
.z
= 40;
522 masterConfig
.acc_unarmedcal
= 1;
524 resetBarometerConfig(&masterConfig
.barometerConfig
);
527 parseRcChannels("AETR1234", &masterConfig
.rxConfig
);
529 resetRcControlsConfig(&masterConfig
.rcControlsConfig
);
531 masterConfig
.throttle_correction_value
= 0; // could 10 with althold or 40 for fpv
532 masterConfig
.throttle_correction_angle
= 800; // could be 80.0 deg with atlhold or 45.0 for fpv
534 // Failsafe Variables
535 masterConfig
.failsafeConfig
.failsafe_delay
= 10; // 1sec
536 masterConfig
.failsafeConfig
.failsafe_off_delay
= 10; // 1sec
537 masterConfig
.failsafeConfig
.failsafe_throttle
= 1000; // default throttle off.
538 masterConfig
.failsafeConfig
.failsafe_kill_switch
= 0; // default failsafe switch action is identical to rc link loss
539 masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
= 100; // default throttle low delay for "just disarm" on failsafe condition
540 masterConfig
.failsafeConfig
.failsafe_procedure
= 0; // default full failsafe procedure is 0: auto-landing
544 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
545 masterConfig
.servoConf
[i
].min
= DEFAULT_SERVO_MIN
;
546 masterConfig
.servoConf
[i
].max
= DEFAULT_SERVO_MAX
;
547 masterConfig
.servoConf
[i
].middle
= DEFAULT_SERVO_MIDDLE
;
548 masterConfig
.servoConf
[i
].rate
= 100;
549 masterConfig
.servoConf
[i
].angleAtMin
= DEFAULT_SERVO_MIN_ANGLE
;
550 masterConfig
.servoConf
[i
].angleAtMax
= DEFAULT_SERVO_MAX_ANGLE
;
551 masterConfig
.servoConf
[i
].forwardFromChannel
= CHANNEL_FORWARDING_DISABLED
;
555 masterConfig
.gimbalConfig
.mode
= GIMBAL_MODE_NORMAL
;
559 resetGpsProfile(&masterConfig
.gpsProfile
);
562 // custom mixer. clear by defaults.
563 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
564 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
567 applyDefaultColors(masterConfig
.colors
, CONFIGURABLE_COLOR_COUNT
);
568 applyDefaultLedStripConfig(masterConfig
.ledConfigs
);
572 featureSet(FEATURE_BLACKBOX
);
573 masterConfig
.blackbox_device
= 1;
575 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
577 memcpy(masterConfig
.transponderData
, &defaultTransponderData
, sizeof(defaultTransponderData
));
580 #if defined(ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT)
581 featureSet(FEATURE_BLACKBOX
);
582 masterConfig
.blackbox_device
= BLACKBOX_DEVICE_FLASH
;
583 #elif defined(ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT)
584 featureSet(FEATURE_BLACKBOX
);
585 masterConfig
.blackbox_device
= BLACKBOX_DEVICE_SDCARD
;
587 masterConfig
.blackbox_device
= 0;
590 masterConfig
.blackbox_rate_num
= 1;
591 masterConfig
.blackbox_rate_denom
= 1;
594 // alternative defaults settings for COLIBRI RACE targets
595 #if defined(COLIBRI_RACE)
596 masterConfig
.escAndServoConfig
.minthrottle
= 1025;
597 masterConfig
.escAndServoConfig
.maxthrottle
= 1980;
598 masterConfig
.batteryConfig
.vbatmaxcellvoltage
= 45;
599 masterConfig
.batteryConfig
.vbatmincellvoltage
= 30;
601 featureSet(FEATURE_VBAT
);
602 featureSet(FEATURE_FAILSAFE
);
605 // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
607 featureSet(FEATURE_RX_SERIAL
);
608 featureSet(FEATURE_MOTOR_STOP
);
609 featureClear(FEATURE_ONESHOT125
);
611 masterConfig
.serialConfig
.portConfigs
[2].functionMask
= FUNCTION_RX_SERIAL
;
612 masterConfig
.batteryConfig
.vbatscale
= 20;
613 masterConfig
.mag_hardware
= MAG_NONE
; // disabled by default
615 masterConfig
.serialConfig
.portConfigs
[1].functionMask
= FUNCTION_RX_SERIAL
;
617 masterConfig
.rxConfig
.serialrx_provider
= 1;
618 masterConfig
.rxConfig
.spektrum_sat_bind
= 5;
619 masterConfig
.rxConfig
.spektrum_sat_bind_autoreset
= 1;
620 masterConfig
.escAndServoConfig
.minthrottle
= 1000;
621 masterConfig
.escAndServoConfig
.maxthrottle
= 2000;
622 masterConfig
.motor_pwm_rate
= 32000;
623 currentProfile
->pidProfile
.pidController
= 2;
624 masterConfig
.failsafeConfig
.failsafe_delay
= 2;
625 masterConfig
.failsafeConfig
.failsafe_off_delay
= 0;
626 masterConfig
.mixerConfig
.yaw_jump_prevention_limit
= 500;
627 currentControlRateProfile
->rcRate8
= 100;
628 currentControlRateProfile
->rates
[FD_PITCH
] = 20;
629 currentControlRateProfile
->rates
[FD_ROLL
] = 20;
630 currentControlRateProfile
->rates
[FD_YAW
] = 20;
631 parseRcChannels("TAER1234", &masterConfig
.rxConfig
);
633 // { 1.0f, -0.414178f, 1.0f, -1.0f }, // REAR_R
634 masterConfig
.customMotorMixer
[0].throttle
= 1.0f
;
635 masterConfig
.customMotorMixer
[0].roll
= -0.414178f
;
636 masterConfig
.customMotorMixer
[0].pitch
= 1.0f
;
637 masterConfig
.customMotorMixer
[0].yaw
= -1.0f
;
639 // { 1.0f, -0.414178f, -1.0f, 1.0f }, // FRONT_R
640 masterConfig
.customMotorMixer
[1].throttle
= 1.0f
;
641 masterConfig
.customMotorMixer
[1].roll
= -0.414178f
;
642 masterConfig
.customMotorMixer
[1].pitch
= -1.0f
;
643 masterConfig
.customMotorMixer
[1].yaw
= 1.0f
;
645 // { 1.0f, 0.414178f, 1.0f, 1.0f }, // REAR_L
646 masterConfig
.customMotorMixer
[2].throttle
= 1.0f
;
647 masterConfig
.customMotorMixer
[2].roll
= 0.414178f
;
648 masterConfig
.customMotorMixer
[2].pitch
= 1.0f
;
649 masterConfig
.customMotorMixer
[2].yaw
= 1.0f
;
651 // { 1.0f, 0.414178f, -1.0f, -1.0f }, // FRONT_L
652 masterConfig
.customMotorMixer
[3].throttle
= 1.0f
;
653 masterConfig
.customMotorMixer
[3].roll
= 0.414178f
;
654 masterConfig
.customMotorMixer
[3].pitch
= -1.0f
;
655 masterConfig
.customMotorMixer
[3].yaw
= -1.0f
;
657 // { 1.0f, -1.0f, -0.414178f, -1.0f }, // MIDFRONT_R
658 masterConfig
.customMotorMixer
[4].throttle
= 1.0f
;
659 masterConfig
.customMotorMixer
[4].roll
= -1.0f
;
660 masterConfig
.customMotorMixer
[4].pitch
= -0.414178f
;
661 masterConfig
.customMotorMixer
[4].yaw
= -1.0f
;
663 // { 1.0f, 1.0f, -0.414178f, 1.0f }, // MIDFRONT_L
664 masterConfig
.customMotorMixer
[5].throttle
= 1.0f
;
665 masterConfig
.customMotorMixer
[5].roll
= 1.0f
;
666 masterConfig
.customMotorMixer
[5].pitch
= -0.414178f
;
667 masterConfig
.customMotorMixer
[5].yaw
= 1.0f
;
669 // { 1.0f, -1.0f, 0.414178f, 1.0f }, // MIDREAR_R
670 masterConfig
.customMotorMixer
[6].throttle
= 1.0f
;
671 masterConfig
.customMotorMixer
[6].roll
= -1.0f
;
672 masterConfig
.customMotorMixer
[6].pitch
= 0.414178f
;
673 masterConfig
.customMotorMixer
[6].yaw
= 1.0f
;
675 // { 1.0f, 1.0f, 0.414178f, -1.0f }, // MIDREAR_L
676 masterConfig
.customMotorMixer
[7].throttle
= 1.0f
;
677 masterConfig
.customMotorMixer
[7].roll
= 1.0f
;
678 masterConfig
.customMotorMixer
[7].pitch
= 0.414178f
;
679 masterConfig
.customMotorMixer
[7].yaw
= -1.0f
;
682 // copy first profile into remaining profile
683 for (i
= 1; i
< MAX_PROFILE_COUNT
; i
++) {
684 memcpy(&masterConfig
.profile
[i
], currentProfile
, sizeof(profile_t
));
689 static uint8_t calculateChecksum(const uint8_t *data
, uint32_t length
)
691 uint8_t checksum
= 0;
692 const uint8_t *byteOffset
;
694 for (byteOffset
= data
; byteOffset
< (data
+ length
); byteOffset
++)
695 checksum
^= *byteOffset
;
699 static bool isEEPROMContentValid(void)
701 const master_t
*temp
= (const master_t
*) CONFIG_START_FLASH_ADDRESS
;
702 uint8_t checksum
= 0;
704 // check version number
705 if (EEPROM_CONF_VERSION
!= temp
->version
)
708 // check size and magic numbers
709 if (temp
->size
!= sizeof(master_t
) || temp
->magic_be
!= 0xBE || temp
->magic_ef
!= 0xEF)
712 // verify integrity of temporary copy
713 checksum
= calculateChecksum((const uint8_t *) temp
, sizeof(master_t
));
717 // looks good, let's roll!
721 void activateControlRateConfig(void)
723 generatePitchRollCurve(currentControlRateProfile
);
724 generateYawCurve(currentControlRateProfile
);
725 generateThrottleCurve(currentControlRateProfile
, &masterConfig
.escAndServoConfig
);
728 void activateConfig(void)
730 static imuRuntimeConfig_t imuRuntimeConfig
;
732 activateControlRateConfig();
734 resetAdjustmentStates();
737 masterConfig
.modeActivationConditions
,
738 &masterConfig
.escAndServoConfig
,
739 ¤tProfile
->pidProfile
742 useGyroConfig(&masterConfig
.gyroConfig
, masterConfig
.gyro_soft_lpf_hz
);
745 telemetryUseConfig(&masterConfig
.telemetryConfig
);
747 pidSetController(currentProfile
->pidProfile
.pidController
);
750 gpsUseProfile(&masterConfig
.gpsProfile
);
751 gpsUsePIDs(¤tProfile
->pidProfile
);
754 useFailsafeConfig(&masterConfig
.failsafeConfig
);
755 setAccelerationTrims(&masterConfig
.accZero
);
756 setAccelerationFilter(masterConfig
.acc_lpf_hz
);
760 masterConfig
.servoConf
,
761 &masterConfig
.gimbalConfig
,
763 &masterConfig
.flight3DConfig
,
764 &masterConfig
.escAndServoConfig
,
765 &masterConfig
.mixerConfig
,
766 &masterConfig
.airplaneConfig
,
767 &masterConfig
.rxConfig
770 imuRuntimeConfig
.dcm_kp
= masterConfig
.dcm_kp
/ 10000.0f
;
771 imuRuntimeConfig
.dcm_ki
= masterConfig
.dcm_ki
/ 10000.0f
;
772 imuRuntimeConfig
.acc_unarmedcal
= masterConfig
.acc_unarmedcal
;
773 imuRuntimeConfig
.small_angle
= masterConfig
.small_angle
;
777 ¤tProfile
->pidProfile
,
778 &masterConfig
.accDeadband
,
779 masterConfig
.throttle_correction_angle
782 configureAltitudeHold(
783 ¤tProfile
->pidProfile
,
784 &masterConfig
.barometerConfig
,
785 &masterConfig
.rcControlsConfig
,
786 &masterConfig
.escAndServoConfig
790 useBarometerConfig(&masterConfig
.barometerConfig
);
794 void validateAndFixConfig(void)
796 if (!(featureConfigured(FEATURE_RX_PARALLEL_PWM
) || featureConfigured(FEATURE_RX_PPM
) || featureConfigured(FEATURE_RX_SERIAL
) || featureConfigured(FEATURE_RX_MSP
))) {
797 featureSet(FEATURE_RX_PARALLEL_PWM
); // Consider changing the default to PPM
800 if (featureConfigured(FEATURE_RX_PPM
)) {
801 featureClear(FEATURE_RX_PARALLEL_PWM
);
804 if (featureConfigured(FEATURE_RX_MSP
)) {
805 featureClear(FEATURE_RX_SERIAL
);
806 featureClear(FEATURE_RX_PARALLEL_PWM
);
807 featureClear(FEATURE_RX_PPM
);
810 if (featureConfigured(FEATURE_RX_SERIAL
)) {
811 featureClear(FEATURE_RX_PARALLEL_PWM
);
812 featureClear(FEATURE_RX_PPM
);
815 if (featureConfigured(FEATURE_RX_PARALLEL_PWM
)) {
816 #if defined(STM32F10X)
817 // rssi adc needs the same ports
818 featureClear(FEATURE_RSSI_ADC
);
819 // current meter needs the same ports
820 if (masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
821 featureClear(FEATURE_CURRENT_METER
);
825 #if defined(STM32F10X) || defined(CHEBUZZ) || defined(STM32F3DISCOVERY)
826 // led strip needs the same ports
827 featureClear(FEATURE_LED_STRIP
);
830 // software serial needs free PWM ports
831 featureClear(FEATURE_SOFTSERIAL
);
835 #if defined(LED_STRIP) && (defined(USE_SOFTSERIAL1) || defined(USE_SOFTSERIAL2))
836 if (featureConfigured(FEATURE_SOFTSERIAL
) && (
838 #ifdef USE_SOFTSERIAL1
839 || (LED_STRIP_TIMER
== SOFTSERIAL_1_TIMER
)
841 #ifdef USE_SOFTSERIAL2
842 || (LED_STRIP_TIMER
== SOFTSERIAL_2_TIMER
)
845 // led strip needs the same timer as softserial
846 featureClear(FEATURE_LED_STRIP
);
850 #if defined(NAZE) && defined(SONAR)
851 if (featureConfigured(FEATURE_RX_PARALLEL_PWM
) && featureConfigured(FEATURE_SONAR
) && featureConfigured(FEATURE_CURRENT_METER
) && masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
852 featureClear(FEATURE_CURRENT_METER
);
856 #if defined(OLIMEXINO) && defined(SONAR)
857 if (feature(FEATURE_SONAR
) && feature(FEATURE_CURRENT_METER
) && masterConfig
.batteryConfig
.currentMeterType
== CURRENT_SENSOR_ADC
) {
858 featureClear(FEATURE_CURRENT_METER
);
862 #if defined(CC3D) && defined(DISPLAY) && defined(USE_USART3)
863 if (doesConfigurationUsePort(SERIAL_PORT_USART3
) && feature(FEATURE_DISPLAY
)) {
864 featureClear(FEATURE_DISPLAY
);
869 // hardware supports serial port inversion, make users life easier for those that want to connect SBus RX's
870 masterConfig
.telemetryConfig
.telemetry_inversion
= 1;
874 /*#if defined(LED_STRIP) && defined(TRANSPONDER) // TODO - Add transponder feature
875 if ((WS2811_DMA_TC_FLAG == TRANSPONDER_DMA_TC_FLAG) && featureConfigured(FEATURE_TRANSPONDER) && featureConfigured(FEATURE_LED_STRIP)) {
876 featureClear(FEATURE_LED_STRIP);
881 #if defined(CC3D) && defined(SONAR) && defined(USE_SOFTSERIAL1) && defined(RSSI_ADC_GPIO)
883 if ((featureConfigured(FEATURE_SONAR
) + featureConfigured(FEATURE_SOFTSERIAL
) + featureConfigured(FEATURE_RSSI_ADC
)) > 1) {
884 featureClear(FEATURE_SONAR
);
885 featureClear(FEATURE_SOFTSERIAL
);
886 featureClear(FEATURE_RSSI_ADC
);
890 #if defined(COLIBRI_RACE)
891 masterConfig
.serialConfig
.portConfigs
[0].functionMask
= FUNCTION_MSP
;
892 if(featureConfigured(FEATURE_RX_PARALLEL_PWM
) || featureConfigured(FEATURE_RX_MSP
)) {
893 featureClear(FEATURE_RX_PARALLEL_PWM
);
894 featureClear(FEATURE_RX_MSP
);
895 featureSet(FEATURE_RX_PPM
);
897 if(featureConfigured(FEATURE_RX_SERIAL
)) {
898 masterConfig
.serialConfig
.portConfigs
[2].functionMask
= FUNCTION_RX_SERIAL
;
899 //masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS;
903 useRxConfig(&masterConfig
.rxConfig
);
905 serialConfig_t
*serialConfig
= &masterConfig
.serialConfig
;
907 if (!isSerialConfigValid(serialConfig
)) {
908 resetSerialConfig(serialConfig
);
912 void initEEPROM(void)
916 void readEEPROM(void)
919 if (!isEEPROMContentValid())
920 failureMode(FAILURE_INVALID_EEPROM_CONTENTS
);
925 memcpy(&masterConfig
, (char *) CONFIG_START_FLASH_ADDRESS
, sizeof(master_t
));
927 if (masterConfig
.current_profile_index
> MAX_PROFILE_COUNT
- 1) // sanity check
928 masterConfig
.current_profile_index
= 0;
930 setProfile(masterConfig
.current_profile_index
);
932 validateAndFixConfig();
938 void readEEPROMAndNotify(void)
940 // re-read written data
942 beeperConfirmationBeeps(1);
945 void writeEEPROM(void)
947 // Generate compile time error if the config does not fit in the reserved area of flash.
948 BUILD_BUG_ON(sizeof(master_t
) > FLASH_TO_RESERVE_FOR_CONFIG
);
950 FLASH_Status status
= 0;
952 int8_t attemptsRemaining
= 3;
956 // prepare checksum/version constants
957 masterConfig
.version
= EEPROM_CONF_VERSION
;
958 masterConfig
.size
= sizeof(master_t
);
959 masterConfig
.magic_be
= 0xBE;
960 masterConfig
.magic_ef
= 0xEF;
961 masterConfig
.chk
= 0; // erase checksum before recalculating
962 masterConfig
.chk
= calculateChecksum((const uint8_t *) &masterConfig
, sizeof(master_t
));
966 while (attemptsRemaining
--) {
968 FLASH_ClearFlag(FLASH_FLAG_EOP
| FLASH_FLAG_PGERR
| FLASH_FLAG_WRPERR
);
971 FLASH_ClearFlag(FLASH_FLAG_EOP
| FLASH_FLAG_PGERR
| FLASH_FLAG_WRPRTERR
);
973 for (wordOffset
= 0; wordOffset
< sizeof(master_t
); wordOffset
+= 4) {
974 if (wordOffset
% FLASH_PAGE_SIZE
== 0) {
975 status
= FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS
+ wordOffset
);
976 if (status
!= FLASH_COMPLETE
) {
981 status
= FLASH_ProgramWord(CONFIG_START_FLASH_ADDRESS
+ wordOffset
,
982 *(uint32_t *) ((char *) &masterConfig
+ wordOffset
));
983 if (status
!= FLASH_COMPLETE
) {
987 if (status
== FLASH_COMPLETE
) {
993 // Flash write failed - just die now
994 if (status
!= FLASH_COMPLETE
|| !isEEPROMContentValid()) {
995 failureMode(FAILURE_FLASH_WRITE_FAILED
);
1001 void ensureEEPROMContainsValidData(void)
1003 if (isEEPROMContentValid()) {
1010 void resetEEPROM(void)
1016 void saveConfigAndNotify(void)
1019 readEEPROMAndNotify();
1022 void changeProfile(uint8_t profileIndex
)
1024 masterConfig
.current_profile_index
= profileIndex
;
1027 beeperConfirmationBeeps(profileIndex
+ 1);
1030 void changeControlRateProfile(uint8_t profileIndex
) {
1031 if (profileIndex
> MAX_RATEPROFILES
) {
1032 profileIndex
= MAX_RATEPROFILES
- 1;
1034 setControlRateProfile(profileIndex
);
1035 activateControlRateConfig();
1038 void handleOneshotFeatureChangeOnRestart(void)
1040 // Shutdown PWM on all motors prior to soft restart
1043 // Apply additional delay when OneShot125 feature changed from on to off state
1044 if (feature(FEATURE_ONESHOT125
) && !featureConfigured(FEATURE_ONESHOT125
)) {
1045 delay(ONESHOT_FEATURE_CHANGED_DELAY_ON_BOOT_MS
);
1049 void latchActiveFeatures()
1051 activeFeaturesLatch
= masterConfig
.enabledFeatures
;
1054 bool featureConfigured(uint32_t mask
)
1056 return masterConfig
.enabledFeatures
& mask
;
1059 bool feature(uint32_t mask
)
1061 return activeFeaturesLatch
& mask
;
1064 void featureSet(uint32_t mask
)
1066 masterConfig
.enabledFeatures
|= mask
;
1069 void featureClear(uint32_t mask
)
1071 masterConfig
.enabledFeatures
&= ~(mask
);
1074 void featureClearAll()
1076 masterConfig
.enabledFeatures
= 0;
1079 uint32_t featureMask(void)
1081 return masterConfig
.enabledFeatures
;