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/>.
21 typedef struct master_t
{
24 uint8_t magic_be
; // magic number, should be 0xBE
27 uint32_t enabledFeatures
;
28 uint16_t looptime
; // imu loop time in us
29 uint8_t emf_avoidance
; // change pll settings to avoid noise in the uhf band
30 uint8_t syncGyroToLoop
; // Enable interrupt based loop
31 uint8_t rcSmoothing
; // Enable Interpolation of RC command
33 motorMixer_t customMotorMixer
[MAX_SUPPORTED_MOTORS
];
35 servoMixer_t customServoMixer
[MAX_SERVO_RULES
];
37 // motor/esc/servo related stuff
38 escAndServoConfig_t escAndServoConfig
;
39 flight3DConfig_t flight3DConfig
;
41 uint16_t motor_pwm_rate
; // The update rate of motor outputs (50-498Hz)
42 uint16_t servo_pwm_rate
; // The update rate of servo outputs (50-498Hz)
44 // global sensor-related stuff
46 sensorAlignmentConfig_t sensorAlignmentConfig
;
47 boardAlignment_t boardAlignment
;
49 int8_t yaw_control_direction
; // change control direction of yaw (inverted, normal)
50 uint8_t acc_hardware
; // Which acc hardware to use on boards with more than one device
51 uint16_t gyro_lpf
; // gyro LPF setting - values are driver specific, in case of invalid number, a reasonable default ~30-40HZ is chosen.
52 uint16_t gyro_cmpf_factor
; // Set the Gyro Weight for Gyro/Acc complementary filter. Increasing this value would reduce and delay Acc influence on the output of the filter.
53 uint16_t gyro_cmpfm_factor
; // Set the Gyro Weight for Gyro/Magnetometer complementary filter. Increasing this value would reduce and delay Magnetometer influence on the output of the filter
55 gyroConfig_t gyroConfig
;
57 uint8_t mag_hardware
; // Which mag hardware to use on boards with more than one device
58 uint8_t baro_hardware
; // Barometer hardware to use
60 uint16_t max_angle_inclination
; // max inclination allowed in angle (level) mode. default 500 (50 degrees).
61 flightDynamicsTrims_t accZero
;
62 flightDynamicsTrims_t magZero
;
64 batteryConfig_t batteryConfig
;
67 inputFilteringMode_e inputFilteringMode
; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers.
69 failsafeConfig_t failsafeConfig
;
71 uint8_t retarded_arm
; // allow disarm/arm on throttle down + roll left/right
72 uint8_t disarm_kill_switch
; // allow disarm via AUX switch regardless of throttle value
73 uint8_t auto_disarm_delay
; // allow automatically disarming multicopters after auto_disarm_delay seconds of zero throttle. Disabled when 0
76 // mixer-related configuration
77 mixerConfig_t mixerConfig
;
79 airplaneConfig_t airplaneConfig
;
82 gpsConfig_t gpsConfig
;
85 serialConfig_t serialConfig
;
87 telemetryConfig_t telemetryConfig
;
90 ledConfig_t ledConfigs
[MAX_LED_STRIP_LENGTH
];
91 hsvColor_t colors
[CONFIGURABLE_COLOR_COUNT
];
94 profile_t profile
[MAX_PROFILE_COUNT
];
95 uint8_t current_profile_index
;
96 controlRateConfig_t controlRateProfiles
[MAX_CONTROL_RATE_PROFILE_COUNT
];
99 uint8_t blackbox_rate_num
;
100 uint8_t blackbox_rate_denom
;
101 uint8_t blackbox_device
;
104 uint8_t magic_ef
; // magic number, should be 0xEF
105 uint8_t chk
; // XOR checksum
108 extern master_t masterConfig
;
109 extern profile_t
*currentProfile
;
110 extern controlRateConfig_t
*currentControlRateProfile
;