Change dcm_kp default to 25000
[betaflight.git] / src / main / config / config_master.h
blob24813a1d27f60f28ca1d5471c3c884b83f4e7e93
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 motorMixer_t customMotorMixer[MAX_SUPPORTED_MOTORS];
31 #ifdef USE_SERVOS
32 servoMixer_t customServoMixer[MAX_SERVO_RULES];
33 #endif
34 // motor/esc/servo related stuff
35 escAndServoConfig_t escAndServoConfig;
36 flight3DConfig_t flight3DConfig;
38 uint16_t motor_pwm_rate; // The update rate of motor outputs (50-498Hz)
39 uint16_t servo_pwm_rate; // The update rate of servo outputs (50-498Hz)
40 uint8_t use_fast_pwm; // Use fast PWM implementation when oneshot enabled
42 // global sensor-related stuff
44 sensorAlignmentConfig_t sensorAlignmentConfig;
45 boardAlignment_t boardAlignment;
47 int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
48 uint8_t acc_hardware; // Which acc hardware to use on boards with more than one device
49 uint8_t acc_for_fast_looptime; // shorten acc processing time by using 1 out of 9 samples. For combination with fast looptimes.
50 uint16_t gyro_lpf; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
51 uint16_t dcm_kp; // DCM filter proportional gain ( x 10000)
52 uint16_t dcm_ki; // DCM filter integral gain ( x 10000)
54 gyroConfig_t gyroConfig;
56 uint8_t mag_hardware; // Which mag hardware to use on boards with more than one device
57 uint8_t baro_hardware; // Barometer hardware to use
59 uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
60 flightDynamicsTrims_t accZero;
61 flightDynamicsTrims_t magZero;
63 batteryConfig_t batteryConfig;
65 rxConfig_t rxConfig;
66 inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
68 failsafeConfig_t failsafeConfig;
70 uint8_t retarded_arm; // allow disarm/arm on throttle down + roll left/right
71 uint8_t disarm_kill_switch; // allow disarm via AUX switch regardless of throttle value
72 uint8_t auto_disarm_delay; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
73 uint8_t small_angle;
75 // mixer-related configuration
76 mixerConfig_t mixerConfig;
78 airplaneConfig_t airplaneConfig;
80 #ifdef GPS
81 gpsConfig_t gpsConfig;
82 #endif
84 serialConfig_t serialConfig;
86 telemetryConfig_t telemetryConfig;
88 #ifdef LED_STRIP
89 ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH];
90 hsvColor_t colors[CONFIGURABLE_COLOR_COUNT];
91 #endif
93 profile_t profile[MAX_PROFILE_COUNT];
94 uint8_t current_profile_index;
95 controlRateConfig_t controlRateProfiles[MAX_CONTROL_RATE_PROFILE_COUNT];
97 #ifdef BLACKBOX
98 uint8_t blackbox_rate_num;
99 uint8_t blackbox_rate_denom;
100 uint8_t blackbox_device;
101 #endif
103 beeperOffConditions_t beeper_off;
105 uint8_t magic_ef; // magic number, should be 0xEF
106 uint8_t chk; // XOR checksum
107 } master_t;
109 extern master_t masterConfig;
110 extern profile_t *currentProfile;
111 extern controlRateConfig_t *currentControlRateProfile;