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/>.
17 #include "tracker/defines.h"
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 i2c_overclock
; // Overclock i2c Bus for faster IMU readings
32 motorMixer_t customMotorMixer
[MAX_SUPPORTED_MOTORS
];
34 servoMixer_t customServoMixer
[MAX_SERVO_RULES
];
36 // motor/esc/servo related stuff
37 escAndServoConfig_t escAndServoConfig
;
38 flight3DConfig_t flight3DConfig
;
40 uint16_t motor_pwm_rate
; // The update rate of motor outputs (50-498Hz)
41 uint16_t servo_pwm_rate
; // The update rate of servo outputs (50-498Hz)
43 // global sensor-related stuff
45 sensorAlignmentConfig_t sensorAlignmentConfig
;
46 boardAlignment_t boardAlignment
;
48 //int8_t yaw_control_direction; // change control direction of yaw (inverted, normal)
49 uint8_t acc_hardware
; // Which acc hardware to use on boards with more than one device
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 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.
52 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
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
;
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
;
81 gpsConfig_t gpsConfig
;
84 serialConfig_t serialConfig
;
86 telemetryConfig_t telemetryConfig
;
89 ledConfig_t ledConfigs[MAX_LED_STRIP_LENGTH];
90 hsvColor_t colors[CONFIGURABLE_COLOR_COUNT];
93 profile_t profile
[MAX_PROFILE_COUNT
];
94 uint8_t current_profile_index
;
95 controlRateConfig_t controlRateProfiles
[MAX_CONTROL_RATE_PROFILE_COUNT
];
98 uint8_t blackbox_rate_num;
99 uint8_t blackbox_rate_denom;
100 uint8_t blackbox_device;
103 uint8_t magic_ef
; // magic number, should be 0xEF
104 uint8_t chk
; // XOR checksum
105 ///////////////////////////////
110 uint8_t max_pid_error
;
111 uint16_t max_pid_accumulator
;
112 uint16_t max_pid_gain
;
113 uint8_t max_pid_divider
;
117 uint8_t pan0_calibrated
;
118 uint8_t mag_calibrated
;
119 uint8_t min_pan_speed
;
125 uint8_t tilt_max_angle
;
127 uint8_t easing_steps
;
128 uint8_t easing_min_angle
;
129 uint8_t easing_millis
;
130 uint16_t easing_last_tilt
;
131 uint16_t telemetry_protocol
;
132 uint8_t start_tracking_distance
;
133 uint8_t start_tracking_altitude
;
135 uint8_t telemetry_min_sats
;
136 uint8_t telemetry_provider
;
137 uint8_t telemetry_home
;
138 uint8_t gps_min_sats
;
139 uint8_t min_logic_level
;
140 // NO PID CONTROL SYSTEM
141 float nopid_min_delta
;
142 uint16_t nopid_max_speed
;
143 uint8_t nopid_map_angle
;
145 epsVectorGain_t eps_gain
;
146 uint16_t eps_frequency
;
147 uint8_t eps_interpolation
;
148 uint8_t eps_interpolation_points
;
149 uint8_t update_home_by_local_gps
;
150 uint16_t pan_calibration_pulse
;
151 uint8_t max_speed_filter
;
152 uint8_t altitude_priority
;
153 uint8_t pan_inverted
;
156 extern master_t masterConfig
;
157 extern profile_t
*currentProfile
;
158 extern controlRateConfig_t
*currentControlRateProfile
;