3 values: ["DEFAULT", "CW0", "CW90", "CW180", "CW270", "CW0FLIP", "CW90FLIP", "CW180FLIP", "CW270FLIP"]
5 values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270","LSM6DXX", "FAKE"]
6 enum: accelerationSensor_e
7 - name: rangefinder_hardware
8 values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C", "FAKE", "TERARANGER_EVO", "USD1_V0", "NRA"]
9 enum: rangefinderType_e
11 values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"]
13 - name: opflow_hardware
14 values: ["NONE", "CXOF", "MSP", "FAKE"]
15 enum: opticalFlowSensor_e
17 values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "B2SMPB", "MSP", "FAKE"]
19 - name: pitot_hardware
20 values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP", "DLVR-L10D"]
23 values: ["NONE", "SERIAL", "MSP", "SIM (SITL)"]
24 enum: rxReceiverType_e
26 values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK", "FBUS"]
27 - name: blackbox_device
28 values: ["SERIAL", "SPIFLASH", "SDCARD", "FILE"]
29 - name: motor_pwm_protocol
30 values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"]
31 - name: servo_protocol
32 values: ["PWM", "SBUS", "SBUS_PWM"]
33 - name: failsafe_procedure
34 values: ["LAND", "DROP", "RTH", "NONE"]
35 - name: current_sensor
36 values: ["NONE", "ADC", "VIRTUAL", "FAKE", "ESC"]
38 - name: voltage_sensor
39 values: ["NONE", "ADC", "ESC", "FAKE"]
41 - name: imu_inertia_comp_method
42 values: ["VELNED", "TURNRATE","ADAPTIVE"]
43 enum: imu_inertia_comp_method_e
45 values: ["UBLOX", "MSP", "FAKE"]
48 values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"]
51 values: ["PEDESTRIAN","AUTOMOTIVE", "AIR_1G", "AIR_2G", "AIR_4G", "SEA", "MOWER"]
54 values: ["NEVER", "FIRST_ARM", "EACH_ARM"]
56 values: ["RIGHT", "LEFT", "YAW"]
57 - name: nav_user_control_mode
58 values: ["ATTI", "CRUISE"]
59 - name: nav_rth_alt_mode
60 values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST"]
61 - name: nav_rth_climb_first_stage_modes
62 values: ["AT_LEAST", "EXTRA"]
64 values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK", "GA"]
66 - name: osd_stats_energy_unit
68 enum: osd_stats_energy_unit_e
69 - name: osd_video_system
70 values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT"]
73 values: ["OFF", "ON","TEST"]
76 values: ["LEFT", "RIGHT"]
79 values: ["NORMAL", "MEDIUM", "SLOW"]
81 values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"]
83 values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE",
84 "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
85 "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE",
86 "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST",
87 "ADAPTIVE_FILTER", "HEADTRACKER", "GPS", "LULU"]
90 enum: modeActivationOperator_e
91 - name: osd_crosshairs_style
92 values: ["DEFAULT", "AIRCRAFT", "TYPE3", "TYPE4", "TYPE5", "TYPE6", "TYPE7", "TYPE8"]
93 enum: osd_crosshairs_style_e
94 - name: osd_sidebar_scroll
95 values: ["NONE", "ALTITUDE", "SPEED", "HOME_DISTANCE"]
96 enum: osd_sidebar_scroll_e
97 - name: nav_rth_allow_landing
98 values: ["NEVER", "ALWAYS", "FS_ONLY"]
99 enum: navRTHAllowLanding_e
100 - name: bat_capacity_unit
101 values: ["MAH", "MWH"]
102 enum: batCapacityUnit_e
103 - name: bat_voltage_source
104 values: ["RAW", "SAG_COMP"]
105 enum: batVoltageSource_e
106 - name: smartport_fuel_unit
107 values: ["PERCENT", "MAH", "MWH"]
108 enum: smartportFuelUnit_e
109 - name: platform_type
110 values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
111 - name: tz_automatic_dst
112 values: ["OFF", "EU", "USA"]
113 enum: tz_automatic_dst_e
114 - name: vtx_low_power_disarm
115 values: ["OFF", "ON", "UNTIL_FIRST_ARM"]
116 enum: vtxLowerPowerDisarm_e
117 - name: vtx_frequency_groups
118 values: ["FREQUENCYGROUP_5G8", "FREQUENCYGROUP_2G4", "FREQUENCYGROUP_1G3"]
119 enum: vtxFrequencyGroups_e
121 values: ["PT1", "BIQUAD"]
122 - name: filter_type_full
123 values: ["PT1", "BIQUAD", "PT2", "PT3", "LULU"]
125 values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"]
127 values: ["OFF", "RP", "RPY"]
129 - name: airmodeHandlingType
130 values: ["STICK_CENTER", "THROTTLE_THRESHOLD", "STICK_CENTER_ONCE"]
131 - name: nav_extra_arming_safety
132 values: ["ON", "ALLOW_BYPASS"]
133 enum: navExtraArmingSafety_e
135 values: ["NONE", "AUTO", "ADC", "CHANNEL", "PROTOCOL", "MSP"]
138 values: ["NONE", "PID", "PIFF", "AUTO"]
140 - name: osd_ahi_style
141 values: ["DEFAULT", "LINE"]
142 enum: osd_ahi_style_e
145 values: ["AUTO", "ON", "OFF"]
146 - name: osd_crsf_lq_format
147 enum: osd_crsf_lq_format_e
148 values: ["TYPE1", "TYPE2", "TYPE3"]
150 values: ["OFF", "ON"]
151 - name: djiOsdTempSource
152 values: ["ESC", "IMU", "BARO"]
153 enum: djiOsdTempSource_e
154 - name: osdSpeedSource
155 values: ["GROUND", "3D", "AIR"]
156 enum: osdSpeedSource_e
157 - name: nav_overrides_motor_stop
158 enum: navOverridesMotorStop_e
159 values: ["OFF_ALWAYS", "OFF", "AUTO_ONLY", "ALL_NAV"]
160 - name: osd_plus_code_short
161 values: ["0", "2", "4", "6"]
162 - name: autotune_rate_adjustment
163 enum: autotune_rate_adjustment_e
164 values: ["FIXED", "LIMIT", "AUTO"]
165 - name: safehome_usage_mode
166 values: ["OFF", "RTH", "RTH_FS"]
167 enum: safehomeUsageMode_e
168 - name: nav_rth_climb_first
169 enum: navRTHClimbFirst_e
170 values: ["OFF", "ON", "ON_FW_SPIRAL"]
171 - name: nav_wp_mission_restart
172 enum: navMissionRestart_e
173 values: ["START", "RESUME", "SWITCH"]
174 - name: djiRssiSource
175 values: ["RSSI", "CRSF_LQ"]
176 enum: djiRssiSource_e
177 - name: rth_trackback_mode
178 values: ["OFF", "ON", "FS"]
179 enum: rthTrackbackMode_e
180 - name: dynamic_gyro_notch_mode
182 enum: dynamicGyroNotchMode_e
183 - name: nav_fw_wp_turn_smoothing
184 values: ["OFF", "ON", "ON-CUT"]
185 enum: wpFwTurnSmoothing_e
186 - name: gps_auto_baud_max
187 values: [ '115200', '57600', '38400', '19200', '9600', '230400', '460800', '921600']
189 - name: nav_mc_althold_throttle
190 values: ["STICK", "MID_STICK", "HOVER"]
191 enum: navMcAltHoldThrottle_e
192 - name: led_pin_pwm_mode
193 values: ["SHARED_LOW", "SHARED_HIGH", "LOW", "HIGH"]
194 enum: led_pin_pwm_mode_e
195 - name: gyro_filter_mode
196 values: ["OFF", "STATIC", "DYNAMIC", "ADAPTIVE"]
197 enum: gyroFilterType_e
198 - name: headtracker_dev_type
199 values: ["NONE", "SERIAL", "MSP"]
200 enum: headTrackerDevType_e
209 ROLL_PITCH_RATE_MIN: 4
210 ROLL_PITCH_RATE_MAX: 180
212 MAX_CONTROL_RATE_PROFILE_COUNT: 3
213 MAX_BATTERY_PROFILE_COUNT: 3
217 - name: PG_GYRO_CONFIG
219 headers: ["sensors/gyro.h"]
222 description: "This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible."
225 - name: gyro_anti_aliasing_lpf_hz
226 description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz"
228 field: gyro_anti_aliasing_lpf_hz
230 - name: gyro_lulu_enabled
231 description: "Enable/disable gyro LULU filter"
233 field: gyroLuluEnabled
235 - name: gyro_lulu_sample_count
236 description: "Gyro lulu sample count, in number of samples."
238 field: gyroLuluSampleCount
241 - name: gyro_main_lpf_hz
242 description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)"
244 field: gyro_main_lpf_hz
247 - name: gyro_filter_mode
248 description: "Specifies the type of the software LPF of the gyro signals."
249 default_value: "STATIC"
250 field: gyroFilterMode
251 table: gyro_filter_mode
252 - name: gyro_dyn_lpf_min_hz
253 description: "Minimum frequency of the gyro Dynamic LPF"
255 field: gyroDynamicLpfMinHz
258 - name: gyro_dyn_lpf_max_hz
259 description: "Maximum frequency of the gyro Dynamic LPF"
261 field: gyroDynamicLpfMaxHz
264 - name: gyro_dyn_lpf_curve_expo
265 description: "Expo value for the throttle-to-frequency mapping for Dynamic LPF"
267 field: gyroDynamicLpfCurveExpo
270 - name: dynamic_gyro_notch_enabled
271 description: "Enable/disable dynamic gyro notch also known as Matrix Filter"
273 field: dynamicGyroNotchEnabled
274 condition: USE_DYNAMIC_FILTERS
276 - name: dynamic_gyro_notch_q
277 description: "Q factor for dynamic notches"
279 field: dynamicGyroNotchQ
280 condition: USE_DYNAMIC_FILTERS
283 - name: dynamic_gyro_notch_min_hz
284 description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirotors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`"
286 field: dynamicGyroNotchMinHz
287 condition: USE_DYNAMIC_FILTERS
290 - name: dynamic_gyro_notch_mode
291 description: "Gyro dynamic notch type"
293 table: dynamic_gyro_notch_mode
294 field: dynamicGyroNotchMode
295 condition: USE_DYNAMIC_FILTERS
296 - name: dynamic_gyro_notch_3d_q
297 description: "Q factor for 3D dynamic notches"
299 field: dynamicGyroNotch3dQ
300 condition: USE_DYNAMIC_FILTERS
304 description: "On multi-gyro targets, allows to choose which gyro to use. 0 = first gyro, 1 = second gyro"
305 condition: USE_DUAL_GYRO
309 - name: setpoint_kalman_enabled
310 description: "Enable Kalman filter on the gyro data"
312 condition: USE_GYRO_KALMAN
315 - name: setpoint_kalman_q
316 description: "Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds"
319 condition: USE_GYRO_KALMAN
322 - name: init_gyro_cal
323 description: "If defined to 'OFF', it will ignore the gyroscope calibration done at each startup. Instead, the gyroscope last calibration from when you calibrated will be used. It also means you don't have to keep the UAV stationary during a startup."
325 field: init_gyro_cal_enabled
328 description: "Calculated gyro zero calibration of axis X"
330 field: gyro_zero_cal[X]
334 description: "Calculated gyro zero calibration of axis Y"
336 field: gyro_zero_cal[Y]
340 description: "Calculated gyro zero calibration of axis Z"
342 field: gyro_zero_cal[Z]
345 - name: ins_gravity_cmss
346 description: "Calculated 1G of Acc axis Z to use in INS"
348 field: gravity_cmss_cal
351 - name: gyro_adaptive_filter_target
352 description: "Target value for adaptive filter"
354 field: adaptiveFilterTarget
357 condition: USE_ADAPTIVE_FILTER
358 - name: gyro_adaptive_filter_min_hz
359 description: "Minimum frequency for adaptive filter"
361 field: adaptiveFilterMinHz
364 condition: USE_ADAPTIVE_FILTER
365 - name: gyro_adaptive_filter_max_hz
366 description: "Maximum frequency for adaptive filter"
368 field: adaptiveFilterMaxHz
371 condition: USE_ADAPTIVE_FILTER
372 - name: gyro_adaptive_filter_std_lpf_hz
373 description: "Standard deviation low pass filter cutoff frequency"
375 field: adaptiveFilterStdLpfHz
378 condition: USE_ADAPTIVE_FILTER
379 - name: gyro_adaptive_filter_hpf_hz
380 description: "High pass filter cutoff frequency"
382 field: adaptiveFilterHpfHz
385 condition: USE_ADAPTIVE_FILTER
386 - name: gyro_adaptive_filter_integrator_threshold_high
387 description: "High threshold for adaptive filter integrator"
389 field: adaptiveFilterIntegratorThresholdHigh
392 condition: USE_ADAPTIVE_FILTER
393 - name: gyro_adaptive_filter_integrator_threshold_low
394 description: "Low threshold for adaptive filter integrator"
396 field: adaptiveFilterIntegratorThresholdLow
399 condition: USE_ADAPTIVE_FILTER
401 - name: PG_ADC_CHANNEL_CONFIG
402 type: adcChannelConfig_t
403 headers: ["fc/config.h"]
406 - name: vbat_adc_channel
407 description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled"
408 default_value: :target
409 field: adcFunctionChannel[ADC_BATTERY]
412 - name: rssi_adc_channel
413 description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled"
414 default_value: :target
415 field: adcFunctionChannel[ADC_RSSI]
418 - name: current_adc_channel
419 description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled"
420 default_value: :target
421 field: adcFunctionChannel[ADC_CURRENT]
424 - name: airspeed_adc_channel
425 description: "ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0"
426 default_value: :target
427 field: adcFunctionChannel[ADC_AIRSPEED]
431 - name: PG_ACCELEROMETER_CONFIG
432 type: accelerometerConfig_t
433 headers: ["sensors/acceleration.h"]
436 description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is center frequency (Hz)"
440 - name: acc_notch_cutoff
441 description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz)"
446 description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
447 default_value: "AUTO"
450 description: "Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value."
455 description: "Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds."
456 default_value: "BIQUAD"
457 field: acc_soft_lpf_type
460 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
462 field: accZero.raw[X]
466 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
468 field: accZero.raw[Y]
472 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
474 field: accZero.raw[Z]
478 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
480 field: accGain.raw[X]
484 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
486 field: accGain.raw[Y]
490 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
492 field: accGain.raw[Z]
496 - name: PG_RANGEFINDER_CONFIG
497 type: rangefinderConfig_t
498 headers: ["sensors/rangefinder.h"]
499 condition: USE_RANGEFINDER
501 - name: rangefinder_hardware
502 table: rangefinder_hardware
503 description: "Selection of rangefinder hardware."
504 default_value: "NONE"
505 - name: rangefinder_median_filter
506 description: "3-point median filtering for rangefinder readouts"
508 field: use_median_filtering
511 - name: PG_OPFLOW_CONFIG
512 type: opticalFlowConfig_t
513 headers: ["sensors/opflow.h"]
514 condition: USE_OPFLOW
516 - name: opflow_hardware
517 description: "Selection of OPFLOW hardware."
519 table: opflow_hardware
521 description: "Optical flow module scale factor"
526 description: "Optical flow module alignment (default CW0_DEG_FLIP)"
527 default_value: CW0FLIP
532 - name: PG_COMPASS_CONFIG
533 type: compassConfig_t
534 headers: ["sensors/compass.h"]
538 description: "When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP."
539 default_value: "DEFAULT"
544 description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
545 default_value: "AUTO"
547 - name: mag_declination
548 description: "Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix."
553 description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed."
555 field: magZero.raw[X]
559 description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed."
561 field: magZero.raw[Y]
565 description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed."
567 field: magZero.raw[Z]
571 description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed"
577 description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed"
583 description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed"
588 - name: mag_calibration_time
589 description: "Adjust how long time the Calibration of mag will last."
591 field: magCalibrationTimeLimit
595 description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target"
596 condition: USE_DUAL_MAG
600 - name: align_mag_roll
601 description: "Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw."
603 field: rollDeciDegrees
606 - name: align_mag_pitch
607 description: "Same as align_mag_roll, but for the pitch axis."
609 field: pitchDeciDegrees
612 - name: align_mag_yaw
613 description: "Same as align_mag_roll, but for the yaw axis."
615 field: yawDeciDegrees
619 - name: PG_BAROMETER_CONFIG
620 type: barometerConfig_t
621 headers: ["sensors/barometer.h"]
624 - name: baro_hardware
625 description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
626 default_value: "AUTO"
628 - name: baro_cal_tolerance
629 description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]."
631 field: baro_calibration_tolerance
635 - name: PG_PITOTMETER_CONFIG
636 type: pitotmeterConfig_t
637 headers: ["sensors/pitotmeter.h"]
640 - name: pitot_hardware
641 description: "Selection of pitot hardware."
642 default_value: "NONE"
643 table: pitot_hardware
644 - name: pitot_lpf_milli_hz
645 description: "Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay"
650 description: "Pitot tube scale factor"
657 headers: ["rx/rx.h", "rx/spektrum.h"]
659 - name: receiver_type
660 description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`"
661 default_value: :target
665 description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value."
671 description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value."
677 description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`"
678 default_value: "AUTO"
682 description: "RX channel containing the RSSI signal"
685 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
687 description: "The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI)."
690 min: RSSI_VISIBLE_VALUE_MIN
691 max: RSSI_VISIBLE_VALUE_MAX
693 description: "The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min."
696 min: RSSI_VISIBLE_VALUE_MIN
697 max: RSSI_VISIBLE_VALUE_MAX
698 - name: sbus_sync_interval
699 field: sbusSyncInterval
700 description: "SBUS sync interval in us. Default value is 3000us. Lower values may cause issues with some receivers."
704 - name: rc_filter_lpf_hz
705 description: "RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values"
707 field: rcFilterFrequency
710 - name: rc_filter_auto
711 description: "When enabled, INAV will set RC filtering based on refresh rate and smoothing factor."
715 - name: rc_filter_smoothing_factor
716 description: "The RC filter smoothing factor. The higher the value, the more smoothing but also the more delay in response. Value 1 sets the filter at half the refresh rate. Value 100 sets the filter to aprox. 10% of the RC refresh rate"
717 field: autoSmoothFactor
721 - name: serialrx_provider
722 description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section."
723 default_value: :target
724 condition: USE_SERIAL_RX
726 - name: serialrx_inverted
727 description: "Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY)."
729 condition: USE_SERIAL_RX
731 - name: spektrum_sat_bind
732 description: "0 = disabled. Used to bind the spektrum satellite to RX"
733 condition: USE_SPEKTRUM_BIND
734 min: SPEKTRUM_SAT_BIND_DISABLED
735 max: SPEKTRUM_SAT_BIND_MAX
736 default_value: :SPEKTRUM_SAT_BIND_DISABLED
737 - name: srxl2_unit_id
738 condition: USE_SERIALRX_SRXL2
742 - name: srxl2_baud_fast
743 condition: USE_SERIALRX_SRXL2
747 description: "Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc."
752 description: "Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc."
756 - name: serialrx_halfduplex
757 description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire."
758 default_value: "AUTO"
761 - name: msp_override_channels
762 description: "Mask of RX channels that may be overridden by MSP `SET_RAW_RC`. Note that this requires custom firmware with `USE_RX_MSP` and `USE_MSP_RC_OVERRIDE` compile options and the `MSP RC Override` flight mode."
764 field: mspOverrideChannels
765 condition: USE_MSP_RC_OVERRIDE
769 - name: PG_BLACKBOX_CONFIG
770 type: blackboxConfig_t
771 headers: ["blackbox/blackbox.h"]
772 condition: USE_BLACKBOX
774 - name: blackbox_rate_num
775 description: "Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations"
780 - name: blackbox_rate_denom
781 description: "Blackbox logging rate denominator. See blackbox_rate_num."
786 - name: blackbox_device
787 description: "Selection of where to write blackbox data"
788 default_value: :target
790 table: blackbox_device
791 - name: sdcard_detect_inverted
792 description: "This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value."
793 default_value: :target
794 field: invertedCardDetection
795 condition: USE_SDCARD
798 - name: PG_MOTOR_CONFIG
800 headers: ["flight/mixer.h"]
803 description: "This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once."
808 - name: motor_pwm_rate
809 description: "Output frequency (in Hz) for motor pins. Applies only to brushed motors. "
814 - name: motor_pwm_protocol
815 description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
816 default_value: "ONESHOT125"
817 field: motorPwmProtocol
818 table: motor_pwm_protocol
820 field: motorPoleCount
821 description: "The number of motor poles. Required to compute motor RPM"
826 - name: PG_FAILSAFE_CONFIG
827 type: failsafeConfig_t
828 headers: ["flight/failsafe.h"]
830 - name: failsafe_delay
831 description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)."
835 - name: failsafe_recovery_delay
836 description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)."
840 - name: failsafe_off_delay
841 description: "Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay)."
845 - name: failsafe_throttle_low_delay
846 description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout"
850 - name: failsafe_procedure
851 description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
852 default_value: "LAND"
853 table: failsafe_procedure
854 - name: failsafe_stick_threshold
855 description: "Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe."
857 field: failsafe_stick_motion_threshold
860 - name: failsafe_fw_roll_angle
861 description: "Amount of banking when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll"
865 - name: failsafe_fw_pitch_angle
866 description: "Amount of dive/climb when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb"
870 - name: failsafe_fw_yaw_rate
871 description: "Requested yaw rate to execute when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn"
875 - name: failsafe_min_distance
876 description: "If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken."
880 - name: failsafe_min_distance_procedure
881 description: "What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
882 default_value: "DROP"
883 table: failsafe_procedure
884 - name: failsafe_mission_delay
885 description: "Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end."
889 - name: failsafe_gps_fix_estimation_delay
890 description: "Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation."
891 condition: USE_GPS_FIX_ESTIMATION
896 - name: PG_LIGHTS_CONFIG
898 headers: ["io/lights.h"]
899 condition: USE_LIGHTS
901 - name: failsafe_lights
902 description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
904 field: failsafe.enabled
906 - name: failsafe_lights_flash_period
907 description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
909 field: failsafe.flash_period
912 - name: failsafe_lights_flash_on_time
913 description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
915 field: failsafe.flash_on_time
919 - name: PG_BOARD_ALIGNMENT
920 type: boardAlignment_t
921 headers: ["sensors/boardalignment.h"]
923 - name: align_board_roll
924 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
926 field: rollDeciDegrees
929 - name: align_board_pitch
930 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
932 field: pitchDeciDegrees
935 - name: align_board_yaw
936 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
938 field: yawDeciDegrees
942 - name: PG_BATTERY_METERS_CONFIG
943 type: batteryMetersConfig_t
944 headers: ["sensors/battery_config_structs.h"]
946 - name: vbat_meter_type
947 description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
951 table: voltage_sensor
954 description: "Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing \"status\" in cli."
955 default_value: :target
960 - name: battery_capacity_unit
961 description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)."
964 table: bat_capacity_unit
966 - name: current_meter_scale
967 description: "This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt."
968 default_value: :target
972 - name: current_meter_offset
973 description: "This sets the output offset voltage of the current sensor in millivolts."
974 default_value: :target
975 field: current.offset
978 - name: current_meter_type
979 description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position."
982 table: current_sensor
984 - name: bat_voltage_src
985 description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`"
988 table: bat_voltage_source
991 description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
997 description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
1002 - name: rth_energy_margin
1003 description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
1007 - name: thr_comp_weight
1008 description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
1010 field: throttle_compensation_weight
1014 - name: PG_BATTERY_PROFILES
1015 type: batteryProfile_t
1016 headers: ["sensors/battery_config_structs.h"]
1017 value_type: BATTERY_CONFIG_VALUE
1020 description: "Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected."
1026 - name: vbat_cell_detect_voltage
1027 description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units."
1029 field: voltage.cellDetect
1033 - name: vbat_max_cell_voltage
1034 description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
1036 field: voltage.cellMax
1040 - name: vbat_min_cell_voltage
1041 description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
1043 field: voltage.cellMin
1047 - name: vbat_warning_cell_voltage
1048 description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
1050 field: voltage.cellWarning
1054 - name: battery_capacity
1055 description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
1057 field: capacity.value
1060 - name: battery_capacity_warning
1061 description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
1063 field: capacity.warning
1066 - name: battery_capacity_critical
1067 description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
1069 field: capacity.critical
1072 - name: controlrate_profile
1073 description: "Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile"
1075 field: controlRateProfile
1077 max: MAX_CONTROL_RATE_PROFILE_COUNT
1079 - name: throttle_scale
1080 description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
1082 field: motor.throttleScale
1085 - name: throttle_idle
1086 description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
1088 field: motor.throttleIdle
1091 - name: turtle_mode_power_factor
1092 field: motor.turtleModePowerFactor
1094 description: "Turtle mode power factor"
1095 condition: USE_DSHOT
1098 - name: failsafe_throttle
1099 description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
1103 - name: nav_mc_hover_thr
1104 description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
1106 field: nav.mc.hover_throttle
1109 - name: nav_fw_cruise_thr
1110 description: "Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded )"
1112 field: nav.fw.cruise_throttle
1115 - name: nav_fw_min_thr
1116 description: "Minimum throttle for flying wing in GPS assisted modes"
1118 field: nav.fw.min_throttle
1121 - name: nav_fw_max_thr
1122 description: "Maximum throttle for flying wing in GPS assisted modes"
1124 field: nav.fw.max_throttle
1127 - name: nav_fw_pitch2thr
1128 description: "Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr)"
1130 field: nav.fw.pitch_to_throttle
1133 - name: nav_fw_launch_thr
1134 description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
1136 field: nav.fw.launch_throttle
1139 - name: nav_fw_launch_idle_thr
1140 description: "Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position)"
1142 field: nav.fw.launch_idle_throttle
1145 - name: limit_cont_current
1146 description: "Continous current limit (dA), set to 0 to disable"
1147 condition: USE_POWER_LIMITS
1149 field: powerLimits.continuousCurrent
1151 - name: limit_burst_current
1152 description: "Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable"
1153 condition: USE_POWER_LIMITS
1155 field: powerLimits.burstCurrent
1157 - name: limit_burst_current_time
1158 description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced"
1159 condition: USE_POWER_LIMITS
1161 field: powerLimits.burstCurrentTime
1163 - name: limit_burst_current_falldown_time
1164 description: "Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current`"
1165 condition: USE_POWER_LIMITS
1167 field: powerLimits.burstCurrentFalldownTime
1169 - name: limit_cont_power
1170 description: "Continous power limit (dW), set to 0 to disable"
1171 condition: USE_POWER_LIMITS && USE_ADC
1173 field: powerLimits.continuousPower
1175 - name: limit_burst_power
1176 description: "Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable"
1177 condition: USE_POWER_LIMITS && USE_ADC
1179 field: powerLimits.burstPower
1181 - name: limit_burst_power_time
1182 description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced"
1183 condition: USE_POWER_LIMITS && USE_ADC
1185 field: powerLimits.burstPowerTime
1187 - name: limit_burst_power_falldown_time
1188 description: "Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power`"
1189 condition: USE_POWER_LIMITS && USE_ADC
1191 field: powerLimits.burstPowerFalldownTime
1194 - name: PG_MIXER_PROFILE
1195 type: mixerProfile_t
1196 headers: ["flight/mixer_profile.h"]
1197 value_type: MIXER_CONFIG_VALUE
1199 - name: motor_direction_inverted
1200 description: "Use if you need to inverse yaw motor direction."
1202 field: mixer_config.motorDirectionInverted
1204 - name: platform_type
1205 description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
1206 default_value: "MULTIROTOR"
1207 field: mixer_config.platformType
1209 table: platform_type
1211 description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot"
1213 field: mixer_config.hasFlaps
1215 - name: model_preview_type
1216 description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
1218 field: mixer_config.appliedMixerPreset
1221 - name: motorstop_on_low
1222 description: "If enabled, motor will stop when throttle is low on this mixer_profile"
1224 field: mixer_config.motorstopOnLow
1226 - name: mixer_pid_profile_linking
1227 description: "If enabled, pid profile_index will follow mixer_profile index. Set to OFF(default) if you want to handle PID profile by your self. Recommend to set to ON on all mixer_profiles to let the mixer_profile handle the PID profile switching on a VTOL or mixed platform type setup."
1229 field: mixer_config.PIDProfileLinking
1231 - name: mixer_automated_switch
1232 description: "If set to on, This mixer_profile will try to switch to another mixer_profile when 1.RTH heading home is requested and distance to home is lager than 3*nav_fw_loiter_radius on mixer_profile is a MULTIROTOR or TRICOPTER platform_type. 2. RTH landing is requested on this mixer_profile is a AIRPLANE platform_type"
1234 field: mixer_config.automated_switch
1236 - name: mixer_switch_trans_timer
1237 description: "If switch another mixer_profile is scheduled by mixer_automated_switch or mixer_automated_switch. Activate Mixertransion motor/servo mixing for this many decisecond(0.1s) before the actual mixer_profile switch."
1239 field: mixer_config.switchTransitionTimer
1242 - name: tailsitter_orientation_offset
1243 description: "Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode"
1245 field: mixer_config.tailsitterOrientationOffset
1248 - name: PG_REVERSIBLE_MOTORS_CONFIG
1249 type: reversibleMotorsConfig_t
1251 - name: 3d_deadband_low
1252 description: "Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead)"
1257 - name: 3d_deadband_high
1258 description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
1260 field: deadband_high
1264 description: "Neutral (stop) throttle value for 3D mode"
1270 - name: PG_SERVO_CONFIG
1272 headers: ["flight/servos.h"]
1274 - name: servo_protocol
1275 description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SBUS` (S.Bus protocol output via a configured serial port)"
1276 default_value: "PWM"
1277 field: servo_protocol
1278 table: servo_protocol
1279 - name: servo_center_pulse
1280 description: "Servo midpoint"
1282 field: servoCenterPulse
1285 - name: servo_pwm_rate
1286 description: "Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz."
1291 - name: servo_lpf_hz
1292 description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
1294 field: servo_lowpass_freq
1297 - name: flaperon_throw_offset
1298 description: "Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated."
1300 min: FLAPERON_THROW_MIN
1301 max: FLAPERON_THROW_MAX
1302 - name: tri_unarmed_servo
1303 description: "On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF."
1306 - name: servo_autotrim_rotation_limit
1307 description: "Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`."
1312 - name: PG_CONTROL_RATE_PROFILES
1313 type: controlRateConfig_t
1314 headers: ["fc/controlrate_profile_config_struct.h"]
1315 value_type: CONTROL_RATE_VALUE
1318 description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
1320 field: throttle.rcMid8
1324 description: "Throttle exposition value"
1326 field: throttle.rcExpo8
1330 description: "Throttle PID attenuation reduces influence of PDFF on ROLL and PITCH of multi-rotor, PIDFF on ROLL,PITCH,YAW OF fixed_wing as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate."
1332 field: throttle.dynPID
1335 - name: tpa_breakpoint
1336 description: "See tpa_rate."
1338 field: throttle.pa_breakpoint
1342 description: "Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors."
1344 field: throttle.dynPID_on_YAW
1346 - name: fw_tpa_time_constant
1347 description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. See **PID Attenuation and scaling** Wiki for full details."
1349 field: throttle.fixedWingTauMs
1353 description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
1355 field: stabilized.rcExpo8
1359 description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
1361 field: stabilized.rcYawExpo8
1364 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
1365 # Rate 180 (1800dps) is max. value gyro can measure reliably
1367 description: "Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
1369 field: stabilized.rates[FD_ROLL]
1370 min: ROLL_PITCH_RATE_MIN
1371 max: ROLL_PITCH_RATE_MAX
1373 description: "Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
1375 field: stabilized.rates[FD_PITCH]
1376 min: ROLL_PITCH_RATE_MIN
1377 max: ROLL_PITCH_RATE_MAX
1379 description: "Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure."
1381 field: stabilized.rates[FD_YAW]
1384 - name: manual_rc_expo
1385 description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
1387 field: manual.rcExpo8
1390 - name: manual_rc_yaw_expo
1391 description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
1393 field: manual.rcYawExpo8
1396 - name: manual_roll_rate
1397 description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
1399 field: manual.rates[FD_ROLL]
1400 min: MANUAL_RATE_MIN
1401 max: MANUAL_RATE_MAX
1402 - name: manual_pitch_rate
1403 description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
1405 field: manual.rates[FD_PITCH]
1406 min: MANUAL_RATE_MIN
1407 max: MANUAL_RATE_MAX
1408 - name: manual_yaw_rate
1409 description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
1411 field: manual.rates[FD_YAW]
1412 min: MANUAL_RATE_MIN
1413 max: MANUAL_RATE_MAX
1414 - name: fpv_mix_degrees
1415 description: "The tilt angle of the FPV camera in degrees, used by the FPV ANGLE MIX mode"
1416 field: misc.fpvCamAngleDegrees
1420 - name: rate_dynamics_center_sensitivity
1421 field: rateDynamics.sensitivityCenter
1425 description: "The center stick sensitivity for Rate Dynamics"
1426 condition: USE_RATE_DYNAMICS
1427 - name: rate_dynamics_end_sensitivity
1428 field: rateDynamics.sensitivityEnd
1432 description: "The end stick sensitivity for Rate Dynamics"
1433 condition: USE_RATE_DYNAMICS
1434 - name: rate_dynamics_center_correction
1435 field: rateDynamics.correctionCenter
1439 description: "The center stick correction for Rate Dynamics"
1440 condition: USE_RATE_DYNAMICS
1441 - name: rate_dynamics_end_correction
1442 field: rateDynamics.correctionEnd
1446 description: "The end stick correction for Rate Dynamics"
1447 condition: USE_RATE_DYNAMICS
1448 - name: rate_dynamics_center_weight
1449 field: rateDynamics.weightCenter
1453 description: "The center stick weight for Rate Dynamics"
1454 condition: USE_RATE_DYNAMICS
1455 - name: rate_dynamics_end_weight
1456 field: rateDynamics.weightEnd
1460 description: "The end stick weight for Rate Dynamics"
1461 condition: USE_RATE_DYNAMICS
1463 - name: PG_SERIAL_CONFIG
1464 type: serialConfig_t
1465 headers: ["io/serial.h"]
1467 - name: reboot_character
1468 description: "Special character used to trigger reboot"
1473 - name: PG_IMU_CONFIG
1475 headers: ["flight/imu.h"]
1478 description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
1483 description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
1487 - name: ahrs_dcm_kp_mag
1488 description: "Inertial Measurement Unit KP Gain for compass measurements"
1492 - name: ahrs_dcm_ki_mag
1493 description: "Inertial Measurement Unit KI Gain for compass measurements"
1498 description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
1502 - name: ahrs_acc_ignore_rate
1503 description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy"
1505 field: acc_ignore_rate
1508 - name: ahrs_acc_ignore_slope
1509 description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
1511 field: acc_ignore_slope
1514 - name: ahrs_gps_yaw_windcomp
1515 description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)"
1517 field: gps_yaw_windcomp
1519 - name: ahrs_inertia_comp_method
1520 description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop"
1521 default_value: ADAPTIVE
1522 field: inertia_comp_method
1523 table: imu_inertia_comp_method
1524 - name: ahrs_gps_yaw_weight
1525 description: "Arhs gps yaw weight when mag is avaliable, 0 means no gps yaw, 100 means equal weight as compass"
1527 field: gps_yaw_weight
1531 - name: PG_ARMING_CONFIG
1532 type: armingConfig_t
1534 - name: fixed_wing_auto_arm
1535 description: "Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured."
1538 - name: disarm_always
1539 description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low."
1542 - name: switch_disarm_delay
1543 description: "Delay before disarming when requested by switch (ms) [0-1000]"
1545 field: switchDisarmDelayMs
1548 - name: prearm_timeout
1549 description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
1550 default_value: 10000
1551 field: prearmTimeoutMs
1555 - name: PG_GENERAL_SETTINGS
1556 headers: ["config/general_settings.h"]
1557 type: generalSettings_t
1559 - name: applied_defaults
1560 description: "Internal (configurator) hint. Should not be changed manually"
1562 field: appliedDefaults
1568 headers: ["flight/ez_tune.h"]
1569 type: ezTuneSettings_t
1570 value_type: EZ_TUNE_VALUE
1573 description: "Enables EzTune feature"
1577 - name: ez_filter_hz
1578 description: "EzTune filter cutoff frequency"
1583 - name: ez_axis_ratio
1584 description: "EzTune axis ratio"
1590 description: "EzTune response"
1596 description: "EzTune damping"
1601 - name: ez_stability
1602 description: "EzTune stability"
1607 - name: ez_aggressiveness
1608 description: "EzTune aggressiveness"
1610 field: aggressiveness
1614 description: "EzTune rate"
1620 description: "EzTune expo"
1625 - name: ez_snappiness
1626 description: "EzTune snappiness"
1632 - name: PG_RPM_FILTER_CONFIG
1633 headers: ["flight/rpm_filter.h"]
1634 condition: USE_RPM_FILTER
1635 type: rpmFilterConfig_t
1637 - name: rpm_gyro_filter_enabled
1638 description: "Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV"
1640 field: gyro_filter_enabled
1642 - name: rpm_gyro_harmonics
1643 description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
1645 field: gyro_harmonics
1649 - name: rpm_gyro_min_hz
1650 description: "The lowest frequency for gyro RPM filtere. Default `150` is fine for 5\" mini-quads. On 7-inch drones you can lower even down to `60`-`70`"
1657 description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
1663 - name: PG_GPS_CONFIG
1664 headers: [ "io/gps.h" ]
1668 - name: gps_provider
1669 description: "Which GPS protocol to be used."
1670 default_value: "UBLOX"
1674 - name: gps_sbas_mode
1675 description: "Which SBAS mode to be used"
1676 default_value: "NONE"
1678 table: gps_sbas_mode
1680 - name: gps_dyn_model
1681 description: "GPS navigation model: Pedestrian, Automotive, Air<1g, Air<2g, Air<4g. Default is AIR_2G. Use pedestrian/Automotive with caution, can cause flyaways with fast flying."
1682 default_value: "AIR_2G"
1684 table: gps_dyn_model
1686 - name: gps_auto_config
1687 description: "Enable automatic configuration of UBlox GPS receivers."
1691 - name: gps_auto_baud
1692 description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS"
1696 - name: gps_auto_baud_max_supported
1697 description: "Max baudrate supported by GPS unit. This is used during autobaud. M8 supports up to 460400, M10 supports up to 921600 and 230400 is the value used before INAV 7.0"
1698 default_value: "230400"
1699 table: gps_auto_baud_max
1702 - name: gps_ublox_use_galileo
1703 description: "Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]."
1705 field: ubloxUseGalileo
1707 - name: gps_ublox_use_beidou
1708 description: "Enable use of Beidou satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps hardware support [OFF/ON]."
1710 field: ubloxUseBeidou
1712 - name: gps_ublox_use_glonass
1713 description: "Enable use of Glonass satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires gps haardware support [OFF/ON]."
1715 field: ubloxUseGlonass
1717 - name: gps_min_sats
1718 description: "Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count."
1723 - name: gps_ublox_nav_hz
1724 description: "Navigation update rate for UBLOX receivers. Some receivers may limit the maximum number of satellites tracked when set to a higher rate or even stop sending navigation updates if the value is too high. Some M10 devices can do up to 25Hz. 10 is a safe value for M8 and newer."
1732 - name: PG_RC_CONTROLS_CONFIG
1733 type: rcControlsConfig_t
1734 headers: ["fc/rc_controls.h"]
1737 description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle."
1741 - name: yaw_deadband
1742 description: "These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle."
1746 - name: pos_hold_deadband
1747 description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
1751 - name: alt_hold_deadband
1752 description: "Defines the deadband of throttle during alt_hold [r/c points]"
1756 - name: 3d_deadband_throttle
1757 description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
1759 field: mid_throttle_deadband
1762 - name: airmode_type
1763 description: "Defines the Airmode state handling type. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `airmode_throttle_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER_ONCE** or **STICK_CENTER** modes."
1764 default_value: "STICK_CENTER"
1765 field: airmodeHandlingType
1766 table: airmodeHandlingType
1767 - name: airmode_throttle_threshold
1768 description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
1770 field: airmodeThrottleThreshold
1774 - name: PG_PID_PROFILE
1776 headers: ["flight/pid.h"]
1777 value_type: PROFILE_VALUE
1780 description: "Multicopter rate stabilisation P-gain for PITCH"
1782 field: bank_mc.pid[PID_PITCH].P
1786 description: "Multicopter rate stabilisation I-gain for PITCH"
1788 field: bank_mc.pid[PID_PITCH].I
1792 description: "Multicopter rate stabilisation D-gain for PITCH"
1794 field: bank_mc.pid[PID_PITCH].D
1798 description: "Multicopter Control Derivative gain for PITCH (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1800 field: bank_mc.pid[PID_PITCH].FF
1804 description: "Multicopter rate stabilisation P-gain for ROLL"
1806 field: bank_mc.pid[PID_ROLL].P
1810 description: "Multicopter rate stabilisation I-gain for ROLL"
1812 field: bank_mc.pid[PID_ROLL].I
1816 description: "Multicopter rate stabilisation D-gain for ROLL"
1818 field: bank_mc.pid[PID_ROLL].D
1822 description: "Multicopter Control Derivative gain for ROLL (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1824 field: bank_mc.pid[PID_ROLL].FF
1828 description: "Multicopter rate stabilisation P-gain for YAW"
1830 field: bank_mc.pid[PID_YAW].P
1834 description: "Multicopter rate stabilisation I-gain for YAW"
1836 field: bank_mc.pid[PID_YAW].I
1840 description: "Multicopter rate stabilisation D-gain for YAW"
1842 field: bank_mc.pid[PID_YAW].D
1846 description: "Multicopter Control Derivative gain for YAW (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1848 field: bank_mc.pid[PID_YAW].FF
1852 description: "Multicopter attitude stabilisation P-gain"
1854 field: bank_mc.pid[PID_LEVEL].P
1858 description: "Multicopter attitude stabilisation low-pass filter cutoff"
1860 field: bank_mc.pid[PID_LEVEL].I
1864 description: "Multicopter attitude stabilisation HORIZON transition point"
1866 field: bank_mc.pid[PID_LEVEL].D
1870 description: "Fixed-wing rate stabilisation P-gain for PITCH"
1872 field: bank_fw.pid[PID_PITCH].P
1876 description: "Fixed-wing rate stabilisation I-gain for PITCH"
1878 field: bank_fw.pid[PID_PITCH].I
1882 description: "Fixed wing rate stabilisation D-gain for PITCH"
1884 field: bank_fw.pid[PID_PITCH].D
1888 description: "Fixed-wing rate stabilisation FF-gain for PITCH"
1890 field: bank_fw.pid[PID_PITCH].FF
1894 description: "Fixed-wing rate stabilisation P-gain for ROLL"
1896 field: bank_fw.pid[PID_ROLL].P
1900 description: "Fixed-wing rate stabilisation I-gain for ROLL"
1902 field: bank_fw.pid[PID_ROLL].I
1906 description: "Fixed wing rate stabilisation D-gain for ROLL"
1908 field: bank_fw.pid[PID_ROLL].D
1912 description: "Fixed-wing rate stabilisation FF-gain for ROLL"
1914 field: bank_fw.pid[PID_ROLL].FF
1918 description: "Fixed-wing rate stabilisation P-gain for YAW"
1920 field: bank_fw.pid[PID_YAW].P
1924 description: "Fixed-wing rate stabilisation I-gain for YAW"
1926 field: bank_fw.pid[PID_YAW].I
1930 description: "Fixed wing rate stabilisation D-gain for YAW"
1932 field: bank_fw.pid[PID_YAW].D
1936 description: "Fixed-wing rate stabilisation FF-gain for YAW"
1938 field: bank_fw.pid[PID_YAW].FF
1942 description: "Fixed-wing attitude stabilisation P-gain"
1944 field: bank_fw.pid[PID_LEVEL].P
1948 description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
1950 field: bank_fw.pid[PID_LEVEL].I
1954 description: "Fixed-wing attitude stabilisation HORIZON transition point"
1956 field: bank_fw.pid[PID_LEVEL].D
1959 - name: max_angle_inclination_rll
1960 description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
1962 field: max_angle_inclination[FD_ROLL]
1965 - name: max_angle_inclination_pit
1966 description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
1968 field: max_angle_inclination[FD_PITCH]
1971 - name: dterm_lpf_hz
1972 description: "Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value"
1976 - name: dterm_lpf_type
1977 description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
1978 default_value: "PT2"
1979 field: dterm_lpf_type
1980 table: filter_type_full
1982 description: "Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
1986 - name: fw_reference_airspeed
1987 description: "Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present."
1989 field: fixedWingReferenceAirspeed
1992 - name: fw_turn_assist_yaw_gain
1993 description: "Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter"
1995 field: fixedWingCoordinatedYawGain
1998 - name: fw_turn_assist_pitch_gain
1999 description: "Gain required to keep constant pitch angle during coordinated turns (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter"
2001 field: fixedWingCoordinatedPitchGain
2004 - name: fw_yaw_iterm_freeze_bank_angle
2005 description: "Yaw Iterm is frozen when bank angle is above this threshold [degrees]. This solves the problem of the rudder counteracting turns by partially disabling yaw stabilization when making banked turns. Setting to 0 (the default) disables this feature. Only applies when autopilot is not active and TURN ASSIST is disabled."
2007 field: fixedWingYawItermBankFreeze
2010 - name: iterm_windup
2011 description: "Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter)"
2013 field: itermWindupPointPercent
2016 - name: pid_iterm_limit_percent
2017 description: "Limits max/min I-term value in stabilization PID controller. It solves the problem of servo saturation before take-off/throwing the airplane into the air. Or multirotors with low authority. By default, error accumulated in I-term can not exceed 33% of total pid throw (around 165us on deafult pidsum_limit of pitch/roll). Set 0 to disable completely."
2019 field: pidItermLimitPercent
2022 - name: rate_accel_limit_roll_pitch
2023 description: "Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting."
2025 field: axisAccelerationLimitRollPitch
2027 - name: rate_accel_limit_yaw
2028 description: "Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting."
2029 default_value: 10000
2030 field: axisAccelerationLimitYaw
2032 - name: heading_hold_rate_limit
2033 description: "This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes."
2034 min: HEADING_HOLD_RATE_LIMIT_MIN
2035 max: HEADING_HOLD_RATE_LIMIT_MAX
2037 - name: nav_mc_pos_z_p
2038 description: "P gain of altitude PID controller (Multirotor)"
2039 field: bank_mc.pid[PID_POS_Z].P
2043 - name: nav_mc_vel_z_p
2044 description: "P gain of velocity PID controller"
2045 field: bank_mc.pid[PID_VEL_Z].P
2049 - name: nav_mc_vel_z_i
2050 description: "I gain of velocity PID controller"
2051 field: bank_mc.pid[PID_VEL_Z].I
2055 - name: nav_mc_vel_z_d
2056 description: "D gain of velocity PID controller"
2057 field: bank_mc.pid[PID_VEL_Z].D
2061 - name: nav_mc_pos_xy_p
2062 description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
2063 field: bank_mc.pid[PID_POS_XY].P
2067 - name: nav_mc_vel_xy_p
2068 description: "P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause \"nervous\" behavior and oscillations"
2069 field: bank_mc.pid[PID_VEL_XY].P
2073 - name: nav_mc_vel_xy_i
2074 description: "I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot"
2075 field: bank_mc.pid[PID_VEL_XY].I
2079 - name: nav_mc_vel_xy_d
2080 description: "D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target."
2081 field: bank_mc.pid[PID_VEL_XY].D
2085 - name: nav_mc_vel_xy_ff
2086 description: "FF gain of Position-Rate (Velocity to Acceleration)"
2087 field: bank_mc.pid[PID_VEL_XY].FF
2091 - name: nav_mc_heading_p
2092 description: "P gain of Heading Hold controller (Multirotor)"
2094 field: bank_mc.pid[PID_HEADING].P
2097 - name: nav_mc_vel_xy_dterm_lpf_hz
2098 description: "D-term low pass filter cutoff frequency for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating."
2099 field: navVelXyDTermLpfHz
2103 - name: nav_mc_vel_xy_dterm_attenuation
2104 description: "Maximum D-term attenution percentage for horizontal velocity PID controller (Multirotor). It allows to smooth the PosHold CRUISE, WP and RTH when Multirotor is traveling at full speed. Dterm is not attenuated at low speeds, breaking and accelerating."
2105 field: navVelXyDtermAttenuation
2109 - name: nav_mc_vel_xy_dterm_attenuation_start
2110 description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
2112 field: navVelXyDtermAttenuationStart
2115 - name: nav_mc_vel_xy_dterm_attenuation_end
2116 description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
2118 field: navVelXyDtermAttenuationEnd
2121 - name: nav_fw_pos_z_p
2122 description: "P gain of altitude PID controller (Fixedwing)"
2124 field: bank_fw.pid[PID_POS_Z].P
2127 - name: nav_fw_pos_z_i
2128 description: "I gain of altitude PID controller (Fixedwing)"
2130 field: bank_fw.pid[PID_POS_Z].I
2133 - name: nav_fw_pos_z_d
2134 description: "D gain of altitude PID controller (Fixedwing)"
2136 field: bank_fw.pid[PID_POS_Z].D
2139 - name: nav_fw_alt_control_response
2140 description: "Adjusts the deceleration response of fixed wing altitude control as the target altitude is approached. Decrease value to help avoid overshooting the target altitude."
2142 field: fwAltControlResponseFactor
2145 - name: nav_fw_pos_xy_p
2146 description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
2148 field: bank_fw.pid[PID_POS_XY].P
2151 - name: nav_fw_pos_xy_i
2152 description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2154 field: bank_fw.pid[PID_POS_XY].I
2157 - name: nav_fw_pos_xy_d
2158 description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2160 field: bank_fw.pid[PID_POS_XY].D
2163 - name: nav_fw_heading_p
2164 description: "P gain of Heading Hold controller (Fixedwing)"
2166 field: bank_fw.pid[PID_HEADING].P
2169 - name: nav_fw_pos_hdg_p
2170 description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
2172 field: bank_fw.pid[PID_POS_HEADING].P
2175 - name: nav_fw_pos_hdg_i
2176 description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2178 field: bank_fw.pid[PID_POS_HEADING].I
2181 - name: nav_fw_pos_hdg_d
2182 description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2184 field: bank_fw.pid[PID_POS_HEADING].D
2187 - name: nav_fw_pos_hdg_pidsum_limit
2188 description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
2190 field: navFwPosHdgPidsumLimit
2191 min: PID_SUM_LIMIT_MIN
2192 max: PID_SUM_LIMIT_MAX
2193 - name: mc_iterm_relax
2194 description: "Iterm relax type. When enabled, Iterm will be relaxed when stick is centered. This will help to reduce bounceback and followthrough on multirotors. It is recommended to enable this feature on all multirotors."
2198 - name: mc_iterm_relax_cutoff
2199 description: "Iterm relax cutoff frequency."
2200 field: iterm_relax_cutoff
2205 description: "D-term multiplier when pilot provides rapid stick input. Lower values give sharper response to stick input, higher values give smoother response."
2207 condition: USE_D_BOOST
2212 description: "D-term multiplier when rapid external conditions are detected. Lower values give sharper response to stick input, higher values give smoother response by scaling D-gains up."
2214 condition: USE_D_BOOST
2218 - name: d_boost_max_at_acceleration
2219 description: "Acceleration threshold for D-term multiplier. When acceleration is above this value, D-term multiplier is set to `d_boost_max`"
2220 field: dBoostMaxAtAlleceleration
2221 condition: USE_D_BOOST
2225 - name: d_boost_gyro_delta_lpf_hz
2226 description: "Cutoff frequency for the low pass filter applied to the gyro delta signal used for D-term boost. Lower value will produce a smoother D-term boost signal, but it will be more delayed."
2227 field: dBoostGyroDeltaLpfHz
2228 condition: USE_D_BOOST
2232 - name: antigravity_gain
2233 description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
2235 field: antigravityGain
2236 condition: USE_ANTIGRAVITY
2239 - name: antigravity_accelerator
2240 description: "Multiplier for Antigravity gain. The bigger is the difference between actual and filtered throttle input, the bigger Antigravity gain"
2242 field: antigravityAccelerator
2243 condition: USE_ANTIGRAVITY
2246 - name: antigravity_cutoff_lpf_hz
2247 description: "Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain"
2249 field: antigravityCutoff
2250 condition: USE_ANTIGRAVITY
2254 description: "Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID`"
2255 field: pidControllerType
2258 - name: mc_cd_lpf_hz
2259 description: "Cutoff frequency for Control Derivative. This controls the cutoff for the LPF that is applied to the CD (Feed Forward) signal to the PID controller. Lower value will produce a smoother CD gain to the controller, but it will be more delayed. Higher values will produce CD gain that may have more noise in the signal depending on your RC link but wil be less delayed."
2261 field: controlDerivativeLpfHz
2264 - name: fw_level_pitch_trim
2265 description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
2267 field: fixedWingLevelTrim
2270 - name: smith_predictor_strength
2271 description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2273 field: smithPredictorStrength
2274 condition: USE_SMITH_PREDICTOR
2277 - name: smith_predictor_delay
2278 description: "Expected delay of the gyro signal. In milliseconds"
2280 field: smithPredictorDelay
2281 condition: USE_SMITH_PREDICTOR
2284 - name: smith_predictor_lpf_hz
2285 description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2287 field: smithPredictorFilterHz
2288 condition: USE_SMITH_PREDICTOR
2291 - name: fw_level_pitch_gain
2292 description: "I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations"
2294 field: fixedWingLevelTrimGain
2297 - name: fw_iterm_lock_time_max_ms
2298 description: Defines max time in milliseconds for how long ITerm Lock will shut down Iterm after sticks are release
2300 field: fwItermLockTimeMaxMs
2303 - name: fw_iterm_lock_rate_threshold
2304 description: Defines rate percentage when full P I and D attenuation should happen. 100 disables Iterm Lock for P and D term
2305 field: fwItermLockRateLimit
2309 - name: fw_iterm_lock_engage_threshold
2310 description: Defines error rate (in percents of max rate) when Iterm Lock is engaged when sticks are release. Iterm Lock will stay active until error drops below this number
2314 field: fwItermLockEngageThreshold
2316 - name: PG_PID_AUTOTUNE_CONFIG
2317 type: pidAutotuneConfig_t
2318 condition: USE_AUTOTUNE_FIXED_WING
2320 - name: fw_autotune_min_stick
2321 description: "Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input."
2326 - name: fw_autotune_rate_adjustment
2327 description: "`AUTO` and `LIMIT` adjust the rates to match the capabilities of the airplane, with `LIMIT` they are never increased above the starting rates setting. `FIXED` does not adjust the rates. Rates are not changed when tuning in `ANGLE` mode."
2328 default_value: "AUTO"
2329 field: fw_rate_adjustment
2330 table: autotune_rate_adjustment
2332 - name: fw_autotune_max_rate_deflection
2333 description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
2335 field: fw_max_rate_deflection
2339 - name: PG_POSITION_ESTIMATION_CONFIG
2340 type: positionEstimationConfig_t
2342 - name: inav_auto_mag_decl
2343 description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
2345 field: automatic_mag_declination
2347 - name: inav_gravity_cal_tolerance
2348 description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
2350 field: gravity_calibration_tolerance
2353 - name: inav_allow_dead_reckoning
2354 description: "Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
2356 field: allow_dead_reckoning
2358 - name: inav_allow_gps_fix_estimation
2359 description: "Defines if inav will estimate GPS fix with magnetometer and barometer on GPS outages. Enables navigation and RTH without GPS fix on fixed wing. Also see failsafe_gps_fix_estimation_delay."
2360 condition: USE_GPS_FIX_ESTIMATION
2362 field: allow_gps_fix_estimation
2364 - name: inav_reset_altitude
2365 description: "Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming)"
2366 default_value: "FIRST_ARM"
2367 field: reset_altitude_type
2369 - name: inav_reset_home
2370 description: "Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM"
2371 default_value: "FIRST_ARM"
2372 field: reset_home_type
2374 - name: inav_max_surface_altitude
2375 description: "Max allowed altitude for surface following mode. [cm]"
2377 field: max_surface_altitude
2380 - name: inav_w_z_surface_p
2381 description: "Weight of rangefinder measurements in estimated altitude. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled"
2382 field: w_z_surface_p
2386 - name: inav_w_z_surface_v
2387 description: "Weight of rangefinder measurements in estimated climb rate. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled"
2388 field: w_z_surface_v
2392 - name: inav_w_xy_flow_p
2393 description: "Weight of optical flow measurements in estimated UAV position."
2398 - name: inav_w_xy_flow_v
2399 description: "Weight of optical flow measurements in estimated UAV speed."
2404 - name: inav_w_z_baro_p
2405 description: "Weight of barometer measurements in estimated altitude and climb rate. Setting is used on both airplanes and multirotors."
2410 - name: inav_w_z_gps_p
2411 description: "Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors."
2416 - name: inav_w_z_gps_v
2417 description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
2422 - name: inav_w_xy_gps_p
2423 description: "Weight of GPS coordinates in estimated UAV position and speed."
2428 - name: inav_w_xy_gps_v
2429 description: "Weight of GPS velocity data in estimated UAV speed"
2434 - name: inav_w_z_res_v
2435 description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
2440 - name: inav_w_xy_res_v
2441 description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
2446 - name: inav_w_acc_bias
2447 description: "Weight for accelerometer drift estimation"
2452 - name: inav_max_eph_epv
2453 description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
2458 - name: inav_baro_epv
2459 description: "Uncertainty value for barometric sensor [cm]"
2465 - name: PG_NAV_CONFIG
2467 headers: ["navigation/navigation.h"]
2469 - name: nav_disarm_on_landing
2470 description: "If set to ON, INAV disarms the FC after landing"
2472 field: general.flags.disarm_on_landing
2474 - name: nav_land_detect_sensitivity
2475 description: "Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases."
2477 field: general.land_detect_sensitivity
2480 - name: nav_landing_bump_detection
2481 description: "Allows immediate landing detection based on G bump at touchdown when set to ON. Requires a barometer and GPS and currently only works for multirotors (Note: will work during Failsafe without need for a GPS)."
2483 field: general.flags.landing_bump_detection
2485 - name: nav_mc_inverted_crash_detection
2486 description: "Setting a value > 0 enables inverted crash detection for multirotors. It will auto disarm in situations where the multirotor has crashed inverted on the ground and can't be manually disarmed due to loss of control or for some other reason. When enabled this setting defines the additional number of seconds before disarm beyond a minimum fixed time delay of 3s. Requires a barometer to work."
2488 field: mc.inverted_crash_detection
2491 - name: nav_mc_althold_throttle
2492 description: "If set to STICK the FC remembers the throttle stick position when enabling ALTHOLD and treats it as the neutral midpoint for holding altitude. If set to MID_STICK or HOVER the neutral midpoint is set to the mid stick position or the hover throttle position respectively."
2493 default_value: "STICK"
2494 field: mc.althold_throttle_type
2495 table: nav_mc_althold_throttle
2496 - name: nav_extra_arming_safety
2497 description: "If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used"
2498 default_value: "ALLOW_BYPASS"
2499 field: general.flags.extra_arming_safety
2500 table: nav_extra_arming_safety
2501 - name: nav_user_control_mode
2502 description: "Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction."
2503 default_value: "ATTI"
2504 field: general.flags.user_control_mode
2505 table: nav_user_control_mode
2506 - name: nav_position_timeout
2507 description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
2509 field: general.pos_failure_timeout
2512 - name: nav_wp_load_on_boot
2513 description: "If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup."
2515 field: general.waypoint_load_on_boot
2517 - name: nav_wp_radius
2518 description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
2520 field: general.waypoint_radius
2523 - name: nav_wp_enforce_altitude
2524 description: "Forces craft to achieve the set WP altitude as well as position before moving to next WP. Position is held and altitude adjusted as required before moving on. 0 = disabled, otherwise setting defines altitude capture tolerance [cm], e.g. 100 means required altitude is achieved when within 100cm of waypoint altitude setting."
2526 field: general.waypoint_enforce_altitude
2529 - name: nav_wp_max_safe_distance
2530 description: "First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check."
2532 field: general.waypoint_safe_distance
2535 - name: nav_wp_mission_restart
2536 description: "Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint."
2537 default_value: "RESUME"
2538 field: general.flags.waypoint_mission_restart
2539 table: nav_wp_mission_restart
2540 - name: nav_wp_multi_mission_index
2541 description: "Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions."
2543 field: general.waypoint_multi_mission_index
2544 condition: USE_MULTI_MISSION
2547 - name: nav_fw_wp_tracking_accuracy
2548 description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable."
2550 field: fw.wp_tracking_accuracy
2553 - name: nav_fw_wp_tracking_max_angle
2554 description: "Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved."
2556 field: fw.wp_tracking_max_angle
2559 - name: nav_fw_wp_turn_smoothing
2560 description: "Smooths turns during WP missions by switching to a loiter turn at waypoints. When set to ON the craft will reach the waypoint during the turn. When set to ON-CUT the craft will turn inside the waypoint without actually reaching it (cuts the corner)."
2561 default_value: "OFF"
2562 field: fw.wp_turn_smoothing
2563 table: nav_fw_wp_turn_smoothing
2564 - name: nav_auto_speed
2565 description: "Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]"
2567 field: general.auto_speed
2570 - name: nav_min_ground_speed
2571 description: "Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s."
2573 field: general.min_ground_speed
2576 - name: nav_max_auto_speed
2577 description: "Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]"
2579 field: general.max_auto_speed
2582 - name: nav_manual_speed
2583 description: "Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
2585 field: general.max_manual_speed
2588 - name: nav_land_minalt_vspd
2589 description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
2591 field: general.land_minalt_vspd
2594 - name: nav_land_maxalt_vspd
2595 description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"
2597 field: general.land_maxalt_vspd
2600 - name: nav_land_slowdown_minalt
2601 description: "Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]"
2603 field: general.land_slowdown_minalt
2606 - name: nav_land_slowdown_maxalt
2607 description: "Defines at what altitude the descent velocity should start to ramp down from `nav_land_maxalt_vspd` to `nav_land_minalt_vspd` during the RTH landing phase [cm]"
2609 field: general.land_slowdown_maxalt
2612 - name: nav_emerg_landing_speed
2613 description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
2615 field: general.emerg_descent_rate
2618 - name: nav_min_rth_distance
2619 description: "Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase."
2621 field: general.min_rth_distance
2624 - name: nav_overrides_motor_stop
2625 description: "When set to OFF the navigation system will not take over the control of the motor if the throttle is low (motor will stop). When set to OFF_ALWAYS the navigation system will not take over the control of the motor if the throttle was low even when failsafe is triggered. When set to AUTO_ONLY the navigation system will only take over the control of the throttle in autonomous navigation modes (NAV WP and NAV RTH). When set to ALL_NAV (default) the navigation system will take over the control of the motor completely and never allow the motor to stop even when the throttle is low. This setting only has an effect on NAV modes which take control of the throttle when combined with MOTOR_STOP and is likely to cause a stall if fw_min_throttle_down_pitch isn't set correctly or the pitch estimation is wrong for fixed wing models when not set to ALL_NAV"
2626 default_value: "ALL_NAV"
2627 field: general.flags.nav_overrides_motor_stop
2628 table: nav_overrides_motor_stop
2629 - name: nav_fw_soaring_motor_stop
2630 description: "Stops motor when Soaring mode enabled."
2632 field: general.flags.soaring_motor_stop
2634 - name: nav_fw_soaring_pitch_deadband
2635 description: "Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within deadband allowing pitch to free float whilst soaring."
2637 field: fw.soaring_pitch_deadband
2640 - name: nav_rth_climb_first
2641 description: "If set to ON or ON_FW_SPIRAL aircraft will climb to nav_rth_altitude first before turning to head home. If set to OFF aircraft will turn and head home immediately climbing on the way. For a fixed wing ON will use a linear climb, ON_FW_SPIRAL will use a loiter turning climb with climb rate set by nav_auto_climb_rate, turn rate set by nav_fw_loiter_radius (ON_FW_SPIRAL is a fixed wing setting and behaves the same as ON for a multirotor)"
2643 field: general.flags.rth_climb_first
2644 table: nav_rth_climb_first
2645 - name: nav_rth_climb_first_stage_mode
2646 description: "This determines how rth_climb_first_stage_altitude is used. Default is AT_LEAST."
2647 default_value: "AT_LEAST"
2648 field: general.flags.rth_climb_first_stage_mode
2649 table: nav_rth_climb_first_stage_modes
2650 - name: nav_rth_climb_first_stage_altitude
2651 description: "The altitude [cm] at which climb first will transition to turn first. How the altitude is used, is determined by nav_rth_climb_first_stage_mode. Default=0; feature disabled."
2653 field: general.rth_climb_first_stage_altitude
2655 - name: nav_rth_climb_ignore_emerg
2656 description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
2658 field: general.flags.rth_climb_ignore_emerg
2660 - name: nav_rth_tail_first
2661 description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
2663 field: general.flags.rth_tail_first
2665 - name: nav_rth_allow_landing
2666 description: "If set to ON drone will land as a last phase of RTH."
2667 default_value: "ALWAYS"
2668 field: general.flags.rth_allow_landing
2669 table: nav_rth_allow_landing
2670 - name: nav_rth_fs_landing_delay
2671 description: "If landing is active on Failsafe and this is above 0. The aircraft will hover or loiter for X seconds before performing the landing. If the battery enters the warning or critical levels, the land will proceed. Default = 0 [seconds]"
2675 field: general.rth_fs_landing_delay
2676 - name: nav_rth_alt_mode
2677 description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details"
2678 default_value: "AT_LEAST"
2679 field: general.flags.rth_alt_control_mode
2680 table: nav_rth_alt_mode
2681 - name: nav_rth_alt_control_override
2682 description: "If set to ON RTH altitude and CLIMB FIRST settings can be overridden during the RTH climb phase using full pitch or roll stick held for > 1 second. RTH altitude is reset to the current altitude using pitch down stick. RTH CLIMB FIRST is overridden using right roll stick so craft turns and heads directly to home (CLIMB FIRST override only works for fixed wing)"
2684 field: general.flags.rth_alt_control_override
2686 - name: nav_rth_abort_threshold
2687 description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. Set to 0 to disable. [cm]"
2688 default_value: 50000
2689 field: general.rth_abort_threshold
2692 - name: nav_max_terrain_follow_alt
2693 field: general.max_terrain_follow_altitude
2694 default_value: "100"
2695 description: "Max allowed above the ground altitude for terrain following mode"
2698 - name: nav_max_altitude
2699 field: general.max_altitude
2700 description: "Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled"
2704 - name: nav_rth_altitude
2705 description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
2707 field: general.rth_altitude
2709 - name: nav_rth_home_altitude
2710 description: "Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm]"
2712 field: general.rth_home_altitude
2714 - name: nav_rth_linear_descent_start_distance
2715 description: The distance [m] away from home to start the linear descent. 0 = immediately (original linear descent behaviour)
2719 field: general.rth_linear_descent_start_distance
2720 - name: nav_rth_use_linear_descent
2721 description: If enabled, the aircraft will gradually descent to the nav_rth_home_altitude en route. The distance from home to start the descent can be set with `nav_rth_linear_descent_start_distance`.
2724 field: general.flags.rth_use_linear_descent
2725 - name: nav_rth_trackback_mode
2726 description: "Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only."
2727 default_value: "OFF"
2728 field: general.flags.rth_trackback_mode
2729 table: rth_trackback_mode
2730 - name: nav_rth_trackback_distance
2731 description: "Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m]."
2733 field: general.rth_trackback_distance
2736 - name: safehome_max_distance
2737 description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
2738 default_value: 20000
2739 field: general.safehome_max_distance
2742 - name: safehome_usage_mode
2743 description: "Used to control when safehomes will be used. Possible values are `OFF`, `RTH` and `RTH_FS`. See [Safehome documentation](Safehomes.md#Safehome) for more information."
2744 default_value: "RTH"
2745 field: general.flags.safehome_usage_mode
2746 table: safehome_usage_mode
2747 - name: nav_mission_planner_reset
2748 description: "With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling the mode switch ON-OFF-ON."
2750 field: general.flags.mission_planner_reset
2752 - name: nav_cruise_yaw_rate
2753 description: "Max YAW rate when NAV COURSE HOLD/CRUISE mode is enabled. Set to 0 to disable on fixed wing (Note: On multirotor setting to 0 will disable Course Hold/Cruise mode completely) [dps]"
2755 field: general.cruise_yaw_rate
2758 - name: nav_mc_bank_angle
2759 description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
2761 field: mc.max_bank_angle
2764 - name: nav_mc_auto_climb_rate
2765 description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2767 field: mc.max_auto_climb_rate
2770 - name: nav_mc_manual_climb_rate
2771 description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2773 field: mc.max_manual_climb_rate
2776 - name: nav_auto_disarm_delay
2777 description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)"
2779 field: general.auto_disarm_delay
2782 - name: nav_mc_braking_speed_threshold
2783 description: "min speed in cm/s above which braking can happen"
2785 field: mc.braking_speed_threshold
2786 condition: USE_MR_BRAKING_MODE
2789 - name: nav_mc_braking_disengage_speed
2790 description: "braking is disabled when speed goes below this value"
2792 field: mc.braking_disengage_speed
2793 condition: USE_MR_BRAKING_MODE
2796 - name: nav_mc_braking_timeout
2797 description: "timeout in ms for braking"
2799 field: mc.braking_timeout
2800 condition: USE_MR_BRAKING_MODE
2803 - name: nav_mc_braking_boost_factor
2804 description: "acceleration factor for BOOST phase"
2806 field: mc.braking_boost_factor
2807 condition: USE_MR_BRAKING_MODE
2810 - name: nav_mc_braking_boost_timeout
2811 description: "how long in ms BOOST phase can happen"
2813 field: mc.braking_boost_timeout
2814 condition: USE_MR_BRAKING_MODE
2817 - name: nav_mc_braking_boost_speed_threshold
2818 description: "BOOST can be enabled when speed is above this value"
2820 field: mc.braking_boost_speed_threshold
2821 condition: USE_MR_BRAKING_MODE
2824 - name: nav_mc_braking_boost_disengage_speed
2825 description: "BOOST will be disabled when speed goes below this value"
2827 field: mc.braking_boost_disengage_speed
2828 condition: USE_MR_BRAKING_MODE
2831 - name: nav_mc_braking_bank_angle
2832 description: "max angle that MR is allowed to bank in BOOST mode"
2834 field: mc.braking_bank_angle
2835 condition: USE_MR_BRAKING_MODE
2838 - name: nav_mc_pos_deceleration_time
2839 description: "Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting"
2841 field: mc.posDecelerationTime
2844 - name: nav_mc_pos_expo
2845 description: "Expo for PosHold control"
2847 field: mc.posResponseExpo
2850 - name: nav_mc_wp_slowdown
2851 description: "When ON, NAV engine will slow down when switching to the next waypoint. This prioritizes turning over forward movement. When OFF, NAV engine will continue to the next waypoint and turn as it goes."
2853 field: mc.slowDownForTurning
2855 - name: nav_fw_bank_angle
2856 description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
2858 field: fw.max_bank_angle
2861 - name: nav_fw_auto_climb_rate
2862 description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2864 field: fw.max_auto_climb_rate
2867 - name: nav_fw_manual_climb_rate
2868 description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2870 field: fw.max_manual_climb_rate
2873 - name: nav_fw_climb_angle
2874 description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2876 field: fw.max_climb_angle
2879 - name: nav_fw_dive_angle
2880 description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2882 field: fw.max_dive_angle
2885 - name: nav_fw_pitch2thr_smoothing
2886 description: "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
2888 field: fw.pitch_to_throttle_smooth
2891 - name: fw_min_throttle_down_pitch
2892 description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
2894 field: fw.minThrottleDownPitchAngle
2897 - name: nav_fw_pitch2thr_threshold
2898 description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
2900 field: fw.pitch_to_throttle_thresh
2903 - name: nav_fw_loiter_radius
2904 description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
2906 field: fw.loiter_radius
2909 - name: fw_loiter_direction
2910 description: "Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick."
2911 default_value: "RIGHT"
2912 field: fw.loiter_direction
2914 - name: nav_fw_cruise_speed
2915 description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
2917 field: fw.cruise_speed
2920 - name: nav_fw_control_smoothness
2921 description: "How smoothly the autopilot controls the airplane to correct the navigation error"
2923 field: fw.control_smoothness
2926 - name: nav_fw_land_dive_angle
2927 description: "Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees"
2929 field: fw.land_dive_angle
2932 - name: nav_fw_launch_velocity
2933 description: "Forward velocity threshold for swing-launch detection [cm/s]"
2935 field: fw.launch_velocity_thresh
2938 - name: nav_fw_launch_accel
2939 description: "Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s"
2941 field: fw.launch_accel_thresh
2944 - name: nav_fw_launch_max_angle
2945 description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
2947 field: fw.launch_max_angle
2950 - name: nav_fw_launch_detect_time
2951 description: "Time for which thresholds have to breached to consider launch happened [ms]"
2953 field: fw.launch_time_thresh
2956 - name: nav_fw_launch_idle_motor_delay
2957 description: "Delay between raising throttle and motor starting at idle throttle (ms)"
2959 field: fw.launch_idle_motor_timer
2962 - name: nav_fw_launch_wiggle_to_wake_idle
2963 description: "Trigger the idle throttle by wiggling the plane. 0 = disabled. 1 and 2 signify 1 or 2 yaw wiggles to activate. 1 wiggle has a higher detection point, for airplanes without a tail. 2 wiggles has a lower detection point, but requires the repeated action. This is intended for larger models and airplanes with tails."
2964 field: fw.launch_wiggle_wake_idle
2969 - name: nav_fw_launch_motor_delay
2970 description: "Delay between detected launch and launch sequence start and throttling up (ms)"
2972 field: fw.launch_motor_timer
2975 - name: nav_fw_launch_spinup_time
2976 description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
2978 field: fw.launch_motor_spinup_time
2981 - name: nav_fw_launch_end_time
2982 description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
2984 field: fw.launch_end_time
2987 - name: nav_fw_launch_min_time
2988 description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
2990 field: fw.launch_min_time
2993 - name: nav_fw_launch_timeout
2994 description: "Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms)"
2996 field: fw.launch_timeout
2998 - name: nav_fw_launch_max_altitude
2999 description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
3001 field: fw.launch_max_altitude
3004 - name: nav_fw_launch_climb_angle
3005 description: "Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
3007 field: fw.launch_climb_angle
3010 - name: nav_fw_launch_manual_throttle
3011 description: "Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised)."
3013 field: fw.launch_manual_throttle
3015 - name: nav_fw_launch_land_abort_deadband
3016 description: "Launch and landing abort stick deadband in [r/c points], applied after r/c deadband and expo. The Roll/Pitch stick needs to be deflected beyond this deadband to abort the launch or landing."
3018 field: fw.launch_land_abort_deadband
3021 - name: nav_fw_allow_manual_thr_increase
3022 description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
3024 field: fw.allow_manual_thr_increase
3026 - name: nav_use_fw_yaw_control
3027 description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
3029 field: fw.useFwNavYawControl
3031 - name: nav_fw_yaw_deadband
3032 description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
3034 field: fw.yawControlDeadband
3038 - name: PG_TELEMETRY_CONFIG
3039 type: telemetryConfig_t
3040 headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/sim.h"]
3041 condition: USE_TELEMETRY
3043 - name: telemetry_switch
3044 description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
3047 - name: telemetry_inverted
3048 description: "Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used."
3051 - name: frsky_pitch_roll
3052 description: "S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
3055 - name: report_cell_voltage
3056 description: "S.Port and IBUS telemetry: Send the average cell voltage if set to ON"
3059 - name: hott_alarm_sound_interval
3060 description: "Battery alarm delay in seconds for Hott telemetry"
3062 field: hottAlarmSoundInterval
3065 - name: telemetry_halfduplex
3066 description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
3070 - name: smartport_fuel_unit
3071 description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]"
3072 default_value: "MAH"
3073 field: smartportFuelUnit
3074 condition: USE_TELEMETRY_SMARTPORT
3076 table: smartport_fuel_unit
3077 - name: ibus_telemetry_type
3078 description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
3080 field: ibusTelemetryType
3083 - name: ltm_update_rate
3084 description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details."
3085 default_value: "NORMAL"
3086 field: ltmUpdateRate
3087 condition: USE_TELEMETRY_LTM
3089 - name: sim_ground_station_number
3090 description: "Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module."
3092 field: simGroundStationNumber
3093 condition: USE_TELEMETRY_SIM
3095 description: "PIN code for the SIM module"
3096 default_value: "0000"
3098 condition: USE_TELEMETRY_SIM
3099 - name: sim_transmit_interval
3100 description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
3102 field: simTransmitInterval
3103 condition: USE_TELEMETRY_SIM
3105 min: SIM_MIN_TRANSMIT_INTERVAL
3107 - name: sim_transmit_flags
3108 description: "Bitmask specifying text message transmit condition flags for the SIM module. 1: continuous transmission, 2: continuous transmission in failsafe mode, 4: continuous transmission when GPS signal quality is low, 8: acceleration events, 16: continuous transmission when altitude is below `sim_low_altitude`"
3109 default_value: :SIM_TX_FLAG_FAILSAFE
3110 field: simTransmitFlags
3111 condition: USE_TELEMETRY_SIM
3113 - name: acc_event_threshold_high
3114 description: "Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off."
3116 field: accEventThresholdHigh
3117 condition: USE_TELEMETRY_SIM
3121 - name: acc_event_threshold_low
3122 description: "Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off."
3124 field: accEventThresholdLow
3125 condition: USE_TELEMETRY_SIM
3129 - name: acc_event_threshold_neg_x
3130 description: "Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off."
3132 field: accEventThresholdNegX
3133 condition: USE_TELEMETRY_SIM
3137 - name: sim_low_altitude
3138 description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
3139 default_value: -32767
3140 field: simLowAltitude
3141 condition: USE_TELEMETRY_SIM
3145 - name: mavlink_ext_status_rate
3146 field: mavlink.extended_status_rate
3147 description: "Rate of the extended status message for MAVLink telemetry"
3152 - name: mavlink_rc_chan_rate
3153 description: "Rate of the RC channels message for MAVLink telemetry"
3154 field: mavlink.rc_channels_rate
3159 - name: mavlink_pos_rate
3160 description: "Rate of the position message for MAVLink telemetry"
3161 field: mavlink.position_rate
3166 - name: mavlink_extra1_rate
3167 description: "Rate of the extra1 message for MAVLink telemetry"
3168 field: mavlink.extra1_rate
3173 - name: mavlink_extra2_rate
3174 description: "Rate of the extra2 message for MAVLink telemetry"
3175 field: mavlink.extra2_rate
3180 - name: mavlink_extra3_rate
3181 description: "Rate of the extra3 message for MAVLink telemetry"
3182 field: mavlink.extra3_rate
3187 - name: mavlink_version
3188 field: mavlink.version
3189 description: "Version of MAVLink to use"
3195 - name: PG_OSD_CONFIG
3197 headers: ["io/osd.h", "drivers/osd.h"]
3200 - name: osd_telemetry
3201 description: "To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`"
3202 table: osd_telemetry
3205 default_value: "OFF"
3206 - name: osd_video_system
3207 description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT`"
3208 default_value: "AUTO"
3209 table: osd_video_system
3212 - name: osd_row_shiftdown
3213 description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
3215 field: row_shiftdown
3218 - name: osd_msp_displayport_fullframe_interval
3219 description: "Full Frame redraw interval for MSP DisplayPort [deciseconds]. This is how often a full frame update is sent to the DisplayPort, to cut down on OSD artifacting. The default value should be fine for most pilots. Though long range pilots may benefit from increasing the refresh time, especially near the edge of range. -1 = disabled (legacy mode) | 0 = every frame (not recommended) | default = 10 (1 second)"
3224 field: msp_displayport_fullframe_interval
3226 description: "IMPERIAL, METRIC, UK"
3227 default_value: "METRIC"
3231 - name: osd_stats_energy_unit
3232 description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)"
3233 default_value: "MAH"
3234 field: stats_energy_unit
3235 table: osd_stats_energy_unit
3237 - name: osd_stats_page_auto_swap_time
3238 description: "Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0."
3240 field: stats_page_auto_swap_time
3243 - name: osd_stats_show_metric_efficiency
3244 description: "Enabling this option will show metric efficiency statistics on the post flight stats screen. In addition to the efficiency statistics in your chosen units."
3247 field: stats_show_metric_efficiency
3248 - name: osd_rssi_alarm
3249 description: "Value below which to make the OSD RSSI indicator blink"
3254 - name: osd_time_alarm
3255 description: "Value above which to make the OSD flight time indicator blink (minutes)"
3260 - name: osd_alt_alarm
3261 description: "Value above which to make the OSD relative altitude indicator blink (meters)"
3266 - name: osd_dist_alarm
3267 description: "Value above which to make the OSD distance from home indicator blink (meters)"
3272 - name: osd_neg_alt_alarm
3273 description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
3275 field: neg_alt_alarm
3278 - name: osd_current_alarm
3279 description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
3281 field: current_alarm
3284 - name: osd_gforce_alarm
3285 description: "Value above which the OSD g force indicator will blink (g)"
3290 - name: osd_gforce_axis_alarm_min
3291 description: "Value under which the OSD axis g force indicators will blink (g)"
3293 field: gforce_axis_alarm_min
3296 - name: osd_gforce_axis_alarm_max
3297 description: "Value above which the OSD axis g force indicators will blink (g)"
3299 field: gforce_axis_alarm_max
3302 - name: osd_imu_temp_alarm_min
3303 description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3305 field: imu_temp_alarm_min
3308 - name: osd_imu_temp_alarm_max
3309 description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3311 field: imu_temp_alarm_max
3314 - name: osd_esc_temp_alarm_max
3315 description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3317 field: esc_temp_alarm_max
3320 - name: osd_esc_temp_alarm_min
3321 description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3323 field: esc_temp_alarm_min
3326 - name: osd_baro_temp_alarm_min
3327 description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3329 field: baro_temp_alarm_min
3333 - name: osd_baro_temp_alarm_max
3334 description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3336 field: baro_temp_alarm_max
3340 - name: osd_snr_alarm
3341 condition: USE_SERIALRX_CRSF
3342 description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
3347 - name: osd_link_quality_alarm
3348 condition: USE_SERIALRX_CRSF
3349 description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
3351 field: link_quality_alarm
3354 - name: osd_rssi_dbm_alarm
3355 condition: USE_SERIALRX_CRSF
3356 description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
3358 field: rssi_dbm_alarm
3361 - name: osd_rssi_dbm_max
3362 condition: USE_SERIALRX_CRSF
3363 description: "RSSI dBm upper end of curve. Perfect rssi (max) = 100%"
3368 - name: osd_rssi_dbm_min
3369 condition: USE_SERIALRX_CRSF
3370 description: "RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%"
3375 - name: osd_temp_label_align
3376 description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
3377 default_value: "LEFT"
3378 field: temp_label_align
3379 condition: USE_TEMPERATURE_SENSOR
3380 table: osd_alignment
3382 - name: osd_airspeed_alarm_min
3383 condition: USE_PITOT
3384 description: "Airspeed under which the airspeed OSD element will start blinking (cm/s)"
3386 field: airspeed_alarm_min
3388 max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3389 - name: osd_airspeed_alarm_max
3390 condition: USE_PITOT
3391 description: "Airspeed above which the airspeed OSD element will start blinking (cm/s)"
3393 field: airspeed_alarm_max
3395 max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3396 - name: osd_ahi_reverse_roll
3397 description: "Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement."
3398 field: ahi_reverse_roll
3401 - name: osd_ahi_max_pitch
3402 description: "Max pitch, in degrees, for OSD artificial horizon"
3404 field: ahi_max_pitch
3408 - name: osd_crosshairs_style
3409 description: "To set the visual type for the crosshair"
3410 default_value: "DEFAULT"
3411 field: crosshairs_style
3412 table: osd_crosshairs_style
3414 - name: osd_crsf_lq_format
3415 description: "To select LQ format"
3416 default_value: "TYPE1"
3417 field: crsf_lq_format
3418 table: osd_crsf_lq_format
3420 - name: osd_horizon_offset
3421 description: "To vertically adjust the whole OSD and AHI and scrolling bars"
3423 field: horizon_offset
3426 - name: osd_camera_uptilt
3427 description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled)."
3429 field: camera_uptilt
3432 - name: osd_ahi_camera_uptilt_comp
3433 description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD)."
3435 field: ahi_camera_uptilt_comp
3437 - name: osd_camera_fov_h
3438 description: "Horizontal field of view for the camera in degres"
3443 - name: osd_camera_fov_v
3444 description: "Vertical field of view for the camera in degres"
3449 - name: osd_hud_margin_h
3450 description: "Left and right margins for the hud area"
3455 - name: osd_hud_margin_v
3456 description: "Top and bottom margins for the hud area"
3461 - name: osd_hud_homing
3462 description: "To display little arrows around the crossair showing where the home point is in the hud"
3466 - name: osd_hud_homepoint
3467 description: "To 3D-display the home point location in the hud"
3469 field: hud_homepoint
3471 - name: osd_hud_radar_disp
3472 description: "Maximum count of nearby aircrafts or points of interest to display in the hud, as sent from an ESP32 LoRa module. Set to 0 to disable (show nothing). The nearby aircrafts will appear as markers A, B, C, etc"
3474 field: hud_radar_disp
3477 - name: osd_hud_radar_range_min
3478 description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
3480 field: hud_radar_range_min
3483 - name: osd_hud_radar_range_max
3484 description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
3486 field: hud_radar_range_max
3489 - name: osd_hud_radar_alt_difference_display_time
3490 description: "Time in seconds to display the altitude difference in radar"
3491 field: hud_radar_alt_difference_display_time
3495 - name: osd_hud_radar_distance_display_time
3496 description: "Time in seconds to display the distance in radar"
3497 field: hud_radar_distance_display_time
3501 - name: osd_radar_peers_display_time
3502 description: "Time in seconds to display next peer "
3503 field: radar_peers_display_time
3507 - name: osd_hud_wp_disp
3508 description: "How many navigation waypoints are displayed, set to 0 (zero) to disable. As sample, if set to 2, and you just passed the 3rd waypoint of the mission, you'll see markers for the 4th waypoint (marked 1) and the 5th waypoint (marked 2)"
3513 - name: osd_left_sidebar_scroll
3514 description: "Scroll type for the left sidebar"
3515 field: left_sidebar_scroll
3516 table: osd_sidebar_scroll
3519 - name: osd_right_sidebar_scroll
3520 description: "Scroll type for the right sidebar"
3521 field: right_sidebar_scroll
3522 table: osd_sidebar_scroll
3525 - name: osd_sidebar_scroll_arrows
3526 description: "Show arrows for scrolling the sidebars"
3527 field: sidebar_scroll_arrows
3530 - name: osd_main_voltage_decimals
3531 description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
3533 field: main_voltage_decimals
3536 - name: osd_coordinate_digits
3537 description: "Number of digits for the coordinates displayed in the OSD [8-11]."
3538 field: coordinate_digits
3542 - name: osd_adsb_distance_warning
3543 description: "Distance in meters of ADSB aircraft that is displayed"
3544 default_value: 20000
3546 field: adsb_distance_warning
3550 - name: osd_adsb_distance_alert
3551 description: "Distance inside which ADSB data flashes for proximity warning"
3554 field: adsb_distance_alert
3558 - name: osd_adsb_ignore_plane_above_me_limit
3559 description: "Ignore adsb planes above, limit, 0 disabled (meters)"
3562 field: adsb_ignore_plane_above_me_limit
3566 - name: osd_estimations_wind_compensation
3567 description: "Use wind estimation for remaining flight time/distance estimation"
3569 condition: USE_WIND_ESTIMATOR
3570 field: estimations_wind_compensation
3572 - name: osd_estimations_wind_mps
3573 description: "Wind speed estimation in m/s"
3575 condition: USE_WIND_ESTIMATOR
3576 field: estimations_wind_mps
3578 - name: osd_failsafe_switch_layout
3579 description: "If enabled the OSD automatically switches to the first layout during failsafe"
3582 - name: osd_plus_code_digits
3583 description: "Numer of plus code digits before shortening with `osd_plus_code_short`. Precision at the equator: 10=13.9x13.9m; 11=2.8x3.5m; 12=56x87cm; 13=11x22cm."
3584 field: plus_code_digits
3588 - name: osd_plus_code_short
3589 description: "Number of leading digits removed from plus code. Removing 2, 4 and 6 digits requires a reference location within, respectively, ~800km, ~40 km and ~2km to recover the original coordinates."
3590 field: plus_code_short
3592 table: osd_plus_code_short
3593 - name: osd_ahi_style
3594 description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
3596 default_value: "DEFAULT"
3597 table: osd_ahi_style
3599 - name: osd_force_grid
3603 description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
3604 - name: osd_ahi_bordered
3607 description: Shows a border/corners around the AHI region (pixel OSD only)
3609 - name: osd_ahi_width
3612 description: AHI width in pixels (pixel OSD only)
3614 - name: osd_ahi_height
3617 description: AHI height in pixels (pixel OSD only)
3619 - name: osd_ahi_vertical_offset
3620 field: ahi_vertical_offset
3623 description: AHI vertical offset from center (pixel OSD only)
3625 - name: osd_sidebar_horizontal_offset
3626 field: sidebar_horizontal_offset
3630 description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
3631 - name: osd_left_sidebar_scroll_step
3632 field: left_sidebar_scroll_step
3635 description: How many units each sidebar step represents. 0 means the default value for the scroll type.
3636 - name: osd_right_sidebar_scroll_step
3637 field: right_sidebar_scroll_step
3640 description: Same as left_sidebar_scroll_step, but for the right sidebar
3641 - name: osd_sidebar_height
3642 field: sidebar_height
3646 description: Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
3647 - name: osd_ahi_pitch_interval
3648 field: ahi_pitch_interval
3652 description: Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD)
3653 - name: osd_home_position_arm_screen
3656 description: Should home position coordinates be displayed on the arming screen.
3657 - name: osd_pan_servo_index
3658 description: Index of the pan servo, used to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos.
3659 field: pan_servo_index
3663 - name: osd_pan_servo_pwm2centideg
3664 description: Centidegrees of pan servo rotation us PWM signal. A servo with 180 degrees of rotation from 1000 to 2000 us PWM typically needs `18` for this setting. Change sign to inverse direction.
3665 field: pan_servo_pwm2centideg
3669 - name: osd_pan_servo_offcentre_warning
3670 description: Degrees either side of the pan servo centre; where it is assumed camera is wanted to be facing forwards, but isn't at 0. If in this range and not 0 for longer than 10 seconds, the pan servo offset OSD element will blink. 0 means the warning is disabled.
3671 field: pan_servo_offcentre_warning
3675 - name: osd_pan_servo_indicator_show_degrees
3676 description: Show the degress of offset from centre on the pan servo OSD display element.
3677 field: pan_servo_indicator_show_degrees
3680 - name: osd_esc_rpm_precision
3681 description: Number of characters used to display the RPM value.
3682 field: esc_rpm_precision
3686 - name: osd_mah_precision
3687 description: Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity
3688 field: mAh_precision
3692 - name: osd_use_pilot_logo
3693 description: Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511
3694 field: use_pilot_logo
3697 - name: osd_inav_to_pilot_logo_spacing
3698 description: The space between the INAV and pilot logos, if `osd_use_pilot_logo` is `ON`. This number may be adjusted so that it fits the odd/even col width displays. For example, if using an odd column width display, such as Walksnail, and this is set to 4. 1 will be added so that the logos are equally spaced from the centre of the screen.
3699 field: inav_to_pilot_logo_spacing
3703 - name: osd_arm_screen_display_time
3704 description: Amount of time to display the arm screen [ms]
3705 field: arm_screen_display_time
3709 - name: osd_switch_indicator_zero_name
3710 description: "Character to use for OSD switch incicator 0."
3711 field: osd_switch_indicator0_name
3714 default_value: "FLAP"
3715 - name: osd_switch_indicator_one_name
3716 description: "Character to use for OSD switch incicator 1."
3717 field: osd_switch_indicator1_name
3720 default_value: "GEAR"
3721 - name: osd_switch_indicator_two_name
3722 description: "Character to use for OSD switch incicator 2."
3723 field: osd_switch_indicator2_name
3726 default_value: "CAM"
3727 - name: osd_switch_indicator_three_name
3728 description: "Character to use for OSD switch incicator 3."
3729 field: osd_switch_indicator3_name
3732 default_value: "LIGT"
3733 - name: osd_switch_indicator_zero_channel
3734 description: "RC Channel to use for OSD switch indicator 0."
3735 field: osd_switch_indicator0_channel
3737 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3739 - name: osd_switch_indicator_one_channel
3740 description: "RC Channel to use for OSD switch indicator 1."
3741 field: osd_switch_indicator1_channel
3743 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3745 - name: osd_switch_indicator_two_channel
3746 description: "RC Channel to use for OSD switch indicator 2."
3747 field: osd_switch_indicator2_channel
3749 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3751 - name: osd_switch_indicator_three_channel
3752 description: "RC Channel to use for OSD switch indicator 3."
3753 field: osd_switch_indicator3_channel
3755 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3757 - name: osd_switch_indicators_align_left
3758 description: "Align text to left of switch indicators"
3759 field: osd_switch_indicators_align_left
3762 - name: osd_system_msg_display_time
3763 description: System message display cycle time for multiple messages (milliseconds).
3764 field: system_msg_display_time
3768 - name: osd_highlight_djis_missing_font_symbols
3769 description: Show question marks where there is no symbol in the DJI font to represent the INAV OSD element's symbol. When off, blank spaces will be used. Only relevent for DJICOMPAT modes.
3770 field: highlight_djis_missing_characters
3773 - name: PG_OSD_COMMON_CONFIG
3774 type: osdCommonConfig_t
3775 headers: ["io/osd_common.h"]
3776 condition: USE_OSD || USE_DJI_HD_OSD
3778 - name: osd_speed_source
3779 description: "Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR"
3780 default_value: "GROUND"
3782 table: osdSpeedSource
3785 - name: PG_SYSTEM_CONFIG
3786 type: systemConfig_t
3787 headers: ["fc/config.h"]
3790 description: "This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate)"
3791 default_value: "400KHZ"
3795 description: "Defines debug values exposed in debug variables (developer / debugging setting)"
3796 default_value: "NONE"
3798 - name: ground_test_mode
3799 description: "For developer ground test use. Disables motors, sets heading status = Trusted on FW."
3800 condition: USE_DEV_TOOLS
3802 field: groundTestMode
3804 - name: throttle_tilt_comp_str
3805 description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
3807 field: throttle_tilt_compensation_strength
3811 description: "Craft name"
3815 max: MAX_NAME_LENGTH
3817 description: "Pilot name"
3821 max: MAX_NAME_LENGTH
3823 - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
3824 type: modeActivationOperatorConfig_t
3825 headers: ["fc/rc_modes.h"]
3827 - name: mode_range_logic_operator
3828 description: "Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode."
3830 field: modeActivationOperator
3834 - name: PG_STATS_CONFIG
3836 headers: ["fc/stats.h"]
3837 condition: USE_STATS
3840 description: "General switch of the statistics recording feature (a.k.a. odometer)"
3842 field: stats_enabled
3844 - name: stats_total_time
3845 description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
3848 - name: stats_total_dist
3849 description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
3852 - name: stats_total_energy
3853 description: "Total energy consumption [in mWh]. The value is updated on every disarm when \"stats\" are enabled."
3858 - name: PG_TIME_CONFIG
3860 headers: ["common/time.h"]
3863 description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
3867 - name: tz_automatic_dst
3868 description: "Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`."
3869 default_value: "OFF"
3871 table: tz_automatic_dst
3873 - name: PG_DISPLAY_CONFIG
3874 type: displayConfig_t
3875 headers: ["drivers/display.h"]
3877 - name: display_force_sw_blink
3878 description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
3880 field: force_sw_blink
3883 - name: PG_VTX_CONFIG
3885 headers: ["io/vtx_control.h"]
3886 condition: USE_VTX_CONTROL
3888 - name: vtx_halfduplex
3889 description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
3893 - name: vtx_smartaudio_early_akk_workaround
3894 description: "Enable workaround for early AKK SAudio-enabled VTX bug."
3896 field: smartAudioEarlyAkkWorkaroundEnable
3898 - name: vtx_smartaudio_alternate_softserial_method
3899 description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier."
3901 field: smartAudioAltSoftSerialMethod
3903 - name: vtx_softserial_shortstop
3904 description: "Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes."
3906 field: softSerialShortStop
3908 - name: vtx_smartaudio_stopbits
3909 description: "Set stopbit count for serial (TBS Sixty9 SmartAudio 2.1 require value of 1 bit)"
3911 field: smartAudioStopBits
3915 - name: PG_VTX_SETTINGS_CONFIG
3916 type: vtxSettingsConfig_t
3917 headers: ["drivers/vtx_common.h", "io/vtx.h"]
3918 condition: USE_VTX_SMARTAUDIO || USE_VTX_TRAMP
3921 description: "Configure the VTX band. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
3924 min: VTX_SETTINGS_MIN_BAND
3925 max: VTX_SETTINGS_MAX_BAND
3927 description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
3930 min: VTX_SETTINGS_MIN_CHANNEL
3931 max: VTX_SETTINGS_MAX_CHANNEL
3933 description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
3936 min: VTX_SETTINGS_MIN_POWER
3937 max: VTX_SETTINGS_MAX_POWER
3938 - name: vtx_low_power_disarm
3939 description: "When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled."
3940 default_value: "OFF"
3941 field: lowPowerDisarm
3942 table: vtx_low_power_disarm
3944 - name: vtx_pit_mode_chan
3945 description: "Pit mode channel."
3947 min: VTX_SETTINGS_MIN_CHANNEL
3948 max: VTX_SETTINGS_MAX_CHANNEL
3950 - name: vtx_max_power_override
3951 description: "Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as its capabilities"
3953 field: maxPowerOverride
3956 - name: vtx_frequency_group
3957 field: frequencyGroup
3958 description: "VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz."
3959 table: vtx_frequency_groups
3962 default_value: FREQUENCYGROUP_5G8
3964 - name: PG_PINIOBOX_CONFIG
3965 type: pinioBoxConfig_t
3966 headers: ["io/piniobox.h"]
3967 condition: USE_PINIOBOX
3970 field: permanentId[0]
3971 description: "Mode assignment for PINIO#1"
3972 default_value: "target specific"
3975 default_value: :BOX_PERMANENT_ID_NONE
3978 field: permanentId[1]
3979 default_value: "target specific"
3980 description: "Mode assignment for PINIO#1"
3983 default_value: :BOX_PERMANENT_ID_NONE
3986 field: permanentId[2]
3987 default_value: "target specific"
3988 description: "Mode assignment for PINIO#1"
3991 default_value: :BOX_PERMANENT_ID_NONE
3994 field: permanentId[3]
3995 default_value: "target specific"
3996 description: "Mode assignment for PINIO#1"
3999 default_value: :BOX_PERMANENT_ID_NONE
4002 - name: PG_LOG_CONFIG
4004 headers: ["common/log.h"]
4010 description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
4011 default_value: "ERROR"
4016 description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
4019 - name: PG_ESC_SENSOR_CONFIG
4020 type: escSensorConfig_t
4021 headers: ["sensors/esc_sensor.h"]
4022 condition: USE_ESC_SENSOR
4024 - name: esc_sensor_listen_only
4026 description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
4031 - name: PG_SMARTPORT_MASTER_CONFIG
4032 type: smartportMasterConfig_t
4033 headers: ["io/smartport_master.h"]
4034 condition: USE_SMARTPORT_MASTER
4036 - name: smartport_master_halfduplex
4040 - name: smartport_master_inverted
4045 - name: PG_DJI_OSD_CONFIG
4046 type: djiOsdConfig_t
4047 headers: ["io/osd_dji_hd.h"]
4048 condition: USE_DJI_HD_OSD
4050 - name: dji_use_name_for_messages
4051 description: "Re-purpose the craft name field for messages."
4053 field: use_name_for_messages
4055 - name: dji_esc_temp_source
4056 description: "Re-purpose the ESC temperature field for IMU/BARO temperature"
4057 default_value: "ESC"
4058 field: esc_temperature_source
4059 table: djiOsdTempSource
4061 - name: dji_message_speed_source
4062 description: "Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR"
4064 field: messageSpeedSource
4065 table: osdSpeedSource
4067 - name: dji_rssi_source
4068 description: "Source of the DJI RSSI field: RSSI, CRSF_LQ"
4069 default_value: "RSSI"
4071 table: djiRssiSource
4073 - name: dji_use_adjustments
4074 description: "Show inflight adjustments in craft name field"
4077 field: useAdjustments
4078 - name: dji_cn_alternating_duration
4079 description: "Alternating duration of craft name elements, in tenths of a second"
4083 field: craftNameAlternatingDuration
4086 - name: PG_BEEPER_CONFIG
4087 type: beeperConfig_t
4088 headers: [ "fc/config.h" ]
4090 - name: dshot_beeper_enabled
4091 description: "Whether using DShot motors as beepers is enabled"
4093 field: dshot_beeper_enabled
4095 - name: dshot_beeper_tone
4096 description: "Sets the DShot beeper tone"
4100 field: dshot_beeper_tone
4102 - name: beeper_pwm_mode
4106 description: "Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode"
4108 - name: PG_POWER_LIMITS_CONFIG
4109 type: powerLimitsConfig_t
4110 headers: ["flight/power_limits.h"]
4111 condition: USE_POWER_LIMITS
4114 description: "Throttle attenuation PI control P term"
4119 description: "Throttle attenuation PI control I term"
4123 - name: limit_attn_filter_cutoff
4124 description: "Throttle attenuation PI control output filter cutoff frequency"
4126 field: attnFilterCutoff
4129 - name: PG_LEDPIN_CONFIG
4130 type: ledPinConfig_t
4131 headers: ["drivers/light_ws2811strip.h"]
4133 - name: led_pin_pwm_mode
4134 condition: USE_LED_STRIP
4135 description: "PWM mode of LED pin."
4136 default_value: "SHARED_LOW"
4137 field: led_pin_pwm_mode
4138 table: led_pin_pwm_mode
4140 - name: PG_OSD_JOYSTICK_CONFIG
4141 type: osdJoystickConfig_t
4142 headers: ["io/osd_joystick.h"]
4143 condition: USE_RCDEVICE && USE_LED_STRIP
4145 - name: osd_joystick_enabled
4146 description: "Enable OSD Joystick emulation"
4148 field: osd_joystick_enabled
4150 - name: osd_joystick_down
4151 description: "PWM value for DOWN key"
4153 field: osd_joystick_down
4156 - name: osd_joystick_up
4157 description: "PWM value for UP key"
4159 field: osd_joystick_up
4162 - name: osd_joystick_left
4163 description: "PWM value for LEFT key"
4165 field: osd_joystick_left
4168 - name: osd_joystick_right
4169 description: "PWM value for RIGHT key"
4171 field: osd_joystick_right
4174 - name: osd_joystick_enter
4175 description: "PWM value for ENTER key"
4177 field: osd_joystick_enter
4181 - name: PG_FW_AUTOLAND_CONFIG
4182 type: navFwAutolandConfig_t
4183 headers: ["navigation/navigation.h"]
4184 condition: USE_FW_AUTOLAND
4186 - name: nav_fw_land_approach_length
4187 description: "Length of the final approach"
4188 default_value: 35000
4189 field: approachLength
4192 - name: nav_fw_land_final_approach_pitch2throttle_mod
4193 description: "Modifier for pitch to throttle ratio at final approach. In Percent."
4195 field: finalApproachPitchToThrottleMod
4198 - name: nav_fw_land_glide_alt
4199 description: "Initial altitude of the glide phase"
4201 field: glideAltitude
4204 - name: nav_fw_land_flare_alt
4205 description: "Initial altitude of the flare phase"
4207 field: flareAltitude
4210 - name: nav_fw_land_glide_pitch
4211 description: "Pitch value for glide phase. In degrees."
4216 - name: nav_fw_land_flare_pitch
4217 description: "Pitch value for flare phase. In degrees"
4222 - name: nav_fw_land_max_tailwind
4223 description: "Max. tailwind (in cm/s) if no landing direction with downwind is available"
4228 - name: PG_GIMBAL_CONFIG
4229 type: gimbalConfig_t
4230 headers: ["drivers/gimbal_common.h"]
4231 condition: USE_SERIAL_GIMBAL
4233 - name: gimbal_pan_channel
4234 description: "Gimbal pan rc channel index. 0 is no channel."
4239 - name: gimbal_roll_channel
4240 description: "Gimbal roll rc channel index. 0 is no channel."
4245 - name: gimbal_tilt_channel
4246 description: "Gimbal tilt rc channel index. 0 is no channel."
4251 - name: gimbal_sensitivity
4252 description: "Gimbal sensitivity is similar to gain and will affect how quickly the gimbal will react."
4257 - name: gimbal_pan_trim
4259 description: "Trim gimbal pan center position."
4263 - name: gimbal_tilt_trim
4265 description: "Trim gimbal tilt center position."
4269 - name: gimbal_roll_trim
4271 description: "Trim gimbal roll center position."
4275 - name: PG_GIMBAL_SERIAL_CONFIG
4276 type: gimbalSerialConfig_t
4277 headers: ["io/gimbal_serial.h"]
4278 condition: USE_SERIAL_GIMBAL
4280 - name: gimbal_serial_single_uart
4281 description: "Gimbal serial and headtracker device share same UART. FC RX goes to headtracker device, FC TX goes to gimbal."
4285 - name: PG_HEADTRACKER_CONFIG
4286 type: headTrackerConfig_t
4287 headers: ["drivers/headtracker_common.h"]
4288 condition: USE_HEADTRACKER
4290 - name: headtracker_type
4291 description: "Type of headtrackr dervice"
4292 default_value: "NONE"
4295 table: headtracker_dev_type
4296 - name: headtracker_pan_ratio
4297 description: "Head pan movement vs camera movement ratio"
4303 - name: headtracker_tilt_ratio
4304 description: "Head tilt movement vs camera movement ratio"
4310 - name: headtracker_roll_ratio
4311 description: "Head roll movement vs camera movement ratio"