STM32F4: USARTS 4,5,6 added
[betaflight.git] / src / main / config / config_master.h
blobb06553335002a25991e8c132124293ed89d12ee2
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 // motor/esc/servo related stuff
31 motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
32 escAndServoConfig_t escAndServoConfig;
33 flight3DConfig_t flight3DConfig;
35 uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
36 uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
37 uint8_t motor_pwm_protocol; // Pwm Protocol
38 uint8_t use_unsyncedPwm; // unsync fast pwm protocol from PID loop
40 #ifdef USE_SERVOS
41 servoMixer_t customServoMixer[MAX_SERVO_RULES];
42 // Servo-related stuff
43 servoParam_t servoConf[MAX_SUPPORTED_SERVOS]; // servo configuration
44 // gimbal-related configuration
45 gimbalConfig_t gimbalConfig;
46 #endif
48 #ifdef CC3D
49 uint8_t use_buzzer_p6;
50 #endif
52 // global sensor-related stuff
53 sensorAlignmentConfig_t sensorAlignmentConfig;
54 boardAlignment_t boardAlignment;
56 int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
57 uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
58 uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
59 uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
60 uint8_t gyro_sync_denom; // Gyro sample divider
61 uint8_t gyro_soft_lpf_hz; // Biqyad gyro lpf hz
62 uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
63 uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
65 uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate
67 uint8_t debug_mode; // Processing denominator for PID controller vs gyro sampling rate
69 gyroConfig_t gyroConfig;
71 uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
72 uint8_t baro_hardware; // Barometer hardware to use
73 int16_t mag_declination; // Get your magnetic decliniation from here : http://magnetic-declination.com/
74 // For example, -6deg 37min, = -637 Japan, format is [sign]dddmm (degreesminutes) default is zero.
76 rollAndPitchTrims_t accelerometerTrims; // accelerometer trim
78 float acc_lpf_hz; // cutoff frequency for the low pass filter used on the acc z-axis for althold in Hz
79 accDeadband_t accDeadband;
80 barometerConfig_t barometerConfig;
81 uint8_t acc_unarmedcal; // turn automatic acc compensation on/off
83 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
84 uint8_t throttle_correction_value; // the correction that will be applied at throttle_correction_angle.
85 batteryConfig_t batteryConfig;
87 // Radio/ESC-related configuration
88 rcControlsConfig_t rcControlsConfig;
90 #ifdef GPS
91 gpsProfile_t gpsProfile;
92 #endif
94 uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
95 flightDynamicsTrims_t accZero;
96 flightDynamicsTrims_t magZero;
98 rxConfig_t rxConfig;
99 inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
102 uint8_t gyro_cal_on_first_arm; // allow disarm/arm on throttle down + roll left/right
103 uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
104 uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
105 uint8_t small_angle;
107 // mixer-related configuration
108 mixerConfig_t mixerConfig;
109 airplaneConfig_t airplaneConfig;
111 #ifdef GPS
112 gpsConfig_t gpsConfig;
113 #endif
115 failsafeConfig_t failsafeConfig;
116 serialConfig_t serialConfig;
117 telemetryConfig_t telemetryConfig;
119 #ifdef LED_STRIP
120 ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH];
121 hsvColor_t colors[CONFIGURABLE_COLOR_COUNT];
122 uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on
123 #endif
125 #ifdef TRANSPONDER
126 uint8_t transponderData[6];
127 #endif
129 profile_t profile[MAX_PROFILE_COUNT];
130 uint8_t current_profile_index;
132 modeActivationCondition_t modeActivationConditions[MAX_MODE_ACTIVATION_CONDITION_COUNT];
133 adjustmentRange_t adjustmentRanges[MAX_ADJUSTMENT_RANGE_COUNT];
135 #ifdef VTX
136 uint8_t vtx_band; //1=A, 2=B, 3=E, 4=F(Airwaves/Fatshark), 5=Raceband
137 uint8_t vtx_channel; //1-8
138 uint8_t vtx_mode; //0=ch+band 1=mhz
139 uint16_t vtx_mhz; //5740
141 vtxChannelActivationCondition_t vtxChannelActivationConditions[MAX_CHANNEL_ACTIVATION_CONDITION_COUNT];
142 #endif
144 #ifdef BLACKBOX
145 uint8_t blackbox_rate_num;
146 uint8_t blackbox_rate_denom;
147 uint8_t blackbox_device;
148 #endif
150 uint32_t beeper_off_flags;
151 uint32_t preferred_beeper_off_flags;
153 uint8_t magic_ef; // magic number, should be 0xEF
154 uint8_t chk; // XOR checksum
155 } master_t;
157 extern master_t masterConfig;
158 extern profile_t *currentProfile;
159 extern controlRateConfig_t *currentControlRateProfile;