Update actions to ubuntu-latest (#14114)
[betaflight.git] / src / main / fc / parameter_names.h
blob930a8ee9e27349d2e498d1541299b54607ae1619
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
21 #pragma once
23 #define PARAM_NAME_GYRO_HARDWARE_LPF "gyro_hardware_lpf"
24 #define PARAM_NAME_GYRO_LPF1_TYPE "gyro_lpf1_type"
25 #define PARAM_NAME_GYRO_LPF1_STATIC_HZ "gyro_lpf1_static_hz"
26 #define PARAM_NAME_GYRO_LPF2_TYPE "gyro_lpf2_type"
27 #define PARAM_NAME_GYRO_LPF2_STATIC_HZ "gyro_lpf2_static_hz"
28 #define PARAM_NAME_GYRO_TO_USE "gyro_to_use"
29 #define PARAM_NAME_DYN_NOTCH_MAX_HZ "dyn_notch_max_hz"
30 #define PARAM_NAME_DYN_NOTCH_COUNT "dyn_notch_count"
31 #define PARAM_NAME_DYN_NOTCH_Q "dyn_notch_q"
32 #define PARAM_NAME_DYN_NOTCH_MIN_HZ "dyn_notch_min_hz"
33 #define PARAM_NAME_ACC_HARDWARE "acc_hardware"
34 #define PARAM_NAME_ACC_LPF_HZ "acc_lpf_hz"
35 #define PARAM_NAME_MAG_HARDWARE "mag_hardware"
36 #define PARAM_NAME_BARO_HARDWARE "baro_hardware"
37 #define PARAM_NAME_RC_SMOOTHING "rc_smoothing"
38 #define PARAM_NAME_RC_SMOOTHING_AUTO_FACTOR "rc_smoothing_auto_factor"
39 #define PARAM_NAME_RC_SMOOTHING_AUTO_FACTOR_THROTTLE "rc_smoothing_auto_factor_throttle"
40 #define PARAM_NAME_RC_SMOOTHING_SETPOINT_CUTOFF "rc_smoothing_setpoint_cutoff"
41 #define PARAM_NAME_RC_SMOOTHING_FEEDFORWARD_CUTOFF "rc_smoothing_feedforward_cutoff"
42 #define PARAM_NAME_RC_SMOOTHING_THROTTLE_CUTOFF "rc_smoothing_throttle_cutoff"
43 #define PARAM_NAME_RC_SMOOTHING_DEBUG_AXIS "rc_smoothing_debug_axis"
44 #define PARAM_NAME_RC_SMOOTHING_ACTIVE_CUTOFFS "rc_smoothing_active_cutoffs_ff_sp_thr"
45 #define PARAM_NAME_SERIAL_RX_PROVIDER "serialrx_provider"
46 #define PARAM_NAME_MOTOR_IDLE "motor_idle"
47 #define PARAM_NAME_DSHOT_BIDIR "dshot_bidir"
48 #define PARAM_NAME_USE_UNSYNCED_PWM "use_unsynced_pwm"
49 #define PARAM_NAME_MOTOR_PWM_PROTOCOL "motor_pwm_protocol"
50 #define PARAM_NAME_MOTOR_PWM_RATE "motor_pwm_rate"
51 #define PARAM_NAME_MOTOR_POLES "motor_poles"
52 #define PARAM_NAME_THR_MID "thr_mid"
53 #define PARAM_NAME_THR_EXPO "thr_expo"
54 #define PARAM_NAME_RATES_TYPE "rates_type"
55 #define PARAM_NAME_TPA_RATE "tpa_rate"
56 #define PARAM_NAME_TPA_BREAKPOINT "tpa_breakpoint"
57 #define PARAM_NAME_TPA_LOW_RATE "tpa_low_rate"
58 #define PARAM_NAME_TPA_LOW_BREAKPOINT "tpa_low_breakpoint"
59 #define PARAM_NAME_TPA_LOW_ALWAYS "tpa_low_always"
60 #define PARAM_NAME_TPA_MODE "tpa_mode"
61 #define PARAM_NAME_TPA_CURVE_TYPE "tpa_curve_type"
62 #define PARAM_NAME_TPA_CURVE_STALL_THROTTLE "tpa_curve_stall_throttle"
63 #define PARAM_NAME_TPA_CURVE_PID_THR0 "tpa_curve_pid_thr0"
64 #define PARAM_NAME_TPA_CURVE_PID_THR100 "tpa_curve_pid_thr100"
65 #define PARAM_NAME_TPA_CURVE_EXPO "tpa_curve_expo"
66 #define PARAM_NAME_TPA_SPEED_TYPE "tpa_speed_type"
67 #define PARAM_NAME_TPA_SPEED_BASIC_DELAY "tpa_speed_basic_delay"
68 #define PARAM_NAME_TPA_SPEED_BASIC_GRAVITY "tpa_speed_basic_gravity"
69 #define PARAM_NAME_TPA_SPEED_ADV_PROP_PITCH "tpa_speed_adv_prop_pitch"
70 #define PARAM_NAME_TPA_SPEED_ADV_MASS "tpa_speed_adv_mass"
71 #define PARAM_NAME_TPA_SPEED_ADV_DRAG_K "tpa_speed_adv_drag_k"
72 #define PARAM_NAME_TPA_SPEED_ADV_THRUST "tpa_speed_adv_thrust"
73 #define PARAM_NAME_TPA_SPEED_MAX_VOLTAGE "tpa_speed_max_voltage"
74 #define PARAM_NAME_TPA_SPEED_PITCH_OFFSET "tpa_speed_pitch_offset"
75 #define PARAM_NAME_YAW_TYPE "yaw_type"
76 #define PARAM_NAME_MIXER_TYPE "mixer_type"
77 #define PARAM_NAME_EZ_LANDING_THRESHOLD "ez_landing_threshold"
78 #define PARAM_NAME_EZ_LANDING_LIMIT "ez_landing_limit"
79 #define PARAM_NAME_EZ_LANDING_SPEED "ez_landing_speed"
80 #define PARAM_NAME_LANDING_DISARM_THRESHOLD "landing_disarm_threshold"
81 #define PARAM_NAME_SPA_ROLL_CENTER "spa_roll_center"
82 #define PARAM_NAME_SPA_ROLL_WIDTH "spa_roll_width"
83 #define PARAM_NAME_SPA_ROLL_MODE "spa_roll_mode"
84 #define PARAM_NAME_SPA_PITCH_CENTER "spa_pitch_center"
85 #define PARAM_NAME_SPA_PITCH_WIDTH "spa_pitch_width"
86 #define PARAM_NAME_SPA_PITCH_MODE "spa_pitch_mode"
87 #define PARAM_NAME_SPA_YAW_CENTER "spa_yaw_center"
88 #define PARAM_NAME_SPA_YAW_WIDTH "spa_yaw_width"
89 #define PARAM_NAME_SPA_YAW_MODE "spa_yaw_mode"
90 #define PARAM_NAME_THROTTLE_LIMIT_TYPE "throttle_limit_type"
91 #define PARAM_NAME_THROTTLE_LIMIT_PERCENT "throttle_limit_percent"
92 #define PARAM_NAME_GYRO_CAL_ON_FIRST_ARM "gyro_cal_on_first_arm"
93 #define PARAM_NAME_PREARM_ALLOW_REARM "prearm_allow_rearm"
94 #define PARAM_NAME_DEADBAND "deadband"
95 #define PARAM_NAME_YAW_DEADBAND "yaw_deadband"
96 #define PARAM_NAME_PID_PROCESS_DENOM "pid_process_denom"
97 #define PARAM_NAME_DTERM_LPF1_TYPE "dterm_lpf1_type"
98 #define PARAM_NAME_DTERM_LPF1_STATIC_HZ "dterm_lpf1_static_hz"
99 #define PARAM_NAME_DTERM_LPF2_TYPE "dterm_lpf2_type"
100 #define PARAM_NAME_DTERM_LPF2_STATIC_HZ "dterm_lpf2_static_hz"
101 #define PARAM_NAME_DTERM_NOTCH_HZ "dterm_notch_hz"
102 #define PARAM_NAME_DTERM_NOTCH_CUTOFF "dterm_notch_cutoff"
103 #define PARAM_NAME_VBAT_SAG_COMPENSATION "vbat_sag_compensation"
104 #define PARAM_NAME_PID_AT_MIN_THROTTLE "pid_at_min_throttle"
105 #define PARAM_NAME_ANTI_GRAVITY_GAIN "anti_gravity_gain"
106 #define PARAM_NAME_ANTI_GRAVITY_CUTOFF_HZ "anti_gravity_cutoff_hz"
107 #define PARAM_NAME_ANTI_GRAVITY_P_GAIN "anti_gravity_p_gain"
108 #define PARAM_NAME_ACC_LIMIT_YAW "acc_limit_yaw"
109 #define PARAM_NAME_ACC_LIMIT "acc_limit"
110 #define PARAM_NAME_ITERM_RELAX "iterm_relax"
111 #define PARAM_NAME_ITERM_RELAX_TYPE "iterm_relax_type"
112 #define PARAM_NAME_ITERM_RELAX_CUTOFF "iterm_relax_cutoff"
113 #define PARAM_NAME_ITERM_WINDUP "iterm_windup"
114 #define PARAM_NAME_PIDSUM_LIMIT "pidsum_limit"
115 #define PARAM_NAME_PIDSUM_LIMIT_YAW "pidsum_limit_yaw"
116 #define PARAM_NAME_YAW_LOWPASS_HZ "yaw_lowpass_hz"
117 #define PARAM_NAME_THROTTLE_BOOST "throttle_boost"
118 #define PARAM_NAME_THROTTLE_BOOST_CUTOFF "throttle_boost_cutoff"
119 #define PARAM_NAME_THRUST_LINEARIZATION "thrust_linear"
120 #define PARAM_NAME_ABS_CONTROL_GAIN "abs_control_gain"
121 #define PARAM_NAME_USE_INTEGRATED_YAW "use_integrated_yaw"
122 #define PARAM_NAME_D_MAX_GAIN "d_max_gain"
123 #define PARAM_NAME_D_MAX_ADVANCE "d_max_advance"
124 #define PARAM_NAME_MOTOR_OUTPUT_LIMIT "motor_output_limit"
125 #define PARAM_NAME_FEEDFORWARD_TRANSITION "feedforward_transition"
126 #define PARAM_NAME_FEEDFORWARD_AVERAGING "feedforward_averaging"
127 #define PARAM_NAME_FEEDFORWARD_SMOOTH_FACTOR "feedforward_smooth_factor"
128 #define PARAM_NAME_FEEDFORWARD_JITTER_FACTOR "feedforward_jitter_factor"
129 #define PARAM_NAME_FEEDFORWARD_BOOST "feedforward_boost"
130 #define PARAM_NAME_FEEDFORWARD_MAX_RATE_LIMIT "feedforward_max_rate_limit"
131 #define PARAM_NAME_FEEDFORWARD_YAW_HOLD_GAIN "feedforward_yaw_hold_gain"
132 #define PARAM_NAME_FEEDFORWARD_YAW_HOLD_TIME "feedforward_yaw_hold_time"
133 #define PARAM_NAME_DYN_IDLE_MIN_RPM "dyn_idle_min_rpm"
134 #define PARAM_NAME_DYN_IDLE_P_GAIN "dyn_idle_p_gain"
135 #define PARAM_NAME_DYN_IDLE_I_GAIN "dyn_idle_i_gain"
136 #define PARAM_NAME_DYN_IDLE_D_GAIN "dyn_idle_d_gain"
137 #define PARAM_NAME_DYN_IDLE_MAX_INCREASE "dyn_idle_max_increase"
138 #define PARAM_NAME_SIMPLIFIED_PIDS_MODE "simplified_pids_mode"
139 #define PARAM_NAME_SIMPLIFIED_MASTER_MULTIPLIER "simplified_master_multiplier"
140 #define PARAM_NAME_SIMPLIFIED_I_GAIN "simplified_i_gain"
141 #define PARAM_NAME_SIMPLIFIED_D_GAIN "simplified_d_gain"
142 #define PARAM_NAME_SIMPLIFIED_PI_GAIN "simplified_pi_gain"
143 #define PARAM_NAME_SIMPLIFIED_D_MAX_GAIN "simplified_d_max_gain"
144 #define PARAM_NAME_SIMPLIFIED_FEEDFORWARD_GAIN "simplified_feedforward_gain"
145 #define PARAM_NAME_SIMPLIFIED_PITCH_D_GAIN "simplified_pitch_d_gain"
146 #define PARAM_NAME_SIMPLIFIED_PITCH_PI_GAIN "simplified_pitch_pi_gain"
147 #define PARAM_NAME_SIMPLIFIED_DTERM_FILTER "simplified_dterm_filter"
148 #define PARAM_NAME_SIMPLIFIED_DTERM_FILTER_MULTIPLIER "simplified_dterm_filter_multiplier"
149 #define PARAM_NAME_SIMPLIFIED_GYRO_FILTER "simplified_gyro_filter"
150 #define PARAM_NAME_SIMPLIFIED_GYRO_FILTER_MULTIPLIER "simplified_gyro_filter_multiplier"
151 #define PARAM_NAME_DEBUG_MODE "debug_mode"
152 #define PARAM_NAME_RPM_FILTER_HARMONICS "rpm_filter_harmonics"
153 #define PARAM_NAME_RPM_FILTER_WEIGHTS "rpm_filter_weights"
154 #define PARAM_NAME_RPM_FILTER_Q "rpm_filter_q"
155 #define PARAM_NAME_RPM_FILTER_MIN_HZ "rpm_filter_min_hz"
156 #define PARAM_NAME_RPM_FILTER_FADE_RANGE_HZ "rpm_filter_fade_range_hz"
157 #define PARAM_NAME_RPM_FILTER_LPF_HZ "rpm_filter_lpf_hz"
159 #define PARAM_NAME_ALTITUDE_SOURCE "altitude_source"
160 #define PARAM_NAME_ALTITUDE_PREFER_BARO "altitude_prefer_baro"
161 #define PARAM_NAME_ALTITUDE_LPF "altitude_lpf"
162 #define PARAM_NAME_ALTITUDE_D_LPF "altitude_d_lpf"
164 #define PARAM_NAME_HOVER_THROTTLE "hover_throttle"
165 #define PARAM_NAME_LANDING_ALTITUDE "landing_altitude_m"
166 #define PARAM_NAME_THROTTLE_MIN "autopilot_throttle_min"
167 #define PARAM_NAME_THROTTLE_MAX "autopilot_throttle_max"
168 #define PARAM_NAME_ALTITUDE_P "autopilot_altitude_P"
169 #define PARAM_NAME_ALTITUDE_I "autopilot_altitude_I"
170 #define PARAM_NAME_ALTITUDE_D "autopilot_altitude_D"
171 #define PARAM_NAME_ALTITUDE_F "autopilot_altitude_F"
172 #define PARAM_NAME_POSITION_P "autopilot_position_P"
173 #define PARAM_NAME_POSITION_I "autopilot_position_I"
174 #define PARAM_NAME_POSITION_D "autopilot_position_D"
175 #define PARAM_NAME_POSITION_A "autopilot_position_A"
176 #define PARAM_NAME_POSITION_CUTOFF "autopilot_position_cutoff"
177 #define PARAM_NAME_AP_MAX_ANGLE "autopilot_max_angle"
179 #define PARAM_NAME_ANGLE_FEEDFORWARD "angle_feedforward"
180 #define PARAM_NAME_ANGLE_FF_SMOOTHING_MS "angle_feedforward_smoothing_ms"
181 #define PARAM_NAME_ANGLE_LIMIT "angle_limit"
182 #define PARAM_NAME_S_PITCH "s_pitch"
183 #define PARAM_NAME_S_ROLL "s_roll"
184 #define PARAM_NAME_S_YAW "s_yaw"
185 #define PARAM_NAME_ANGLE_P_GAIN "angle_p_gain"
186 #define PARAM_NAME_ANGLE_EARTH_REF "angle_earth_ref"
187 #define PARAM_NAME_ANGLE_PITCH_OFFSET "angle_pitch_offset"
189 #define PARAM_NAME_HORIZON_LEVEL_STRENGTH "horizon_level_strength"
190 #define PARAM_NAME_HORIZON_LIMIT_DEGREES "horizon_limit_degrees"
191 #define PARAM_NAME_HORIZON_LIMIT_STICKS "horizon_limit_sticks"
192 #define PARAM_NAME_HORIZON_IGNORE_STICKS "horizon_ignore_sticks"
193 #define PARAM_NAME_HORIZON_DELAY_MS "horizon_delay_ms"
195 #ifdef USE_GPS
196 #define PARAM_NAME_GPS_PROVIDER "gps_provider"
197 #define PARAM_NAME_GPS_SBAS_MODE "gps_sbas_mode"
198 #define PARAM_NAME_GPS_SBAS_INTEGRITY "gps_sbas_integrity"
199 #define PARAM_NAME_GPS_AUTO_CONFIG "gps_auto_config"
200 #define PARAM_NAME_GPS_AUTO_BAUD "gps_auto_baud"
201 #define PARAM_NAME_GPS_UBLOX_USE_GALILEO "gps_ublox_use_galileo"
202 #define PARAM_NAME_GPS_UBLOX_ACQUIRE_MODEL "gps_ublox_acquire_model"
203 #define PARAM_NAME_GPS_UBLOX_FLIGHT_MODEL "gps_ublox_flight_model"
204 #define PARAM_NAME_GPS_UBLOX_UTC_STANDARD "gps_ublox_utc_standard"
205 #define PARAM_NAME_GPS_SET_HOME_POINT_ONCE "gps_set_home_point_once"
206 #define PARAM_NAME_GPS_USE_3D_SPEED "gps_use_3d_speed"
207 #define PARAM_NAME_GPS_NMEA_CUSTOM_COMMANDS "gps_nmea_custom_commands"
208 #define PARAM_NAME_GPS_UPDATE_RATE_HZ "gps_update_rate_hz"
210 #ifdef USE_GPS_RESCUE
211 #define PARAM_NAME_GPS_RESCUE_MIN_START_DIST "gps_rescue_min_start_dist"
212 #define PARAM_NAME_GPS_RESCUE_ALT_MODE "gps_rescue_alt_mode"
213 #define PARAM_NAME_GPS_RESCUE_INITIAL_CLIMB "gps_rescue_initial_climb"
214 #define PARAM_NAME_GPS_RESCUE_ASCEND_RATE "gps_rescue_ascend_rate"
216 #define PARAM_NAME_GPS_RESCUE_RETURN_ALT "gps_rescue_return_alt"
217 #define PARAM_NAME_GPS_RESCUE_GROUND_SPEED "gps_rescue_ground_speed"
218 #define PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE "gps_rescue_max_angle"
219 #define PARAM_NAME_GPS_RESCUE_ROLL_MIX "gps_rescue_roll_mix"
220 #define PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF "gps_rescue_pitch_cutoff"
221 #define PARAM_NAME_GPS_RESCUE_IMU_YAW_GAIN "gps_rescue_imu_yaw_gain"
223 #define PARAM_NAME_GPS_RESCUE_DESCENT_DIST "gps_rescue_descent_dist"
224 #define PARAM_NAME_GPS_RESCUE_DESCEND_RATE "gps_rescue_descend_rate"
225 #define PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD "gps_rescue_disarm_threshold"
227 #define PARAM_NAME_GPS_RESCUE_SANITY_CHECKS "gps_rescue_sanity_checks"
228 #define PARAM_NAME_GPS_RESCUE_MIN_SATS "gps_rescue_min_sats"
229 #define PARAM_NAME_GPS_RESCUE_ALLOW_ARMING_WITHOUT_FIX "gps_rescue_allow_arming_without_fix"
231 #define PARAM_NAME_GPS_RESCUE_VELOCITY_P "gps_rescue_velocity_p"
232 #define PARAM_NAME_GPS_RESCUE_VELOCITY_I "gps_rescue_velocity_i"
233 #define PARAM_NAME_GPS_RESCUE_VELOCITY_D "gps_rescue_velocity_d"
234 #define PARAM_NAME_GPS_RESCUE_YAW_P "gps_rescue_yaw_p"
236 #ifdef USE_MAG
237 #define PARAM_NAME_GPS_RESCUE_USE_MAG "gps_rescue_use_mag"
238 #endif // USE_MAG
240 #endif // USE_GPS_RESCUE
242 #ifdef USE_GPS_LAP_TIMER
243 #define PARAM_NAME_GPS_LAP_TIMER_GATE_LAT "gps_lap_timer_gate_lat"
244 #define PARAM_NAME_GPS_LAP_TIMER_GATE_LON "gps_lap_timer_gate_lon"
245 #define PARAM_NAME_GPS_LAP_TIMER_MIN_LAP_TIME "gps_lap_timer_min_lap_time_s"
246 #define PARAM_NAME_GPS_LAP_TIMER_GATE_TOLERANCE "gps_lap_timer_gate_tolerance_m"
247 #endif // USE_GPS_LAP_TIMER
249 #endif // USE_GPS
251 #ifdef USE_ALTITUDE_HOLD
252 #define PARAM_NAME_ALT_HOLD_DEADBAND "alt_hold_deadband"
253 #define PARAM_NAME_ALT_HOLD_THROTTLE_RESPONSE "alt_hold_throttle_response"
254 #endif
256 #ifdef USE_POSITION_HOLD
257 #define PARAM_NAME_POS_HOLD_WITHOUT_MAG "pos_hold_without_mag"
258 #define PARAM_NAME_POS_HOLD_DEADBAND "pos_hold_deadband"
259 #endif
261 #define PARAM_NAME_IMU_DCM_KP "imu_dcm_kp"
262 #define PARAM_NAME_IMU_DCM_KI "imu_dcm_ki"
263 #define PARAM_NAME_IMU_SMALL_ANGLE "small_angle"
264 #define PARAM_NAME_IMU_PROCESS_DENOM "imu_process_denom"
265 #ifdef USE_MAG
266 #define PARAM_NAME_IMU_MAG_DECLINATION "mag_declination"
267 #endif