Taskmain rework part II
[betaflight.git] / src / main / config / config_master.h
blobe55cb8f6e11350b74755decab5aee22c16265c1b
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 #pragma once
20 // System-wide
21 typedef struct master_t {
22 uint8_t version;
23 uint16_t size;
24 uint8_t magic_be; // magic number, should be 0xBE
26 uint8_t mixerMode;
27 uint32_t enabledFeatures;
28 uint8_t emf_avoidance; // change pll settings to avoid noise in the uhf band
30 beeperOffConditions_t beeper_off;
32 // motor/esc/servo related stuff
33 motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
34 escAndServoConfig_t escAndServoConfig;
35 flight3DConfig_t flight3DConfig;
37 uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
38 uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
39 uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
40 uint8_t use_oneshot42; // Oneshot42
41 uint8_t use_multiShot; // multishot
43 #ifdef USE_SERVOS
44 servoMixer_t customServoMixer[MAX_SERVO_RULES];
45 // Servo-related stuff
46 servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
47 // gimbal-related configuration
48 gimbalConfig_t gimbalConfig;
49 #endif
51 #ifdef CC3D
52 uint8_t use_buzzer_p6;
53 #endif
55 // global sensor-related stuff
56 sensorAlignmentConfig_t sensorAlignmentConfig;
57 boardAlignment_t boardAlignment;
59 int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
60 uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
61 uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
62 uint8_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
63 uint8_t gyro_sync_denom; // Gyro sample divider
64 float gyro_soft_lpf_hz; // Biqyad gyro lpf hz
65 uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
66 uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
68 uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
70 uint8_t debug_mode; // Processing denominator for PID controller vs gyro sampling rate
72 gyroConfig_t gyroConfig;
74 uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
75 uint8_t baro_hardware; // Barometer hardware to use
76 int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
77 // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
79 rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
81 float acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
82 accDeadband_t accDeadband;
83 barometerConfig_t barometerConfig;
84 uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
86 uint16_t throttle_correction_angle; // the angle when the throttle correction is maximal. in 0.1 degres, ex 225 = 22.5 ,30.0, 450 = 45.0 deg
87 uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
88 batteryConfig_t batteryConfig;
90 // Radio/ESC-related configuration
91 rcControlsConfig_t rcControlsConfig;
93 #ifdef GPS
94 gpsProfile_t gpsProfile;
95 #endif
97 uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
98 flightDynamicsTrims_t accZero;
99 flightDynamicsTrims_t magZero;
101 rxConfig_t rxConfig;
102 inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
105 uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
106 uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
107 uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
108 uint8_t small_angle;
110 // mixer-related configuration
111 mixerConfig_t mixerConfig;
112 airplaneConfig_t airplaneConfig;
114 #ifdef GPS
115 gpsConfig_t gpsConfig;
116 #endif
118 failsafeConfig_t failsafeConfig;
119 serialConfig_t serialConfig;
120 telemetryConfig_t telemetryConfig;
122 #ifdef LED_STRIP
123 ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH];
124 hsvColor_t colors[CONFIGURABLE_COLOR_COUNT];
125 #endif
127 #ifdef TRANSPONDER
128 uint8_t transponderData[6];
129 #endif
131 profile_t profile[MAX_PROFILE_COUNT];
132 uint8_t current_profile_index;
134 modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
135 adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
137 #ifdef BLACKBOX
138 uint8_t blackbox_rate_num;
139 uint8_t blackbox_rate_denom;
140 uint8_t blackbox_device;
141 #endif
143 uint8_t magic_ef; // magic number, should be 0xEF
144 uint8_t chk; // XOR checksum
145 } master_t;
147 extern master_t masterConfig;
148 extern profile_t *currentProfile;
149 extern controlRateConfig_t *currentControlRateProfile;