Merge pull request #11198 from SteveCEvans/sce_rc2
[betaflight.git] / src / main / fc / parameter_names.h
blobecadc67529c16255be199791d0cf2e8d8e189733
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_DSHOT_IDLE_VALUE "dshot_idle_value"
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_THROTTLE_LIMIT_TYPE "throttle_limit_type"
58 #define PARAM_NAME_THROTTLE_LIMIT_PERCENT "throttle_limit_percent"
59 #define PARAM_NAME_GYRO_CAL_ON_FIRST_ARM "gyro_cal_on_first_arm"
60 #define PARAM_NAME_DEADBAND "deadband"
61 #define PARAM_NAME_YAW_DEADBAND "yaw_deadband"
62 #define PARAM_NAME_PID_PROCESS_DENOM "pid_process_denom"
63 #define PARAM_NAME_DTERM_LPF1_TYPE "dterm_lpf1_type"
64 #define PARAM_NAME_DTERM_LPF1_STATIC_HZ "dterm_lpf1_static_hz"
65 #define PARAM_NAME_DTERM_LPF2_TYPE "dterm_lpf2_type"
66 #define PARAM_NAME_DTERM_LPF2_STATIC_HZ "dterm_lpf2_static_hz"
67 #define PARAM_NAME_DTERM_NOTCH_HZ "dterm_notch_hz"
68 #define PARAM_NAME_DTERM_NOTCH_CUTOFF "dterm_notch_cutoff"
69 #define PARAM_NAME_VBAT_SAG_COMPENSATION "vbat_sag_compensation"
70 #define PARAM_NAME_PID_AT_MIN_THROTTLE "pid_at_min_throttle"
71 #define PARAM_NAME_ANTI_GRAVITY_MODE "anti_gravity_mode"
72 #define PARAM_NAME_ANTI_GRAVITY_THRESHOLD "anti_gravity_threshold"
73 #define PARAM_NAME_ANTI_GRAVITY_GAIN "anti_gravity_gain"
74 #define PARAM_NAME_ACC_LIMIT_YAW "acc_limit_yaw"
75 #define PARAM_NAME_ACC_LIMIT "acc_limit"
76 #define PARAM_NAME_ITERM_RELAX "iterm_relax"
77 #define PARAM_NAME_ITERM_RELAX_TYPE "iterm_relax_type"
78 #define PARAM_NAME_ITERM_RELAX_CUTOFF "iterm_relax_cutoff"
79 #define PARAM_NAME_ITERM_WINDUP "iterm_windup"
80 #define PARAM_NAME_PIDSUM_LIMIT "pidsum_limit"
81 #define PARAM_NAME_PIDSUM_LIMIT_YAW "pidsum_limit_yaw"
82 #define PARAM_NAME_YAW_LOWPASS_HZ "yaw_lowpass_hz"
83 #define PARAM_NAME_THROTTLE_BOOST "throttle_boost"
84 #define PARAM_NAME_THROTTLE_BOOST_CUTOFF "throttle_boost_cutoff"
85 #define PARAM_NAME_ABS_CONTROL_GAIN "abs_control_gain"
86 #define PARAM_NAME_USE_INTEGRATED_YAW "use_integrated_yaw"
87 #define PARAM_NAME_D_MAX_GAIN "d_max_gain"
88 #define PARAM_NAME_D_MAX_ADVANCE "d_max_advance"
89 #define PARAM_NAME_MOTOR_OUTPUT_LIMIT "motor_output_limit"
90 #define PARAM_NAME_FEEDFORWARD_TRANSITION "feedforward_transition"
91 #define PARAM_NAME_FEEDFORWARD_AVERAGING "feedforward_averaging"
92 #define PARAM_NAME_FEEDFORWARD_SMOOTH_FACTOR "feedforward_smooth_factor"
93 #define PARAM_NAME_FEEDFORWARD_JITTER_FACTOR "feedforward_jitter_factor"
94 #define PARAM_NAME_FEEDFORWARD_BOOST "feedforward_boost"
95 #define PARAM_NAME_FEEDFORWARD_MAX_RATE_LIMIT "feedforward_max_rate_limit"
96 #define PARAM_NAME_DYN_IDLE_MIN_RPM "dyn_idle_min_rpm"
97 #define PARAM_NAME_DYN_IDLE_P_GAIN "dyn_idle_p_gain"
98 #define PARAM_NAME_DYN_IDLE_I_GAIN "dyn_idle_i_gain"
99 #define PARAM_NAME_DYN_IDLE_D_GAIN "dyn_idle_d_gain"
100 #define PARAM_NAME_DYN_IDLE_MAX_INCREASE "dyn_idle_max_increase"
101 #define PARAM_NAME_SIMPLIFIED_PIDS_MODE "simplified_pids_mode"
102 #define PARAM_NAME_SIMPLIFIED_MASTER_MULTIPLIER "simplified_master_multiplier"
103 #define PARAM_NAME_SIMPLIFIED_I_GAIN "simplified_i_gain"
104 #define PARAM_NAME_SIMPLIFIED_D_GAIN "simplified_d_gain"
105 #define PARAM_NAME_SIMPLIFIED_PI_GAIN "simplified_pi_gain"
106 #define PARAM_NAME_SIMPLIFIED_DMAX_GAIN "simplified_dmax_gain"
107 #define PARAM_NAME_SIMPLIFIED_FEEDFORWARD_GAIN "simplified_feedforward_gain"
108 #define PARAM_NAME_SIMPLIFIED_PITCH_D_GAIN "simplified_pitch_d_gain"
109 #define PARAM_NAME_SIMPLIFIED_PITCH_PI_GAIN "simplified_pitch_pi_gain"
110 #define PARAM_NAME_SIMPLIFIED_DTERM_FILTER "simplified_dterm_filter"
111 #define PARAM_NAME_SIMPLIFIED_DTERM_FILTER_MULTIPLIER "simplified_dterm_filter_multiplier"
112 #define PARAM_NAME_SIMPLIFIED_GYRO_FILTER "simplified_gyro_filter"
113 #define PARAM_NAME_SIMPLIFIED_GYRO_FILTER_MULTIPLIER "simplified_gyro_filter_multiplier"
114 #define PARAM_NAME_DEBUG_MODE "debug_mode"
115 #define PARAM_NAME_RPM_FILTER_HARMONICS "rpm_filter_harmonics"
116 #define PARAM_NAME_RPM_FILTER_Q "rpm_filter_q"
117 #define PARAM_NAME_RPM_FILTER_MIN_HZ "rpm_filter_min_hz"
118 #define PARAM_NAME_RPM_FILTER_FADE_RANGE_HZ "rpm_filter_fade_range_hz"
119 #define PARAM_NAME_RPM_FILTER_LPF_HZ "rpm_filter_lpf_hz"