EZ-Tune Filter-HZ min value 20
[inav.git] / src / main / fc / settings.yaml
blob6e5d78deb1a1f5698d704a7e1e56a012f923a04a
1 tables:
2   - name: alignment
3     values: ["DEFAULT", "CW0", "CW90", "CW180", "CW270", "CW0FLIP", "CW90FLIP", "CW180FLIP", "CW270FLIP"]
4   - name: acc_hardware
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
10   - name: mag_hardware
11     values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"]
12     enum: magSensor_e
13   - name: opflow_hardware
14     values: ["NONE", "CXOF", "MSP", "FAKE"]
15     enum: opticalFlowSensor_e
16   - name: baro_hardware
17     values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "B2SMPB", "MSP", "FAKE"]
18     enum: baroSensor_e
19   - name: pitot_hardware
20     values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP", "DLVR-L10D"]
21     enum: pitotSensor_e
22   - name: receiver_type
23     values: ["NONE", "SERIAL", "MSP", "SIM (SITL)"]
24     enum: rxReceiverType_e
25   - name: serial_rx
26     values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK", "FBUS", "SBUS2"]
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"]
37     enum: currentSensor_e
38   - name: voltage_sensor
39     values: ["NONE", "ADC", "ESC", "FAKE"]
40     enum: voltageSensor_e
41   - name: imu_inertia_comp_method
42     values: ["VELNED", "TURNRATE","ADAPTIVE"]
43     enum: imu_inertia_comp_method_e
44   - name: gps_provider
45     values: ["UBLOX", "MSP", "FAKE"]
46     enum: gpsProvider_e
47   - name: gps_sbas_mode
48     values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "SPAN", "NONE"]
49     enum: sbasMode_e
50   - name: gps_dyn_model
51     values: ["PEDESTRIAN","AUTOMOTIVE", "AIR_1G", "AIR_2G", "AIR_4G", "SEA", "MOWER"]
52     enum: gpsDynModel_e
53   - name: reset_type
54     values: ["NEVER", "FIRST_ARM", "EACH_ARM"]
55   - name: direction
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"]
63   - name: osd_unit
64     values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK", "GA"]
65     enum: osd_unit_e
66   - name: osd_stats_energy_unit
67     values: ["MAH", "WH"]
68     enum: osd_stats_energy_unit_e
69   - name: osd_video_system
70     values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT", "BFHDCOMPAT"]
71     enum: videoSystem_e
72   - name: osd_telemetry
73     values: ["OFF", "ON","TEST"]
74     enum: osd_telemetry_e
75   - name: osd_alignment
76     values: ["LEFT", "RIGHT"]
77     enum: osd_alignment_e
78   - name: ltm_rates
79     values: ["NORMAL", "MEDIUM", "SLOW"]
80   - name: i2c_speed
81     values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"]
82   - name: debug_modes
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", "SBUS2"]
88   - name: aux_operator
89     values: ["OR", "AND"]
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
120   - name: filter_type
121     values: ["PT1", "BIQUAD"]
122   - name: filter_type_full
123     values: ["PT1", "BIQUAD", "PT2", "PT3", "LULU"]
124   - name: log_level
125     values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"]
126   - name: iterm_relax
127     values: ["OFF", "RP", "RPY"]
128     enum: itermRelax_e
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
134   - name: rssi_source
135     values: ["NONE", "AUTO", "ADC", "CHANNEL", "PROTOCOL", "MSP"]
136     enum: rssiSource_e
137   - name: pidTypeTable
138     values: ["NONE", "PID", "PIFF", "AUTO"]
139     enum: pidType_e
140   - name: osd_ahi_style
141     values: ["DEFAULT", "LINE"]
142     enum: osd_ahi_style_e
143   - name: tristate
144     enum: tristate_e
145     values: ["AUTO", "ON", "OFF"]
146   - name: osd_crsf_lq_format
147     enum: osd_crsf_lq_format_e
148     values: ["TYPE1", "TYPE2", "TYPE3"]
149   - name: off_on
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
181     values: ["2D", "3D"]
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']
188     enum: gpsBaudRate_e
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
201   - name: mavlink_radio_type
202     values: ["GENERIC", "ELRS", "SIK"]
203     enum: mavlinkRadio_e
204   - name: default_altitude_source
205     values: ["GPS", "BARO", "GPS_ONLY", "BARO_ONLY"]
206     enum: navDefaultAltitudeSensor_e
208 constants:
209   RPYL_PID_MIN: 0
210   RPYL_PID_MAX: 255
212   MANUAL_RATE_MIN: 0
213   MANUAL_RATE_MAX: 100
215   ROLL_PITCH_RATE_MIN: 4
216   ROLL_PITCH_RATE_MAX: 180
218   MAX_CONTROL_RATE_PROFILE_COUNT: 3
219   MAX_BATTERY_PROFILE_COUNT: 3
222 groups:
223   - name: PG_GYRO_CONFIG
224     type: gyroConfig_t
225     headers: ["sensors/gyro.h"]
226     members:
227       - name: looptime
228         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."
229         default_value: 500
230         max: 9000
231       - name: gyro_anti_aliasing_lpf_hz
232         description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz"
233         default_value: 250
234         field: gyro_anti_aliasing_lpf_hz
235         max: 1000
236       - name: gyro_lulu_enabled
237         description: "Enable/disable gyro LULU filter"
238         default_value: OFF
239         field: gyroLuluEnabled
240         type: bool
241       - name: gyro_lulu_sample_count
242         description: "Gyro lulu sample count, in number of samples."
243         default_value: 3
244         field: gyroLuluSampleCount
245         min: 1
246         max: 15
247       - name: gyro_main_lpf_hz
248         description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)"
249         default_value: 60
250         field: gyro_main_lpf_hz
251         min: 0
252         max: 500
253       - name: gyro_filter_mode
254         description: "Specifies the type of the software LPF of the gyro signals."
255         default_value: "STATIC"
256         field: gyroFilterMode
257         table: gyro_filter_mode
258       - name: gyro_dyn_lpf_min_hz
259         description: "Minimum frequency of the gyro Dynamic LPF"
260         default_value: 200
261         field: gyroDynamicLpfMinHz
262         min: 40
263         max: 400
264       - name: gyro_dyn_lpf_max_hz
265         description: "Maximum frequency of the gyro Dynamic LPF"
266         default_value: 500
267         field: gyroDynamicLpfMaxHz
268         min: 40
269         max: 1000
270       - name: gyro_dyn_lpf_curve_expo
271         description: "Expo value for the throttle-to-frequency mapping for Dynamic LPF"
272         default_value: 5
273         field: gyroDynamicLpfCurveExpo
274         min: 1
275         max: 10
276       - name: dynamic_gyro_notch_enabled
277         description: "Enable/disable dynamic gyro notch also known as Matrix Filter"
278         default_value: ON
279         field: dynamicGyroNotchEnabled
280         condition: USE_DYNAMIC_FILTERS
281         type: bool
282       - name: dynamic_gyro_notch_q
283         description: "Q factor for dynamic notches"
284         default_value: 120
285         field: dynamicGyroNotchQ
286         condition: USE_DYNAMIC_FILTERS
287         min: 1
288         max: 1000
289       - name: dynamic_gyro_notch_min_hz
290         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`"
291         default_value: 50
292         field: dynamicGyroNotchMinHz
293         condition: USE_DYNAMIC_FILTERS
294         min: 30
295         max: 250
296       - name: dynamic_gyro_notch_mode
297         description: "Gyro dynamic notch type"
298         default_value: "2D"
299         table: dynamic_gyro_notch_mode
300         field: dynamicGyroNotchMode
301         condition: USE_DYNAMIC_FILTERS
302       - name: dynamic_gyro_notch_3d_q
303         description: "Q factor for 3D dynamic notches"
304         default_value: 200
305         field: dynamicGyroNotch3dQ
306         condition: USE_DYNAMIC_FILTERS
307         min: 1
308         max: 1000
309       - name: gyro_to_use
310         description: "On multi-gyro targets, allows to choose which gyro to use. 0 = first gyro, 1 = second gyro"
311         condition: USE_DUAL_GYRO
312         min: 0
313         max: 2
314         default_value: 0
315       - name: setpoint_kalman_enabled
316         description: "Enable Kalman filter on the gyro data"
317         default_value: ON
318         condition: USE_GYRO_KALMAN
319         field: kalmanEnabled
320         type: bool
321       - name: setpoint_kalman_q
322         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"
323         default_value: 100
324         field: kalman_q
325         condition: USE_GYRO_KALMAN
326         min: 1
327         max: 1000
328       - name: init_gyro_cal
329         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."
330         default_value: ON
331         field: init_gyro_cal_enabled
332         type: bool
333       - name: gyro_zero_x
334         description: "Calculated gyro zero calibration of axis X"
335         default_value: 0
336         field: gyro_zero_cal[X]
337         min: INT16_MIN
338         max: INT16_MAX
339       - name: gyro_zero_y
340         description: "Calculated gyro zero calibration of axis Y"
341         default_value: 0
342         field: gyro_zero_cal[Y]
343         min: INT16_MIN
344         max: INT16_MAX
345       - name: gyro_zero_z
346         description: "Calculated gyro zero calibration of axis Z"
347         default_value: 0
348         field: gyro_zero_cal[Z]
349         min: INT16_MIN
350         max: INT16_MAX
351       - name: ins_gravity_cmss
352         description: "Calculated 1G of Acc axis Z to use in INS"
353         default_value: 0.0
354         field: gravity_cmss_cal
355         min: 0
356         max: 2000
357       - name: gyro_adaptive_filter_target
358         description: "Target value for adaptive filter"
359         default_value: 3.5
360         field: adaptiveFilterTarget
361         min: 1
362         max: 6
363         condition: USE_ADAPTIVE_FILTER
364       - name: gyro_adaptive_filter_min_hz
365         description: "Minimum frequency for adaptive filter"
366         default_value: 50
367         field: adaptiveFilterMinHz
368         min: 0
369         max: 250
370         condition: USE_ADAPTIVE_FILTER
371       - name: gyro_adaptive_filter_max_hz
372         description: "Maximum frequency for adaptive filter"
373         default_value: 150
374         field: adaptiveFilterMaxHz
375         min: 0
376         max: 505
377         condition: USE_ADAPTIVE_FILTER
378       - name: gyro_adaptive_filter_std_lpf_hz
379         description: "Standard deviation low pass filter cutoff frequency"
380         default_value: 2
381         field: adaptiveFilterStdLpfHz
382         min: 0
383         max: 10
384         condition: USE_ADAPTIVE_FILTER
385       - name: gyro_adaptive_filter_hpf_hz
386         description: "High pass filter cutoff frequency"
387         default_value: 10
388         field: adaptiveFilterHpfHz
389         min: 1
390         max: 50
391         condition: USE_ADAPTIVE_FILTER
392       - name: gyro_adaptive_filter_integrator_threshold_high
393         description: "High threshold for adaptive filter integrator"
394         default_value: 4
395         field: adaptiveFilterIntegratorThresholdHigh
396         min: 1
397         max: 10
398         condition: USE_ADAPTIVE_FILTER
399       - name: gyro_adaptive_filter_integrator_threshold_low
400         description: "Low threshold for adaptive filter integrator"
401         default_value: -2
402         field: adaptiveFilterIntegratorThresholdLow
403         min: -10
404         max: 0
405         condition: USE_ADAPTIVE_FILTER
407   - name: PG_ADC_CHANNEL_CONFIG
408     type: adcChannelConfig_t
409     headers: ["fc/config.h"]
410     condition: USE_ADC
411     members:
412       - name: vbat_adc_channel
413         description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled"
414         default_value: :target
415         field: adcFunctionChannel[ADC_BATTERY]
416         min: ADC_CHN_NONE
417         max: ADC_CHN_MAX
418       - name: rssi_adc_channel
419         description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled"
420         default_value: :target
421         field: adcFunctionChannel[ADC_RSSI]
422         min: ADC_CHN_NONE
423         max: ADC_CHN_MAX
424       - name: current_adc_channel
425         description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled"
426         default_value: :target
427         field: adcFunctionChannel[ADC_CURRENT]
428         min: ADC_CHN_NONE
429         max: ADC_CHN_MAX
430       - name: airspeed_adc_channel
431         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"
432         default_value: :target
433         field: adcFunctionChannel[ADC_AIRSPEED]
434         min: ADC_CHN_NONE
435         max: ADC_CHN_MAX
437   - name: PG_ACCELEROMETER_CONFIG
438     type: accelerometerConfig_t
439     headers: ["sensors/acceleration.h"]
440     members:
441       - name: acc_notch_hz
442         description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is center frequency (Hz)"
443         min: 0
444         max: 255
445         default_value: 0
446       - name: acc_notch_cutoff
447         description: "Frequency of the software notch filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz)"
448         min: 1
449         max: 255
450         default_value: 1
451       - name: acc_hardware
452         description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
453         default_value: "AUTO"
454         table: acc_hardware
455       - name: acc_lpf_hz
456         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."
457         default_value: 15
458         min: 0
459         max: 200
460       - name: acc_lpf_type
461         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."
462         default_value: "BIQUAD"
463         field: acc_soft_lpf_type
464         table: filter_type
465       - name: acczero_x
466         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
467         default_value: 0
468         field: accZero.raw[X]
469         min: INT16_MIN
470         max: INT16_MAX
471       - name: acczero_y
472         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
473         default_value: 0
474         field: accZero.raw[Y]
475         min: INT16_MIN
476         max: INT16_MAX
477       - name: acczero_z
478         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
479         default_value: 0
480         field: accZero.raw[Z]
481         min: INT16_MIN
482         max: INT16_MAX
483       - name: accgain_x
484         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
485         default_value: 4096
486         field: accGain.raw[X]
487         min: 1
488         max: 8192
489       - name: accgain_y
490         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
491         default_value: 4096
492         field: accGain.raw[Y]
493         min: 1
494         max: 8192
495       - name: accgain_z
496         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
497         default_value: 4096
498         field: accGain.raw[Z]
499         min: 1
500         max: 8192
502   - name: PG_RANGEFINDER_CONFIG
503     type: rangefinderConfig_t
504     headers: ["sensors/rangefinder.h"]
505     condition: USE_RANGEFINDER
506     members:
507       - name: rangefinder_hardware
508         table: rangefinder_hardware
509         description: "Selection of rangefinder hardware."
510         default_value: "NONE"
511       - name: rangefinder_median_filter
512         description: "3-point median filtering for rangefinder readouts"
513         default_value: OFF
514         field: use_median_filtering
515         type: bool
517   - name: PG_OPFLOW_CONFIG
518     type: opticalFlowConfig_t
519     headers: ["sensors/opflow.h"]
520     condition: USE_OPFLOW
521     members:
522       - name: opflow_hardware
523         description: "Selection of OPFLOW hardware."
524         default_value: NONE
525         table: opflow_hardware
526       - name: opflow_scale
527         description: "Optical flow module scale factor"
528         min: 0
529         max: 10000
530         default_value: 10.5
531       - name: align_opflow
532         description: "Optical flow module alignment (default CW0_DEG_FLIP)"
533         default_value: CW0FLIP
534         field: opflow_align
535         type: uint8_t
536         table: alignment
538   - name: PG_COMPASS_CONFIG
539     type: compassConfig_t
540     headers: ["sensors/compass.h"]
541     condition: USE_MAG
542     members:
543       - name: align_mag
544         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."
545         default_value: "DEFAULT"
546         field: mag_align
547         type: uint8_t
548         table: alignment
549       - name: mag_hardware
550         description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
551         default_value: "AUTO"
552         table: mag_hardware
553       - name: mag_declination
554         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."
555         default_value: 0
556         min: -18000
557         max: 18000
558       - name: magzero_x
559         description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed."
560         default_value: :zero
561         field: magZero.raw[X]
562         min: INT16_MIN
563         max: INT16_MAX
564       - name: magzero_y
565         description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed."
566         default_value: :zero
567         field: magZero.raw[Y]
568         min: INT16_MIN
569         max: INT16_MAX
570       - name: magzero_z
571         description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed."
572         default_value: :zero
573         field: magZero.raw[Z]
574         min: INT16_MIN
575         max: INT16_MAX
576       - name: maggain_x
577         description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed"
578         default_value: 1024
579         field: magGain[X]
580         min: INT16_MIN
581         max: INT16_MAX
582       - name: maggain_y
583         description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed"
584         default_value: 1024
585         field: magGain[Y]
586         min: INT16_MIN
587         max: INT16_MAX
588       - name: maggain_z
589         description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed"
590         default_value: 1024
591         field: magGain[Z]
592         min: INT16_MIN
593         max: INT16_MAX
594       - name: mag_calibration_time
595         description: "Adjust how long time the Calibration of mag will last."
596         default_value: 30
597         field: magCalibrationTimeLimit
598         min: 20
599         max: 120
600       - name: mag_to_use
601         description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target"
602         condition: USE_DUAL_MAG
603         min: 0
604         max: 1
605         default_value: 0
606       - name: align_mag_roll
607         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."
608         default_value: 0
609         field: rollDeciDegrees
610         min: -1800
611         max: 3600
612       - name: align_mag_pitch
613         description: "Same as align_mag_roll, but for the pitch axis."
614         default_value: 0
615         field: pitchDeciDegrees
616         min: -1800
617         max: 3600
618       - name: align_mag_yaw
619         description: "Same as align_mag_roll, but for the yaw axis."
620         default_value: 0
621         field: yawDeciDegrees
622         min: -1800
623         max: 3600
625   - name: PG_BAROMETER_CONFIG
626     type: barometerConfig_t
627     headers: ["sensors/barometer.h"]
628     condition: USE_BARO
629     members:
630       - name: baro_hardware
631         description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
632         default_value: "AUTO"
633         table: baro_hardware
634       - name: baro_cal_tolerance
635         description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]."
636         default_value: 150
637         field: baro_calibration_tolerance
638         min: 0
639         max: 1000
641   - name: PG_PITOTMETER_CONFIG
642     type: pitotmeterConfig_t
643     headers: ["sensors/pitotmeter.h"]
644     condition: USE_PITOT
645     members:
646       - name: pitot_hardware
647         description: "Selection of pitot hardware."
648         default_value: "NONE"
649         table: pitot_hardware
650       - name: pitot_lpf_milli_hz
651         description: "Pitot tube lowpass filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay"
652         min: 0
653         max: 10000
654         default_value: 350
655       - name: pitot_scale
656         description: "Pitot tube scale factor"
657         min: 0
658         max: 100
659         default_value: 1.0
661   - name: PG_RX_CONFIG
662     type: rxConfig_t
663     headers: ["rx/rx.h", "rx/spektrum.h"]
664     members:
665       - name: receiver_type
666         description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`"
667         default_value: :target
668         field: receiverType
669         table: receiver_type
670       - name: min_check
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."
672         default_value: 1100
673         field: mincheck
674         min: PWM_RANGE_MIN
675         max: PWM_RANGE_MAX
676       - name: max_check
677         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."
678         default_value: 1900
679         field: maxcheck
680         min: PWM_RANGE_MIN
681         max: PWM_RANGE_MAX
682       - name: rssi_source
683         description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`"
684         default_value: "AUTO"
685         field: rssi_source
686         table: rssi_source
687       - name: rssi_channel
688         description: "RX channel containing the RSSI signal"
689         default_value: 0
690         min: 0
691         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
692       - name: rssi_min
693         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)."
694         default_value: 0
695         field: rssiMin
696         min: RSSI_VISIBLE_VALUE_MIN
697         max: RSSI_VISIBLE_VALUE_MAX
698       - name: rssi_max
699         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."
700         default_value: 100
701         field: rssiMax
702         min: RSSI_VISIBLE_VALUE_MIN
703         max: RSSI_VISIBLE_VALUE_MAX
704       - name: sbus_sync_interval
705         field: sbusSyncInterval
706         description: "SBUS sync interval in us. Default value is 3000us. Lower values may cause issues with some receivers."
707         min: 500
708         max: 10000
709         default_value: 3000
710       - name: rc_filter_lpf_hz
711         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"
712         default_value: 50
713         field: rcFilterFrequency
714         min: 15
715         max: 250
716       - name: rc_filter_auto
717         description: "When enabled, INAV will set RC filtering based on refresh rate and smoothing factor."
718         type: bool
719         default_value: ON
720         field: autoSmooth
721       - name: rc_filter_smoothing_factor
722         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"
723         field: autoSmoothFactor
724         default_value: 30
725         min: 1
726         max: 100
727       - name: serialrx_provider
728         description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section."
729         default_value: :target
730         condition: USE_SERIAL_RX
731         table: serial_rx
732       - name: serialrx_inverted
733         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)."
734         default_value: OFF
735         condition: USE_SERIAL_RX
736         type: bool
737       - name: spektrum_sat_bind
738         description: "0 = disabled. Used to bind the spektrum satellite to RX"
739         condition: USE_SPEKTRUM_BIND
740         min: SPEKTRUM_SAT_BIND_DISABLED
741         max: SPEKTRUM_SAT_BIND_MAX
742         default_value: :SPEKTRUM_SAT_BIND_DISABLED
743       - name: srxl2_unit_id
744         condition: USE_SERIALRX_SRXL2
745         min: 0
746         max: 15
747         default_value: 1
748       - name: srxl2_baud_fast
749         condition: USE_SERIALRX_SRXL2
750         type: bool
751         default_value: ON
752       - name: rx_min_usec
753         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."
754         default_value: 885
755         min: PWM_PULSE_MIN
756         max: PWM_PULSE_MAX
757       - name: rx_max_usec
758         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."
759         default_value: 2115
760         min: PWM_PULSE_MIN
761         max: PWM_PULSE_MAX
762       - name: serialrx_halfduplex
763         description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire."
764         default_value: "AUTO"
765         field: halfDuplex
766         table: tristate
767       - name: msp_override_channels
768         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."
769         default_value: 0
770         field: mspOverrideChannels
771         condition: USE_MSP_RC_OVERRIDE
772         min: 0
773         max: 65535
775   - name: PG_BLACKBOX_CONFIG
776     type: blackboxConfig_t
777     headers: ["blackbox/blackbox.h"]
778     condition: USE_BLACKBOX
779     members:
780       - name: blackbox_rate_num
781         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"
782         default_value: 1
783         field: rate_num
784         min: 1
785         max: 65535
786       - name: blackbox_rate_denom
787         description: "Blackbox logging rate denominator. See blackbox_rate_num."
788         default_value: 1
789         field: rate_denom
790         min: 1
791         max: 65535
792       - name: blackbox_device
793         description: "Selection of where to write blackbox data"
794         default_value: :target
795         field: device
796         table: blackbox_device
797       - name: sdcard_detect_inverted
798         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."
799         default_value: :target
800         field: invertedCardDetection
801         condition: USE_SDCARD
802         type: bool
804   - name: PG_MOTOR_CONFIG
805     type: motorConfig_t
806     headers: ["flight/mixer.h"]
807     members:
808       - name: min_command
809         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."
810         default_value: 1000
811         field: mincommand
812         min: 0
813         max: PWM_RANGE_MAX
814       - name: motor_pwm_rate
815         description: "Output frequency (in Hz) for motor pins.  Applies only to brushed motors. "
816         default_value: 16000
817         field: motorPwmRate
818         min: 50
819         max: 32000
820       - name: motor_pwm_protocol
821         description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
822         default_value: "ONESHOT125"
823         field: motorPwmProtocol
824         table: motor_pwm_protocol
825       - name: motor_poles
826         field: motorPoleCount
827         description: "The number of motor poles. Required to compute motor RPM"
828         min: 4
829         max: 255
830         default_value: 14
832   - name: PG_FAILSAFE_CONFIG
833     type: failsafeConfig_t
834     headers: ["flight/failsafe.h"]
835     members:
836       - name: failsafe_delay
837         description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)."
838         default_value: 5
839         min: 0
840         max: 200
841       - name: failsafe_recovery_delay
842         description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)."
843         default_value: 5
844         min: 0
845         max: 200
846       - name: failsafe_off_delay
847         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)."
848         default_value: 200
849         min: 0
850         max: 200
851       - name: failsafe_throttle_low_delay
852         description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout"
853         default_value: 0
854         min: 0
855         max: 300
856       - name: failsafe_procedure
857         description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
858         default_value: "LAND"
859         table: failsafe_procedure
860       - name: failsafe_stick_threshold
861         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."
862         default_value: 50
863         field: failsafe_stick_motion_threshold
864         min: 0
865         max: 500
866       - name: failsafe_fw_roll_angle
867         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"
868         default_value: -200
869         min: -800
870         max: 800
871       - name: failsafe_fw_pitch_angle
872         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"
873         default_value: 100
874         min: -800
875         max: 800
876       - name: failsafe_fw_yaw_rate
877         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"
878         default_value: -45
879         min: -1000
880         max: 1000
881       - name: failsafe_min_distance
882         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."
883         default_value: 0
884         min: 0
885         max: 65000
886       - name: failsafe_min_distance_procedure
887         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)."
888         default_value: "DROP"
889         table: failsafe_procedure
890       - name: failsafe_mission_delay
891         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."
892         default_value: 0
893         min: -1
894         max: 600
895       - name: failsafe_gps_fix_estimation_delay
896         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."
897         condition: USE_GPS_FIX_ESTIMATION
898         default_value: 7
899         min: -1
900         max: 600
902   - name: PG_LIGHTS_CONFIG
903     type: lightsConfig_t
904     headers: ["io/lights.h"]
905     condition: USE_LIGHTS
906     members:
907       - name: failsafe_lights
908         description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
909         default_value: ON
910         field: failsafe.enabled
911         type: bool
912       - name: failsafe_lights_flash_period
913         description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
914         default_value: 1000
915         field: failsafe.flash_period
916         min: 40
917         max: 65535
918       - name: failsafe_lights_flash_on_time
919         description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
920         default_value: 100
921         field: failsafe.flash_on_time
922         min: 20
923         max: 65535
925   - name: PG_BOARD_ALIGNMENT
926     type: boardAlignment_t
927     headers: ["sensors/boardalignment.h"]
928     members:
929       - name: align_board_roll
930         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
931         default_value: :zero
932         field: rollDeciDegrees
933         min: -1800
934         max: 3600
935       - name: align_board_pitch
936         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
937         default_value: :zero
938         field: pitchDeciDegrees
939         min: -1800
940         max: 3600
941       - name: align_board_yaw
942         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
943         default_value: :zero
944         field: yawDeciDegrees
945         min: -1800
946         max: 3600
948   - name: PG_BATTERY_METERS_CONFIG
949     type: batteryMetersConfig_t
950     headers: ["sensors/battery_config_structs.h"]
951     members:
952       - name: vbat_meter_type
953         description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
954         condition: USE_ADC
955         default_value: ADC
956         field: voltage.type
957         table: voltage_sensor
958         type: uint8_t
959       - name: vbat_scale
960         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."
961         default_value: :target
962         field: voltage.scale
963         condition: USE_ADC
964         min: 0
965         max: 65535
966       - name: battery_capacity_unit
967         description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)."
968         default_value: "MAH"
969         field: capacity_unit
970         table: bat_capacity_unit
971         type: uint8_t
972       - name: current_meter_scale
973         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."
974         default_value: :target
975         field: current.scale
976         min: -10000
977         max: 10000
978       - name: current_meter_offset
979         description: "This sets the output offset voltage of the current sensor in millivolts."
980         default_value: :target
981         field: current.offset
982         min: -32768
983         max: 32767
984       - name: current_meter_type
985         description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position."
986         default_value: "ADC"
987         field: current.type
988         table: current_sensor
989         type: uint8_t
990       - name: bat_voltage_src
991         description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`"
992         default_value: "RAW"
993         field: voltageSource
994         table: bat_voltage_source
995         type: uint8_t
996       - name: cruise_power
997         description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
998         default_value: 0
999         field: cruise_power
1000         min: 0
1001         max: 4294967295
1002       - name: idle_power
1003         description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
1004         default_value: 0
1005         field: idle_power
1006         min: 0
1007         max: 65535
1008       - name: rth_energy_margin
1009         description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
1010         default_value: 5
1011         min: 0
1012         max: 100
1013       - name: thr_comp_weight
1014         description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
1015         default_value: 1
1016         field: throttle_compensation_weight
1017         min: 0
1018         max: 2
1020   - name: PG_BATTERY_PROFILES
1021     type: batteryProfile_t
1022     headers: ["sensors/battery_config_structs.h"]
1023     value_type: BATTERY_CONFIG_VALUE
1024     members:
1025       - name: bat_cells
1026         description: "Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected."
1027         default_value: 0
1028         field: cells
1029         condition: USE_ADC
1030         min: 0
1031         max: 12
1032       - name: vbat_cell_detect_voltage
1033         description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units."
1034         default_value: 425
1035         field: voltage.cellDetect
1036         condition: USE_ADC
1037         min: 100
1038         max: 500
1039       - name: vbat_max_cell_voltage
1040         description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
1041         default_value: 420
1042         field: voltage.cellMax
1043         condition: USE_ADC
1044         min: 100
1045         max: 500
1046       - name: vbat_min_cell_voltage
1047         description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
1048         default_value: 330
1049         field: voltage.cellMin
1050         condition: USE_ADC
1051         min: 100
1052         max: 500
1053       - name: vbat_warning_cell_voltage
1054         description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
1055         default_value: 350
1056         field: voltage.cellWarning
1057         condition: USE_ADC
1058         min: 100
1059         max: 500
1060       - name: battery_capacity
1061         description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
1062         default_value: 0
1063         field: capacity.value
1064         min: 0
1065         max: 4294967295
1066       - name: battery_capacity_warning
1067         description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
1068         default_value: 0
1069         field: capacity.warning
1070         min: 0
1071         max: 4294967295
1072       - name: battery_capacity_critical
1073         description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
1074         default_value: 0
1075         field: capacity.critical
1076         min: 0
1077         max: 4294967295
1078       - name: controlrate_profile
1079         description: "Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile"
1080         default_value: 0
1081         field: controlRateProfile
1082         min: 0
1083         max: MAX_CONTROL_RATE_PROFILE_COUNT
1085       - name: throttle_scale
1086         description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
1087         default_value: 1.0
1088         field: motor.throttleScale
1089         min: 0
1090         max: 1
1091       - name: throttle_idle
1092         description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
1093         default_value: 8
1094         field: motor.throttleIdle
1095         min: 0
1096         max: 30
1097       - name: turtle_mode_power_factor
1098         field: motor.turtleModePowerFactor
1099         default_value: 55
1100         description: "Turtle mode power factor"
1101         condition: USE_DSHOT
1102         min: 0
1103         max: 100
1104       - name: failsafe_throttle
1105         description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
1106         default_value: 1000
1107         min: PWM_RANGE_MIN
1108         max: PWM_RANGE_MAX
1109       - name: nav_mc_hover_thr
1110         description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
1111         default_value: 1300
1112         field: nav.mc.hover_throttle
1113         min: 1000
1114         max: 2000
1115       - name: nav_fw_cruise_thr
1116         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 )"
1117         default_value: 1400
1118         field: nav.fw.cruise_throttle
1119         min: 1000
1120         max: 2000
1121       - name: nav_fw_min_thr
1122         description: "Minimum throttle for flying wing in GPS assisted modes"
1123         default_value: 1200
1124         field: nav.fw.min_throttle
1125         min: 1000
1126         max: 2000
1127       - name: nav_fw_max_thr
1128         description: "Maximum throttle for flying wing in GPS assisted modes"
1129         default_value: 1700
1130         field: nav.fw.max_throttle
1131         min: 1000
1132         max: 2000
1133       - name: nav_fw_pitch2thr
1134         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)"
1135         default_value: 10
1136         field: nav.fw.pitch_to_throttle
1137         min: 0
1138         max: 100
1139       - name: nav_fw_launch_thr
1140         description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
1141         default_value: 1700
1142         field: nav.fw.launch_throttle
1143         min: 1000
1144         max: 2000
1145       - name: nav_fw_launch_idle_thr
1146         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)"
1147         default_value: 1000
1148         field: nav.fw.launch_idle_throttle
1149         min: 1000
1150         max: 2000
1151       - name: limit_cont_current
1152         description: "Continous current limit (dA), set to 0 to disable"
1153         condition: USE_POWER_LIMITS
1154         default_value: 0
1155         field: powerLimits.continuousCurrent
1156         max: 4000
1157       - name: limit_burst_current
1158         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"
1159         condition: USE_POWER_LIMITS
1160         default_value: 0
1161         field: powerLimits.burstCurrent
1162         max: 4000
1163       - name: limit_burst_current_time
1164         description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced"
1165         condition: USE_POWER_LIMITS
1166         default_value: 0
1167         field: powerLimits.burstCurrentTime
1168         max: 3000
1169       - name: limit_burst_current_falldown_time
1170         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`"
1171         condition: USE_POWER_LIMITS
1172         default_value: 0
1173         field: powerLimits.burstCurrentFalldownTime
1174         max: 3000
1175       - name: limit_cont_power
1176         description: "Continous power limit (dW), set to 0 to disable"
1177         condition: USE_POWER_LIMITS && USE_ADC
1178         default_value: 0
1179         field: powerLimits.continuousPower
1180         max: 40000
1181       - name: limit_burst_power
1182         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"
1183         condition: USE_POWER_LIMITS && USE_ADC
1184         default_value: 0
1185         field: powerLimits.burstPower
1186         max: 40000
1187       - name: limit_burst_power_time
1188         description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced"
1189         condition: USE_POWER_LIMITS && USE_ADC
1190         default_value: 0
1191         field: powerLimits.burstPowerTime
1192         max: 3000
1193       - name: limit_burst_power_falldown_time
1194         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`"
1195         condition: USE_POWER_LIMITS && USE_ADC
1196         default_value: 0
1197         field: powerLimits.burstPowerFalldownTime
1198         max: 3000
1200   - name: PG_MIXER_PROFILE
1201     type: mixerProfile_t
1202     headers: ["flight/mixer_profile.h"]
1203     value_type: MIXER_CONFIG_VALUE
1204     members:
1205       - name: motor_direction_inverted
1206         description: "Use if you need to inverse yaw motor direction."
1207         default_value: OFF
1208         field: mixer_config.motorDirectionInverted
1209         type: bool
1210       - name: platform_type
1211         description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
1212         default_value: "MULTIROTOR"
1213         field: mixer_config.platformType
1214         type: uint8_t
1215         table: platform_type
1216       - name: has_flaps
1217         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"
1218         default_value: OFF
1219         field: mixer_config.hasFlaps
1220         type: bool
1221       - name: model_preview_type
1222         description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
1223         default_value: -1
1224         field: mixer_config.appliedMixerPreset
1225         min: -1
1226         max: INT16_MAX
1227       - name: motorstop_on_low
1228         description: "If enabled, motor will stop when throttle is low on this mixer_profile"
1229         default_value: OFF
1230         field: mixer_config.motorstopOnLow
1231         type: bool
1232       - name: mixer_pid_profile_linking
1233         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."
1234         default_value: OFF
1235         field: mixer_config.PIDProfileLinking
1236         type: bool
1237       - name: mixer_automated_switch
1238         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"
1239         default_value: OFF
1240         field: mixer_config.automated_switch
1241         type: bool
1242       - name: mixer_switch_trans_timer
1243         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."
1244         default_value: 0
1245         field: mixer_config.switchTransitionTimer
1246         min: 0
1247         max: 200
1248       - name: tailsitter_orientation_offset
1249         description: "Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode"
1250         default_value: OFF
1251         field: mixer_config.tailsitterOrientationOffset
1252         type: bool
1254   - name: PG_REVERSIBLE_MOTORS_CONFIG
1255     type: reversibleMotorsConfig_t
1256     members:
1257       - name: 3d_deadband_low
1258         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)"
1259         default_value: 1406
1260         field: deadband_low
1261         min: PWM_RANGE_MIN
1262         max: PWM_RANGE_MAX
1263       - name: 3d_deadband_high
1264         description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
1265         default_value: 1514
1266         field: deadband_high
1267         min: PWM_RANGE_MIN
1268         max: PWM_RANGE_MAX
1269       - name: 3d_neutral
1270         description: "Neutral (stop) throttle value for 3D mode"
1271         default_value: 1460
1272         field: neutral
1273         min: PWM_RANGE_MIN
1274         max: PWM_RANGE_MAX
1276   - name: PG_SERVO_CONFIG
1277     type: servoConfig_t
1278     headers: ["flight/servos.h"]
1279     members:
1280       - name: servo_protocol
1281         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)"
1282         default_value: "PWM"
1283         field: servo_protocol
1284         table: servo_protocol
1285       - name: servo_center_pulse
1286         description: "Servo midpoint"
1287         default_value: 1500
1288         field: servoCenterPulse
1289         min: PWM_RANGE_MIN
1290         max: PWM_RANGE_MAX
1291       - name: servo_pwm_rate
1292         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."
1293         default_value: 50
1294         field: servoPwmRate
1295         min: 50
1296         max: 498
1297       - name: servo_lpf_hz
1298         description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
1299         default_value: 20
1300         field: servo_lowpass_freq
1301         min: 0
1302         max: 400
1303       - name: flaperon_throw_offset
1304         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."
1305         default_value: 200
1306         min: FLAPERON_THROW_MIN
1307         max: FLAPERON_THROW_MAX
1308       - name: tri_unarmed_servo
1309         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."
1310         default_value: ON
1311         type: bool
1312       - name: servo_autotrim_rotation_limit
1313         description: "Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`."
1314         default_value: 15
1315         min: 1
1316         max: 60
1318   - name: PG_CONTROL_RATE_PROFILES
1319     type: controlRateConfig_t
1320     headers: ["fc/controlrate_profile_config_struct.h"]
1321     value_type: CONTROL_RATE_VALUE
1322     members:
1323       - name: thr_mid
1324         description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
1325         default_value: 50
1326         field: throttle.rcMid8
1327         min: 0
1328         max: 100
1329       - name: thr_expo
1330         description: "Throttle exposition value"
1331         default_value: 0
1332         field: throttle.rcExpo8
1333         min: 0
1334         max: 100
1335       - name: tpa_rate
1336         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."
1337         default_value: 0
1338         field: throttle.dynPID
1339         min: 0
1340         max: 100
1341       - name: tpa_breakpoint
1342         description: "See tpa_rate."
1343         default_value: 1500
1344         field: throttle.pa_breakpoint
1345         min: PWM_RANGE_MIN
1346         max: PWM_RANGE_MAX
1347       - name: tpa_on_yaw
1348         description: "Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors."
1349         type: bool
1350         field: throttle.dynPID_on_YAW
1351         default_value: OFF
1352       - name: fw_tpa_time_constant
1353         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."
1354         default_value: 1500
1355         field: throttle.fixedWingTauMs
1356         min: 0
1357         max: 5000
1358       - name: rc_expo
1359         description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
1360         default_value: 70
1361         field: stabilized.rcExpo8
1362         min: 0
1363         max: 100
1364       - name: rc_yaw_expo
1365         description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
1366         default_value: 20
1367         field: stabilized.rcYawExpo8
1368         min: 0
1369         max: 100
1370       # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
1371       # Rate 180 (1800dps) is max. value gyro can measure reliably
1372       - name: roll_rate
1373         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."
1374         default_value: 20
1375         field: stabilized.rates[FD_ROLL]
1376         min: ROLL_PITCH_RATE_MIN
1377         max: ROLL_PITCH_RATE_MAX
1378       - name: pitch_rate
1379         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."
1380         default_value: 20
1381         field: stabilized.rates[FD_PITCH]
1382         min: ROLL_PITCH_RATE_MIN
1383         max: ROLL_PITCH_RATE_MAX
1384       - name: yaw_rate
1385         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."
1386         default_value: 20
1387         field: stabilized.rates[FD_YAW]
1388         min: 1
1389         max: 180
1390       - name: manual_rc_expo
1391         description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
1392         default_value: 35
1393         field: manual.rcExpo8
1394         min: 0
1395         max: 100
1396       - name: manual_rc_yaw_expo
1397         description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
1398         default_value: 20
1399         field: manual.rcYawExpo8
1400         min: 0
1401         max: 100
1402       - name: manual_roll_rate
1403         description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
1404         default_value: 100
1405         field: manual.rates[FD_ROLL]
1406         min: MANUAL_RATE_MIN
1407         max: MANUAL_RATE_MAX
1408       - name: manual_pitch_rate
1409         description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
1410         default_value: 100
1411         field: manual.rates[FD_PITCH]
1412         min: MANUAL_RATE_MIN
1413         max: MANUAL_RATE_MAX
1414       - name: manual_yaw_rate
1415         description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
1416         default_value: 100
1417         field: manual.rates[FD_YAW]
1418         min: MANUAL_RATE_MIN
1419         max: MANUAL_RATE_MAX
1420       - name: fpv_mix_degrees
1421         description: "The tilt angle of the FPV camera in degrees, used by the FPV ANGLE MIX mode"
1422         field: misc.fpvCamAngleDegrees
1423         min: 0
1424         max: 50
1425         default_value: 0
1426       - name: rate_dynamics_center_sensitivity
1427         field: rateDynamics.sensitivityCenter
1428         default_value: 100
1429         min: 25
1430         max: 175
1431         description: "The center stick sensitivity for Rate Dynamics"
1432         condition: USE_RATE_DYNAMICS
1433       - name: rate_dynamics_end_sensitivity
1434         field: rateDynamics.sensitivityEnd
1435         default_value: 100
1436         min: 25
1437         max: 175
1438         description: "The end stick sensitivity for Rate Dynamics"
1439         condition: USE_RATE_DYNAMICS
1440       - name: rate_dynamics_center_correction
1441         field: rateDynamics.correctionCenter
1442         default_value: 10
1443         min: 10
1444         max: 95
1445         description: "The center stick correction for Rate Dynamics"
1446         condition: USE_RATE_DYNAMICS
1447       - name: rate_dynamics_end_correction
1448         field: rateDynamics.correctionEnd
1449         default_value: 10
1450         min: 10
1451         max: 95
1452         description: "The end  stick correction for Rate Dynamics"
1453         condition: USE_RATE_DYNAMICS
1454       - name: rate_dynamics_center_weight
1455         field: rateDynamics.weightCenter
1456         default_value: 0
1457         min: 0
1458         max: 95
1459         description: "The center stick weight for Rate Dynamics"
1460         condition: USE_RATE_DYNAMICS
1461       - name: rate_dynamics_end_weight
1462         field: rateDynamics.weightEnd
1463         default_value: 0
1464         min: 0
1465         max: 95
1466         description: "The end  stick weight for Rate Dynamics"
1467         condition: USE_RATE_DYNAMICS
1469   - name: PG_SERIAL_CONFIG
1470     type: serialConfig_t
1471     headers: ["io/serial.h"]
1472     members:
1473       - name: reboot_character
1474         description: "Special character used to trigger reboot"
1475         default_value: 82
1476         min: 48
1477         max: 126
1479   - name: PG_IMU_CONFIG
1480     type: imuConfig_t
1481     headers: ["flight/imu.h"]
1482     members:
1483       - name: ahrs_dcm_kp
1484         description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
1485         default_value: 2000
1486         field: dcm_kp_acc
1487         max: UINT16_MAX
1488       - name: ahrs_dcm_ki
1489         description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
1490         default_value: 50
1491         field: dcm_ki_acc
1492         max: UINT16_MAX
1493       - name: ahrs_dcm_kp_mag
1494         description: "Inertial Measurement Unit KP Gain for compass measurements"
1495         default_value: 2000
1496         field: dcm_kp_mag
1497         max: UINT16_MAX
1498       - name: ahrs_dcm_ki_mag
1499         description: "Inertial Measurement Unit KI Gain for compass measurements"
1500         default_value: 50
1501         field: dcm_ki_mag
1502         max: UINT16_MAX
1503       - name: small_angle
1504         description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
1505         default_value: 25
1506         min: 0
1507         max: 180
1508       - name: ahrs_acc_ignore_rate
1509         description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy"
1510         default_value: 15
1511         field: acc_ignore_rate
1512         min: 0
1513         max: 30
1514       - name: ahrs_acc_ignore_slope
1515         description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
1516         default_value: 5
1517         field: acc_ignore_slope
1518         min: 0
1519         max: 10
1520       - name: ahrs_gps_yaw_windcomp
1521         description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)"
1522         default_value: ON
1523         field: gps_yaw_windcomp
1524         type: bool
1525       - name: ahrs_inertia_comp_method
1526         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"
1527         default_value: ADAPTIVE
1528         field: inertia_comp_method
1529         table: imu_inertia_comp_method
1530       - name: ahrs_gps_yaw_weight
1531         description: "Arhs gps yaw weight when mag is avaliable, 0 means no gps yaw, 100 means equal weight as compass"
1532         default_value: 100
1533         field: gps_yaw_weight
1534         min: 0
1535         max: 500
1537   - name: PG_ARMING_CONFIG
1538     type: armingConfig_t
1539     members:
1540       - name: fixed_wing_auto_arm
1541         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."
1542         default_value: OFF
1543         type: bool
1544       - name: disarm_always
1545         description: "Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low."
1546         default_value: ON
1547         type: bool
1548       - name: switch_disarm_delay
1549         description: "Delay before disarming when requested by switch (ms) [0-1000]"
1550         default_value: 250
1551         field: switchDisarmDelayMs
1552         min: 0
1553         max: 1000
1554       - name: prearm_timeout
1555         description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
1556         default_value: 10000
1557         field: prearmTimeoutMs
1558         min: 0
1559         max: 10000
1561   - name: PG_GENERAL_SETTINGS
1562     headers: ["config/general_settings.h"]
1563     type: generalSettings_t
1564     members:
1565       - name: applied_defaults
1566         description: "Internal (configurator) hint. Should not be changed manually"
1567         default_value: 0
1568         field: appliedDefaults
1569         type: uint8_t
1570         min: 0
1571         max: 99
1573   - name: PG_EZ_TUNE
1574     headers: ["flight/ez_tune.h"]
1575     type: ezTuneSettings_t
1576     value_type: EZ_TUNE_VALUE
1577     members:
1578       - name: ez_enabled
1579         description: "Enables EzTune feature"
1580         default_value: OFF
1581         field: enabled
1582         type: bool
1583       - name: ez_filter_hz
1584         description: "EzTune filter cutoff frequency"
1585         default_value: 110
1586         field: filterHz
1587         min: 20
1588         max: 300
1589       - name: ez_axis_ratio
1590         description: "EzTune axis ratio"
1591         default_value: 110
1592         field: axisRatio
1593         min: 25
1594         max: 175
1595       - name: ez_response
1596         description: "EzTune response"
1597         default_value: 100
1598         field: response
1599         min: 0
1600         max: 200
1601       - name: ez_damping
1602         description: "EzTune damping"
1603         default_value: 100
1604         field: damping
1605         min: 0
1606         max: 200
1607       - name: ez_stability
1608         description: "EzTune stability"
1609         default_value: 100
1610         field: stability
1611         min: 0
1612         max: 200
1613       - name: ez_aggressiveness
1614         description: "EzTune aggressiveness"
1615         default_value: 100
1616         field: aggressiveness
1617         min: 0
1618         max: 200
1619       - name: ez_rate
1620         description: "EzTune rate"
1621         default_value: 100
1622         field: rate
1623         min: 0
1624         max: 200
1625       - name: ez_expo
1626         description: "EzTune expo"
1627         default_value: 100
1628         field: expo
1629         min: 0
1630         max: 200
1631       - name: ez_snappiness
1632         description: "EzTune snappiness"
1633         default_value: 0
1634         field: snappiness
1635         min: 0
1636         max: 100
1638   - name: PG_RPM_FILTER_CONFIG
1639     headers: ["flight/rpm_filter.h"]
1640     condition: USE_RPM_FILTER
1641     type: rpmFilterConfig_t
1642     members:
1643       - name: rpm_gyro_filter_enabled
1644         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"
1645         default_value: OFF
1646         field: gyro_filter_enabled
1647         type: bool
1648       - name: rpm_gyro_harmonics
1649         description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
1650         default_value: 1
1651         field: gyro_harmonics
1652         type: uint8_t
1653         min: 1
1654         max: 3
1655       - name: rpm_gyro_min_hz
1656         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         default_value: 100
1658         field: gyro_min_hz
1659         type: uint8_t
1660         min: 30
1661         max: 200
1662       - name: rpm_gyro_q
1663         description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
1664         default_value: 500
1665         field: gyro_q
1666         type: uint16_t
1667         min: 1
1668         max: 3000
1669   - name: PG_GPS_CONFIG
1670     headers: [ "io/gps.h" ]
1671     type: gpsConfig_t
1672     condition: USE_GPS
1673     members:
1674       - name: gps_provider
1675         description: "Which GPS protocol to be used."
1676         default_value: "UBLOX"
1677         field: provider
1678         table: gps_provider
1679         type: uint8_t
1680       - name: gps_sbas_mode
1681         description: "Which SBAS mode to be used"
1682         default_value: "NONE"
1683         field: sbasMode
1684         table: gps_sbas_mode
1685         type: uint8_t
1686       - name: gps_dyn_model
1687         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."
1688         default_value: "AIR_2G"
1689         field: dynModel
1690         table: gps_dyn_model
1691         type: uint8_t
1692       - name: gps_auto_config
1693         description: "Enable automatic configuration of UBlox GPS receivers."
1694         default_value: ON
1695         field: autoConfig
1696         type: bool
1697       - name: gps_auto_baud
1698         description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS"
1699         default_value: ON
1700         field: autoBaud
1701         type: bool
1702       - name: gps_auto_baud_max_supported
1703         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"
1704         default_value: "230400"
1705         table: gps_auto_baud_max
1706         field: autoBaudMax
1707         type: uint8_t
1708       - name: gps_ublox_use_galileo
1709         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]."
1710         default_value: OFF
1711         field: ubloxUseGalileo
1712         type: bool
1713       - name: gps_ublox_use_beidou
1714         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]."
1715         default_value: OFF
1716         field: ubloxUseBeidou
1717         type: bool
1718       - name: gps_ublox_use_glonass
1719         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]."
1720         default_value: OFF
1721         field: ubloxUseGlonass
1722         type: bool
1723       - name: gps_min_sats
1724         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."
1725         default_value: 6
1726         field: gpsMinSats
1727         min: 5
1728         max: 10
1729       - name: gps_ublox_nav_hz
1730         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."
1731         default_value: 10
1732         field: ubloxNavHz
1733         type: uint8_t
1734         min: 5
1735         max: 200
1738   - name: PG_RC_CONTROLS_CONFIG
1739     type: rcControlsConfig_t
1740     headers: ["fc/rc_controls.h"]
1741     members:
1742       - name: deadband
1743         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."
1744         default_value: 2
1745         min: 0
1746         max: 32
1747       - name: yaw_deadband
1748         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."
1749         default_value: 2
1750         min: 0
1751         max: 100
1752       - name: pos_hold_deadband
1753         description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
1754         default_value: 10
1755         min: 2
1756         max: 250
1757       - name: alt_hold_deadband
1758         description: "Defines the deadband of throttle during alt_hold [r/c points]"
1759         default_value: 50
1760         min: 10
1761         max: 250
1762       - name: 3d_deadband_throttle
1763         description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
1764         default_value: 50
1765         field: mid_throttle_deadband
1766         min: 0
1767         max: 200
1768       - name: airmode_type
1769         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."
1770         default_value: "STICK_CENTER"
1771         field: airmodeHandlingType
1772         table: airmodeHandlingType
1773       - name: airmode_throttle_threshold
1774         description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
1775         default_value: 1150
1776         field: airmodeThrottleThreshold
1777         min: 1000
1778         max: 2000
1780   - name: PG_PID_PROFILE
1781     type: pidProfile_t
1782     headers: ["flight/pid.h"]
1783     value_type: PROFILE_VALUE
1784     members:
1785       - name: mc_p_pitch
1786         description: "Multicopter rate stabilisation P-gain for PITCH"
1787         default_value: 40
1788         field: bank_mc.pid[PID_PITCH].P
1789         min: RPYL_PID_MIN
1790         max: RPYL_PID_MAX
1791       - name: mc_i_pitch
1792         description: "Multicopter rate stabilisation I-gain for PITCH"
1793         default_value: 30
1794         field: bank_mc.pid[PID_PITCH].I
1795         min: RPYL_PID_MIN
1796         max: RPYL_PID_MAX
1797       - name: mc_d_pitch
1798         description: "Multicopter rate stabilisation D-gain for PITCH"
1799         default_value: 23
1800         field: bank_mc.pid[PID_PITCH].D
1801         min: RPYL_PID_MIN
1802         max: RPYL_PID_MAX
1803       - name: mc_cd_pitch
1804         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."
1805         default_value: 60
1806         field: bank_mc.pid[PID_PITCH].FF
1807         min: RPYL_PID_MIN
1808         max: RPYL_PID_MAX
1809       - name: mc_p_roll
1810         description: "Multicopter rate stabilisation P-gain for ROLL"
1811         default_value: 40
1812         field: bank_mc.pid[PID_ROLL].P
1813         min: RPYL_PID_MIN
1814         max: RPYL_PID_MAX
1815       - name: mc_i_roll
1816         description: "Multicopter rate stabilisation I-gain for ROLL"
1817         default_value: 30
1818         field: bank_mc.pid[PID_ROLL].I
1819         min: RPYL_PID_MIN
1820         max: RPYL_PID_MAX
1821       - name: mc_d_roll
1822         description: "Multicopter rate stabilisation D-gain for ROLL"
1823         default_value: 23
1824         field: bank_mc.pid[PID_ROLL].D
1825         min: RPYL_PID_MIN
1826         max: RPYL_PID_MAX
1827       - name: mc_cd_roll
1828         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."
1829         default_value: 60
1830         field: bank_mc.pid[PID_ROLL].FF
1831         min: RPYL_PID_MIN
1832         max: RPYL_PID_MAX
1833       - name: mc_p_yaw
1834         description: "Multicopter rate stabilisation P-gain for YAW"
1835         default_value: 85
1836         field: bank_mc.pid[PID_YAW].P
1837         min: RPYL_PID_MIN
1838         max: RPYL_PID_MAX
1839       - name: mc_i_yaw
1840         description: "Multicopter rate stabilisation I-gain for YAW"
1841         default_value: 45
1842         field: bank_mc.pid[PID_YAW].I
1843         min: RPYL_PID_MIN
1844         max: RPYL_PID_MAX
1845       - name: mc_d_yaw
1846         description: "Multicopter rate stabilisation D-gain for YAW"
1847         default_value: 0
1848         field: bank_mc.pid[PID_YAW].D
1849         min: RPYL_PID_MIN
1850         max: RPYL_PID_MAX
1851       - name: mc_cd_yaw
1852         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."
1853         default_value: 60
1854         field: bank_mc.pid[PID_YAW].FF
1855         min: RPYL_PID_MIN
1856         max: RPYL_PID_MAX
1857       - name: mc_p_level
1858         description: "Multicopter attitude stabilisation P-gain"
1859         default_value: 20
1860         field: bank_mc.pid[PID_LEVEL].P
1861         min: RPYL_PID_MIN
1862         max: RPYL_PID_MAX
1863       - name: mc_i_level
1864         description: "Multicopter attitude stabilisation low-pass filter cutoff"
1865         default_value: 15
1866         field: bank_mc.pid[PID_LEVEL].I
1867         min: RPYL_PID_MIN
1868         max: RPYL_PID_MAX
1869       - name: mc_d_level
1870         description: "Multicopter attitude stabilisation HORIZON transition point"
1871         default_value: 75
1872         field: bank_mc.pid[PID_LEVEL].D
1873         min: RPYL_PID_MIN
1874         max: RPYL_PID_MAX
1875       - name: fw_p_pitch
1876         description: "Fixed-wing rate stabilisation P-gain for PITCH"
1877         default_value: 5
1878         field: bank_fw.pid[PID_PITCH].P
1879         min: RPYL_PID_MIN
1880         max: RPYL_PID_MAX
1881       - name: fw_i_pitch
1882         description: "Fixed-wing rate stabilisation I-gain for PITCH"
1883         default_value: 7
1884         field: bank_fw.pid[PID_PITCH].I
1885         min: RPYL_PID_MIN
1886         max: RPYL_PID_MAX
1887       - name: fw_d_pitch
1888         description: "Fixed wing rate stabilisation D-gain for PITCH"
1889         default_value: 0
1890         field: bank_fw.pid[PID_PITCH].D
1891         min: RPYL_PID_MIN
1892         max: RPYL_PID_MAX
1893       - name: fw_ff_pitch
1894         description: "Fixed-wing rate stabilisation FF-gain for PITCH"
1895         default_value: 50
1896         field: bank_fw.pid[PID_PITCH].FF
1897         min: RPYL_PID_MIN
1898         max: RPYL_PID_MAX
1899       - name: fw_p_roll
1900         description: "Fixed-wing rate stabilisation P-gain for ROLL"
1901         default_value: 5
1902         field: bank_fw.pid[PID_ROLL].P
1903         min: RPYL_PID_MIN
1904         max: RPYL_PID_MAX
1905       - name: fw_i_roll
1906         description: "Fixed-wing rate stabilisation I-gain for ROLL"
1907         default_value: 7
1908         field: bank_fw.pid[PID_ROLL].I
1909         min: RPYL_PID_MIN
1910         max: RPYL_PID_MAX
1911       - name: fw_d_roll
1912         description: "Fixed wing rate stabilisation D-gain for ROLL"
1913         default_value: 0
1914         field: bank_fw.pid[PID_ROLL].D
1915         min: RPYL_PID_MIN
1916         max: RPYL_PID_MAX
1917       - name: fw_ff_roll
1918         description: "Fixed-wing rate stabilisation FF-gain for ROLL"
1919         default_value: 50
1920         field: bank_fw.pid[PID_ROLL].FF
1921         min: RPYL_PID_MIN
1922         max: RPYL_PID_MAX
1923       - name: fw_p_yaw
1924         description: "Fixed-wing rate stabilisation P-gain for YAW"
1925         default_value: 6
1926         field: bank_fw.pid[PID_YAW].P
1927         min: RPYL_PID_MIN
1928         max: RPYL_PID_MAX
1929       - name: fw_i_yaw
1930         description: "Fixed-wing rate stabilisation I-gain for YAW"
1931         default_value: 10
1932         field: bank_fw.pid[PID_YAW].I
1933         min: RPYL_PID_MIN
1934         max: RPYL_PID_MAX
1935       - name: fw_d_yaw
1936         description: "Fixed wing rate stabilisation D-gain for YAW"
1937         default_value: 0
1938         field: bank_fw.pid[PID_YAW].D
1939         min: RPYL_PID_MIN
1940         max: RPYL_PID_MAX
1941       - name: fw_ff_yaw
1942         description: "Fixed-wing rate stabilisation FF-gain for YAW"
1943         default_value: 60
1944         field: bank_fw.pid[PID_YAW].FF
1945         min: RPYL_PID_MIN
1946         max: RPYL_PID_MAX
1947       - name: fw_p_level
1948         description: "Fixed-wing attitude stabilisation P-gain"
1949         default_value: 20
1950         field: bank_fw.pid[PID_LEVEL].P
1951         min: RPYL_PID_MIN
1952         max: RPYL_PID_MAX
1953       - name: fw_i_level
1954         description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
1955         default_value: 5
1956         field: bank_fw.pid[PID_LEVEL].I
1957         min: RPYL_PID_MIN
1958         max: RPYL_PID_MAX
1959       - name: fw_d_level
1960         description: "Fixed-wing attitude stabilisation HORIZON transition point"
1961         default_value: 75
1962         field: bank_fw.pid[PID_LEVEL].D
1963         min: RPYL_PID_MIN
1964         max: RPYL_PID_MAX
1965       - name: max_angle_inclination_rll
1966         description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
1967         default_value: 450
1968         field: max_angle_inclination[FD_ROLL]
1969         min: 100
1970         max: 900
1971       - name: max_angle_inclination_pit
1972         description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
1973         default_value: 450
1974         field: max_angle_inclination[FD_PITCH]
1975         min: 100
1976         max: 900
1977       - name: dterm_lpf_hz
1978         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"
1979         default_value: 110
1980         min: 0
1981         max: 500
1982       - name: dterm_lpf_type
1983         description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
1984         default_value: "PT2"
1985         field: dterm_lpf_type
1986         table: filter_type_full
1987       - name: yaw_lpf_hz
1988         description: "Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
1989         default_value: 0
1990         min: 0
1991         max: 200
1992       - name: fw_reference_airspeed
1993         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."
1994         default_value: 1500
1995         field: fixedWingReferenceAirspeed
1996         min: 300
1997         max: 6000
1998       - name: fw_turn_assist_yaw_gain
1999         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"
2000         default_value: 1
2001         field: fixedWingCoordinatedYawGain
2002         min: 0
2003         max: 2
2004       - name: fw_turn_assist_pitch_gain
2005         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"
2006         default_value: 1
2007         field: fixedWingCoordinatedPitchGain
2008         min: 0
2009         max: 2
2010       - name: fw_yaw_iterm_freeze_bank_angle
2011         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."
2012         default_value: 0
2013         field: fixedWingYawItermBankFreeze
2014         min: 0
2015         max: 90
2016       - name: iterm_windup
2017         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)"
2018         default_value: 50
2019         field: itermWindupPointPercent
2020         min: 0
2021         max: 90
2022       - name: pid_iterm_limit_percent
2023         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."
2024         default_value: 33
2025         field: pidItermLimitPercent
2026         min: 0
2027         max: 200
2028       - name: rate_accel_limit_roll_pitch
2029         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."
2030         default_value: 0
2031         field: axisAccelerationLimitRollPitch
2032         max: 500000
2033       - name: rate_accel_limit_yaw
2034         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."
2035         default_value: 10000
2036         field: axisAccelerationLimitYaw
2037         max: 500000
2038       - name: heading_hold_rate_limit
2039         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."
2040         min: HEADING_HOLD_RATE_LIMIT_MIN
2041         max: HEADING_HOLD_RATE_LIMIT_MAX
2042         default_value: 90
2043       - name: nav_mc_pos_z_p
2044         description: "P gain of altitude PID controller (Multirotor)"
2045         field: bank_mc.pid[PID_POS_Z].P
2046         min: 0
2047         max: 255
2048         default_value: 50
2049       - name: nav_mc_vel_z_p
2050         description: "P gain of velocity PID controller"
2051         field: bank_mc.pid[PID_VEL_Z].P
2052         min: 0
2053         max: 255
2054         default_value: 100
2055       - name: nav_mc_vel_z_i
2056         description: "I gain of velocity PID controller"
2057         field: bank_mc.pid[PID_VEL_Z].I
2058         min: 0
2059         max: 255
2060         default_value: 50
2061       - name: nav_mc_vel_z_d
2062         description: "D gain of velocity PID controller"
2063         field: bank_mc.pid[PID_VEL_Z].D
2064         min: 0
2065         max: 255
2066         default_value: 10
2067       - name: nav_mc_pos_xy_p
2068         description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
2069         field: bank_mc.pid[PID_POS_XY].P
2070         min: 0
2071         max: 255
2072         default_value: 65
2073       - name: nav_mc_vel_xy_p
2074         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"
2075         field: bank_mc.pid[PID_VEL_XY].P
2076         min: 0
2077         max: 255
2078         default_value: 40
2079       - name: nav_mc_vel_xy_i
2080         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"
2081         field: bank_mc.pid[PID_VEL_XY].I
2082         min: 0
2083         max: 255
2084         default_value: 15
2085       - name: nav_mc_vel_xy_d
2086         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."
2087         field: bank_mc.pid[PID_VEL_XY].D
2088         min: 0
2089         max: 255
2090         default_value: 100
2091       - name: nav_mc_vel_xy_ff
2092         description: "FF gain of Position-Rate (Velocity to Acceleration)"
2093         field: bank_mc.pid[PID_VEL_XY].FF
2094         min: 0
2095         max: 255
2096         default_value: 40
2097       - name: nav_mc_heading_p
2098         description: "P gain of Heading Hold controller (Multirotor)"
2099         default_value: 60
2100         field: bank_mc.pid[PID_HEADING].P
2101         min: 0
2102         max: 255
2103       - name: nav_mc_vel_xy_dterm_lpf_hz
2104         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."
2105         field: navVelXyDTermLpfHz
2106         min: 0
2107         max: 100
2108         default_value: 2
2109       - name: nav_mc_vel_xy_dterm_attenuation
2110         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."
2111         field: navVelXyDtermAttenuation
2112         min: 0
2113         max: 100
2114         default_value: 90
2115       - name: nav_mc_vel_xy_dterm_attenuation_start
2116         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
2117         default_value: 10
2118         field: navVelXyDtermAttenuationStart
2119         min: 0
2120         max: 100
2121       - name: nav_mc_vel_xy_dterm_attenuation_end
2122         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
2123         default_value: 60
2124         field: navVelXyDtermAttenuationEnd
2125         min: 0
2126         max: 100
2127       - name: nav_fw_pos_z_p
2128         description: "P gain of altitude PID controller (Fixedwing)"
2129         default_value: 40
2130         field: bank_fw.pid[PID_POS_Z].P
2131         min: 0
2132         max: 255
2133       - name: nav_fw_pos_z_i
2134         description: "I gain of altitude PID controller (Fixedwing)"
2135         default_value: 5
2136         field: bank_fw.pid[PID_POS_Z].I
2137         min: 0
2138         max: 255
2139       - name: nav_fw_pos_z_d
2140         description: "D gain of altitude PID controller (Fixedwing)"
2141         default_value: 10
2142         field: bank_fw.pid[PID_POS_Z].D
2143         min: 0
2144         max: 255
2145       - name: nav_fw_alt_control_response
2146         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."
2147         default_value: 20
2148         field: fwAltControlResponseFactor
2149         min: 5
2150         max: 100
2151       - name: nav_fw_pos_xy_p
2152         description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
2153         default_value: 75
2154         field: bank_fw.pid[PID_POS_XY].P
2155         min: 0
2156         max: 255
2157       - name: nav_fw_pos_xy_i
2158         description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2159         default_value: 5
2160         field: bank_fw.pid[PID_POS_XY].I
2161         min: 0
2162         max: 255
2163       - name: nav_fw_pos_xy_d
2164         description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2165         default_value: 8
2166         field: bank_fw.pid[PID_POS_XY].D
2167         min: 0
2168         max: 255
2169       - name: nav_fw_heading_p
2170         description: "P gain of Heading Hold controller (Fixedwing)"
2171         default_value: 60
2172         field: bank_fw.pid[PID_HEADING].P
2173         min: 0
2174         max: 255
2175       - name: nav_fw_pos_hdg_p
2176         description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
2177         default_value: 30
2178         field: bank_fw.pid[PID_POS_HEADING].P
2179         min: 0
2180         max: 255
2181       - name: nav_fw_pos_hdg_i
2182         description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2183         default_value: 2
2184         field: bank_fw.pid[PID_POS_HEADING].I
2185         min: 0
2186         max: 255
2187       - name: nav_fw_pos_hdg_d
2188         description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2189         default_value: 0
2190         field: bank_fw.pid[PID_POS_HEADING].D
2191         min: 0
2192         max: 255
2193       - name: nav_fw_pos_hdg_pidsum_limit
2194         description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
2195         default_value: 350
2196         field: navFwPosHdgPidsumLimit
2197         min: PID_SUM_LIMIT_MIN
2198         max: PID_SUM_LIMIT_MAX
2199       - name: mc_iterm_relax
2200         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."
2201         field: iterm_relax
2202         table: iterm_relax
2203         default_value: RP
2204       - name: mc_iterm_relax_cutoff
2205         description: "Iterm relax cutoff frequency."
2206         field: iterm_relax_cutoff
2207         min: 1
2208         max: 100
2209         default_value: 15
2210       - name: d_boost_min
2211         description: "D-term multiplier when pilot provides rapid stick input. Lower values give sharper response to stick input, higher values give smoother response."
2212         field: dBoostMin
2213         condition: USE_D_BOOST
2214         min: 0
2215         max: 1
2216         default_value: 0.5
2217       - name: d_boost_max
2218         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."
2219         field: dBoostMax
2220         condition: USE_D_BOOST
2221         min: 1
2222         max: 3
2223         default_value: 1.25
2224       - name: d_boost_max_at_acceleration
2225         description: "Acceleration threshold for D-term multiplier. When acceleration is above this value, D-term multiplier is set to `d_boost_max`"
2226         field: dBoostMaxAtAlleceleration
2227         condition: USE_D_BOOST
2228         min: 1000
2229         max: 16000
2230         default_value: 7500
2231       - name: d_boost_gyro_delta_lpf_hz
2232         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."
2233         field: dBoostGyroDeltaLpfHz
2234         condition: USE_D_BOOST
2235         min: 10
2236         max: 250
2237         default_value: 80
2238       - name: antigravity_gain
2239         description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
2240         default_value: 1
2241         field: antigravityGain
2242         condition: USE_ANTIGRAVITY
2243         min: 1
2244         max: 20
2245       - name: antigravity_accelerator
2246         description: "Multiplier for Antigravity gain. The bigger is the difference between actual and filtered throttle input, the bigger Antigravity gain"
2247         default_value: 1
2248         field: antigravityAccelerator
2249         condition: USE_ANTIGRAVITY
2250         min: 1
2251         max: 20
2252       - name: antigravity_cutoff_lpf_hz
2253         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"
2254         default_value: 15
2255         field: antigravityCutoff
2256         condition: USE_ANTIGRAVITY
2257         min: 1
2258         max: 30
2259       - name: pid_type
2260         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`"
2261         field: pidControllerType
2262         table: pidTypeTable
2263         default_value: AUTO
2264       - name: mc_cd_lpf_hz
2265         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."
2266         default_value: 30
2267         field: controlDerivativeLpfHz
2268         min: 0
2269         max: 200
2270       - name: fw_level_pitch_trim
2271         description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
2272         default_value: 0
2273         field: fixedWingLevelTrim
2274         min: -10
2275         max: 10
2276       - name: smith_predictor_strength
2277         description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2278         default_value: 0.5
2279         field: smithPredictorStrength
2280         condition: USE_SMITH_PREDICTOR
2281         min: 0
2282         max: 1
2283       - name: smith_predictor_delay
2284         description: "Expected delay of the gyro signal. In milliseconds"
2285         default_value: 0
2286         field: smithPredictorDelay
2287         condition: USE_SMITH_PREDICTOR
2288         min: 0
2289         max: 8
2290       - name: smith_predictor_lpf_hz
2291         description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2292         default_value: 50
2293         field: smithPredictorFilterHz
2294         condition: USE_SMITH_PREDICTOR
2295         min: 1
2296         max: 500
2297       - name: fw_level_pitch_gain
2298         description: "I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations"
2299         default_value: 5
2300         field: fixedWingLevelTrimGain
2301         min: 0
2302         max: 20
2303       - name: fw_iterm_lock_time_max_ms
2304         description: Defines max time in milliseconds for how long ITerm Lock will shut down Iterm after sticks are release
2305         default_value: 500
2306         field: fwItermLockTimeMaxMs
2307         min: 100
2308         max: 1000
2309       - name: fw_iterm_lock_rate_threshold
2310         description: Defines rate percentage when full P I and D attenuation should happen. 100 disables Iterm Lock for P and D term
2311         field: fwItermLockRateLimit
2312         default_value: 40
2313         min: 10
2314         max: 100
2315       - name: fw_iterm_lock_engage_threshold
2316         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
2317         default_value: 10
2318         min: 5
2319         max: 25
2320         field: fwItermLockEngageThreshold
2322   - name: PG_PID_AUTOTUNE_CONFIG
2323     type: pidAutotuneConfig_t
2324     condition: USE_AUTOTUNE_FIXED_WING
2325     members:
2326       - name: fw_autotune_min_stick
2327         description: "Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input."
2328         default_value: 50
2329         field: fw_min_stick
2330         min: 0
2331         max: 100
2332       - name: fw_autotune_rate_adjustment
2333         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."
2334         default_value: "AUTO"
2335         field: fw_rate_adjustment
2336         table: autotune_rate_adjustment
2337         type: uint8_t
2338       - name: fw_autotune_max_rate_deflection
2339         description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
2340         default_value: 80
2341         field: fw_max_rate_deflection
2342         min: 50
2343         max: 100
2345   - name: PG_POSITION_ESTIMATION_CONFIG
2346     type: positionEstimationConfig_t
2347     members:
2348       - name: inav_auto_mag_decl
2349         description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
2350         default_value: ON
2351         field: automatic_mag_declination
2352         type: bool
2353       - name: inav_gravity_cal_tolerance
2354         description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
2355         default_value: 5
2356         field: gravity_calibration_tolerance
2357         min: 0
2358         max: 255
2359       - name: inav_allow_dead_reckoning
2360         description: "Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
2361         default_value: OFF
2362         field: allow_dead_reckoning
2363         type: bool
2364       - name: inav_allow_gps_fix_estimation
2365         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."
2366         condition: USE_GPS_FIX_ESTIMATION
2367         default_value: OFF
2368         field: allow_gps_fix_estimation
2369         type: bool
2370       - name: inav_reset_altitude
2371         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)"
2372         default_value: "FIRST_ARM"
2373         field: reset_altitude_type
2374         table: reset_type
2375       - name: inav_reset_home
2376         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"
2377         default_value: "FIRST_ARM"
2378         field: reset_home_type
2379         table: reset_type
2380       - name: inav_max_surface_altitude
2381         description: "Max allowed altitude for surface following mode. [cm]"
2382         default_value: 200
2383         field: max_surface_altitude
2384         min: 0
2385         max: 1000
2386       - name: inav_w_z_surface_p
2387         description: "Weight of rangefinder measurements in estimated altitude. Setting is used on both airplanes and multirotors when rangefinder is present and Surface mode enabled"
2388         field: w_z_surface_p
2389         min: 0
2390         max: 100
2391         default_value: 3.5
2392       - name: inav_w_z_surface_v
2393         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"
2394         field: w_z_surface_v
2395         min: 0
2396         max: 100
2397         default_value: 6.1
2398       - name: inav_w_xy_flow_p
2399         description: "Weight of optical flow measurements in estimated UAV position."
2400         field: w_xy_flow_p
2401         min: 0
2402         max: 100
2403         default_value: 1.0
2404       - name: inav_w_xy_flow_v
2405         description: "Weight of optical flow measurements in estimated UAV speed."
2406         field: w_xy_flow_v
2407         min: 0
2408         max: 100
2409         default_value: 2.0
2410       - name: inav_w_z_baro_p
2411         description: "Weight of barometer measurements in estimated altitude and climb rate. Setting is used on both airplanes and multirotors."
2412         field: w_z_baro_p
2413         min: 0
2414         max: 10
2415         default_value: 0.35
2416       - name: inav_w_z_baro_v
2417         description: "Weight of barometer climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
2418         field: w_z_baro_v
2419         min: 0
2420         max: 10
2421         default_value: 0.1
2422       - name: inav_w_z_gps_p
2423         description: "Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors."
2424         field: w_z_gps_p
2425         min: 0
2426         max: 10
2427         default_value: 0.2
2428       - name: inav_w_z_gps_v
2429         description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
2430         field: w_z_gps_v
2431         min: 0
2432         max: 10
2433         default_value: 0.1
2434       - name: inav_w_xy_gps_p
2435         description: "Weight of GPS coordinates in estimated UAV position and speed."
2436         default_value: 1.0
2437         field: w_xy_gps_p
2438         min: 0
2439         max: 10
2440       - name: inav_w_xy_gps_v
2441         description: "Weight of GPS velocity data in estimated UAV speed"
2442         default_value: 2.0
2443         field: w_xy_gps_v
2444         min: 0
2445         max: 10
2446       - name: inav_w_z_res_v
2447         description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
2448         default_value: 0.5
2449         field: w_z_res_v
2450         min: 0
2451         max: 10
2452       - name: inav_w_xy_res_v
2453         description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
2454         default_value: 0.5
2455         field: w_xy_res_v
2456         min: 0
2457         max: 10
2458       - name: inav_w_acc_bias
2459         description: "Weight for accelerometer drift estimation"
2460         default_value: 0.01
2461         field: w_acc_bias
2462         min: 0
2463         max: 1
2464       - name: inav_max_eph_epv
2465         description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
2466         default_value: 1000
2467         field: max_eph_epv
2468         min: 0
2469         max: 9999
2470       - name: inav_baro_epv
2471         description: "Uncertainty value for barometric sensor [cm]"
2472         default_value: 100
2473         field: baro_epv
2474         min: 0
2475         max: 9999
2476       - name: inav_default_alt_sensor
2477         description: "Sets the default altitude sensor to use. Settings GPS and BARO always use both sensors unless there is an altitude error between the sensors that exceeds a set limit. In this case only the selected sensor will be used while the altitude error limit is exceeded. GPS error limit = 2 * inav_max_eph_epv. BARO error limit = 4 * inav_baro_epv. Settings GPS_ONLY and BARO_ONLY will use only the selected sensor even if the other sensor is working. The other sensor will only be used as a backup if the selected sensor is no longer available to use."
2478         default_value: "GPS"
2479         field: default_alt_sensor
2480         table: default_altitude_source
2482   - name: PG_NAV_CONFIG
2483     type: navConfig_t
2484     headers: ["navigation/navigation.h"]
2485     members:
2486       - name: nav_disarm_on_landing
2487         description: "If set to ON, INAV disarms the FC after landing"
2488         default_value: ON
2489         field: general.flags.disarm_on_landing
2490         type: bool
2491       - name: nav_land_detect_sensitivity
2492         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."
2493         default_value: 5
2494         field: general.land_detect_sensitivity
2495         min: 1
2496         max: 15
2497       - name: nav_landing_bump_detection
2498         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)."
2499         default_value: OFF
2500         field: general.flags.landing_bump_detection
2501         type: bool
2502       - name: nav_mc_inverted_crash_detection
2503         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."
2504         default_value: 0
2505         field: mc.inverted_crash_detection
2506         min: 0
2507         max: 15
2508       - name: nav_mc_althold_throttle
2509         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."
2510         default_value: "STICK"
2511         field: mc.althold_throttle_type
2512         table: nav_mc_althold_throttle
2513       - name: nav_extra_arming_safety
2514         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"
2515         default_value: "ALLOW_BYPASS"
2516         field: general.flags.extra_arming_safety
2517         table: nav_extra_arming_safety
2518       - name: nav_user_control_mode
2519         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."
2520         default_value: "ATTI"
2521         field: general.flags.user_control_mode
2522         table: nav_user_control_mode
2523       - name: nav_position_timeout
2524         description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
2525         default_value: 5
2526         field: general.pos_failure_timeout
2527         min: 0
2528         max: 10
2529       - name: nav_wp_load_on_boot
2530         description: "If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup."
2531         default_value: OFF
2532         field: general.waypoint_load_on_boot
2533         type: bool
2534       - name: nav_wp_radius
2535         description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
2536         default_value: 100
2537         field: general.waypoint_radius
2538         min: 10
2539         max: 10000
2540       - name: nav_wp_enforce_altitude
2541         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."
2542         default_value: 0
2543         field: general.waypoint_enforce_altitude
2544         min: 0
2545         max: 2000
2546       - name: nav_wp_max_safe_distance
2547         description: "First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check."
2548         default_value: 100
2549         field: general.waypoint_safe_distance
2550         min: 0
2551         max: 1500
2552       - name: nav_wp_mission_restart
2553         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."
2554         default_value: "RESUME"
2555         field: general.flags.waypoint_mission_restart
2556         table: nav_wp_mission_restart
2557       - name: nav_wp_multi_mission_index
2558         description: "Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions."
2559         default_value: 1
2560         field: general.waypoint_multi_mission_index
2561         condition: USE_MULTI_MISSION
2562         min: 1
2563         max: 9
2564       - name: nav_fw_wp_tracking_accuracy
2565         description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Setting adjusts tracking deadband distance fom waypoint courseline [m]. Tracking isn't actively controlled within the deadband providing smoother flight adjustments but less accurate tracking. A 2m deadband should work OK in most cases. Setting to 0 disables waypoint tracking accuracy."
2566         default_value: 0
2567         field: fw.wp_tracking_accuracy
2568         min: 0
2569         max: 10
2570       - name: nav_fw_wp_tracking_max_angle
2571         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."
2572         default_value: 60
2573         field: fw.wp_tracking_max_angle
2574         min: 30
2575         max: 80
2576       - name: nav_fw_wp_turn_smoothing
2577         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)."
2578         default_value: "OFF"
2579         field: fw.wp_turn_smoothing
2580         table: nav_fw_wp_turn_smoothing
2581       - name: nav_auto_speed
2582         description: "Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]"
2583         default_value: 500
2584         field: general.auto_speed
2585         min: 10
2586         max: 2000
2587       - name: nav_min_ground_speed
2588         description: "Minimum ground speed for navigation flight modes [m/s]. Currently, this only affects fixed wing. Default 7 m/s."
2589         default_value: 7
2590         field: general.min_ground_speed
2591         min: 6
2592         max: 50
2593       - name: nav_max_auto_speed
2594         description: "Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]"
2595         default_value: 1000
2596         field: general.max_auto_speed
2597         min: 10
2598         max: 2000
2599       - name: nav_manual_speed
2600         description: "Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
2601         default_value: 750
2602         field: general.max_manual_speed
2603         min: 10
2604         max: 2000
2605       - name: nav_land_minalt_vspd
2606         description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
2607         default_value: 50
2608         field: general.land_minalt_vspd
2609         min: 50
2610         max: 500
2611       - name: nav_land_maxalt_vspd
2612         description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"
2613         default_value: 200
2614         field: general.land_maxalt_vspd
2615         min: 100
2616         max: 2000
2617       - name: nav_land_slowdown_minalt
2618         description: "Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]"
2619         default_value: 500
2620         field: general.land_slowdown_minalt
2621         min: 50
2622         max: 1000
2623       - name: nav_land_slowdown_maxalt
2624         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]"
2625         default_value: 2000
2626         field: general.land_slowdown_maxalt
2627         min: 500
2628         max: 4000
2629       - name: nav_emerg_landing_speed
2630         description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
2631         default_value: 500
2632         field: general.emerg_descent_rate
2633         min: 100
2634         max: 2000
2635       - name: nav_min_rth_distance
2636         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."
2637         default_value: 500
2638         field: general.min_rth_distance
2639         min: 0
2640         max: 5000
2641       - name: nav_overrides_motor_stop
2642         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"
2643         default_value: "ALL_NAV"
2644         field: general.flags.nav_overrides_motor_stop
2645         table: nav_overrides_motor_stop
2646       - name: nav_fw_soaring_motor_stop
2647         description: "Stops motor when Soaring mode enabled."
2648         default_value: OFF
2649         field: general.flags.soaring_motor_stop
2650         type: bool
2651       - name: nav_fw_soaring_pitch_deadband
2652         description: "Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within deadband allowing pitch to free float whilst soaring."
2653         default_value: 5
2654         field: fw.soaring_pitch_deadband
2655         min: 0
2656         max: 15
2657       - name: nav_rth_climb_first
2658         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)"
2659         default_value: "ON"
2660         field: general.flags.rth_climb_first
2661         table: nav_rth_climb_first
2662       - name: nav_rth_climb_first_stage_mode
2663         description: "This determines how rth_climb_first_stage_altitude is used. Default is AT_LEAST."
2664         default_value: "AT_LEAST"
2665         field: general.flags.rth_climb_first_stage_mode
2666         table: nav_rth_climb_first_stage_modes
2667       - name: nav_rth_climb_first_stage_altitude
2668         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."
2669         default_value: 0
2670         field: general.rth_climb_first_stage_altitude
2671         max: 65000
2672       - name: nav_rth_climb_ignore_emerg
2673         description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
2674         default_value: OFF
2675         field: general.flags.rth_climb_ignore_emerg
2676         type: bool
2677       - name: nav_rth_tail_first
2678         description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
2679         default_value: OFF
2680         field: general.flags.rth_tail_first
2681         type: bool
2682       - name: nav_rth_allow_landing
2683         description: "If set to ON drone will land as a last phase of RTH."
2684         default_value: "ALWAYS"
2685         field: general.flags.rth_allow_landing
2686         table: nav_rth_allow_landing
2687       - name: nav_rth_fs_landing_delay
2688         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]"
2689         default_value: 0
2690         min: 0
2691         max: 1800
2692         field: general.rth_fs_landing_delay
2693       - name: nav_rth_alt_mode
2694         description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details"
2695         default_value: "AT_LEAST"
2696         field: general.flags.rth_alt_control_mode
2697         table: nav_rth_alt_mode
2698       - name: nav_rth_alt_control_override
2699         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)"
2700         default_value: OFF
2701         field: general.flags.rth_alt_control_override
2702         type: bool
2703       - name: nav_rth_abort_threshold
2704         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]"
2705         default_value: 50000
2706         field: general.rth_abort_threshold
2707         max: 65000
2708         min: 0
2709       - name: nav_max_terrain_follow_alt
2710         field: general.max_terrain_follow_altitude
2711         default_value: "100"
2712         description: "Max allowed above the ground altitude for terrain following mode [cm]"
2713         max: 1000
2714         default_value: 100
2715       - name: nav_max_altitude
2716         field: general.max_altitude
2717         description: "Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled"
2718         default_value: 0
2719         max: 65000
2720         min: 0
2721       - name: nav_rth_altitude
2722         description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
2723         default_value: 1000
2724         field: general.rth_altitude
2725         max: 65000
2726       - name: nav_rth_home_altitude
2727         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]"
2728         default_value: 0
2729         field: general.rth_home_altitude
2730         max: 65000
2731       - name: nav_rth_linear_descent_start_distance
2732         description: The distance [m] away from home to start the linear descent. 0 = immediately (original linear descent behaviour)
2733         default_value: 0
2734         min: 0
2735         max: 10000
2736         field: general.rth_linear_descent_start_distance
2737       - name: nav_rth_use_linear_descent
2738         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`.
2739         default_value: OFF
2740         type: bool
2741         field: general.flags.rth_use_linear_descent
2742       - name: nav_rth_trackback_mode
2743         description: "Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only."
2744         default_value: "OFF"
2745         field: general.flags.rth_trackback_mode
2746         table: rth_trackback_mode
2747       - name: nav_rth_trackback_distance
2748         description: "Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m]."
2749         default_value: 500
2750         field: general.rth_trackback_distance
2751         max: 2000
2752         min: 50
2753       - name: safehome_max_distance
2754         description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
2755         default_value: 20000
2756         field: general.safehome_max_distance
2757         min: 0
2758         max: 65000
2759       - name: safehome_usage_mode
2760         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."
2761         default_value: "RTH"
2762         field: general.flags.safehome_usage_mode
2763         table: safehome_usage_mode
2764       - name: nav_mission_planner_reset
2765         description: "With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling the mode switch ON-OFF-ON."
2766         default_value: ON
2767         field: general.flags.mission_planner_reset
2768         type: bool
2769       - name: nav_cruise_yaw_rate
2770         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]"
2771         default_value: 60
2772         field: general.cruise_yaw_rate
2773         min: 0
2774         max: 120
2775       - name: nav_mc_bank_angle
2776         description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
2777         default_value: 35
2778         field: mc.max_bank_angle
2779         min: 15
2780         max: 45
2781       - name: nav_mc_auto_climb_rate
2782         description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2783         default_value: 500
2784         field: mc.max_auto_climb_rate
2785         min: 10
2786         max: 2000
2787       - name: nav_mc_manual_climb_rate
2788         description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2789         default_value: 200
2790         field: mc.max_manual_climb_rate
2791         min: 10
2792         max: 2000
2793       - name: nav_auto_disarm_delay
2794         description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)"
2795         default_value: 1000
2796         field: general.auto_disarm_delay
2797         min: 100
2798         max: 10000
2799       - name: nav_mc_braking_speed_threshold
2800         description: "min speed in cm/s above which braking can happen"
2801         default_value: 100
2802         field: mc.braking_speed_threshold
2803         condition: USE_MR_BRAKING_MODE
2804         min: 0
2805         max: 1000
2806       - name: nav_mc_braking_disengage_speed
2807         description: "braking is disabled when speed goes below this value"
2808         default_value: 75
2809         field: mc.braking_disengage_speed
2810         condition: USE_MR_BRAKING_MODE
2811         min: 0
2812         max: 1000
2813       - name: nav_mc_braking_timeout
2814         description: "timeout in ms for braking"
2815         default_value: 2000
2816         field: mc.braking_timeout
2817         condition: USE_MR_BRAKING_MODE
2818         min: 100
2819         max: 5000
2820       - name: nav_mc_braking_boost_factor
2821         description: "acceleration factor for BOOST phase"
2822         default_value: 100
2823         field: mc.braking_boost_factor
2824         condition: USE_MR_BRAKING_MODE
2825         min: 0
2826         max: 200
2827       - name: nav_mc_braking_boost_timeout
2828         description: "how long in ms BOOST phase can happen"
2829         default_value: 750
2830         field: mc.braking_boost_timeout
2831         condition: USE_MR_BRAKING_MODE
2832         min: 0
2833         max: 5000
2834       - name: nav_mc_braking_boost_speed_threshold
2835         description: "BOOST can be enabled when speed is above this value"
2836         default_value: 150
2837         field: mc.braking_boost_speed_threshold
2838         condition: USE_MR_BRAKING_MODE
2839         min: 100
2840         max: 1000
2841       - name: nav_mc_braking_boost_disengage_speed
2842         description: "BOOST will be disabled when speed goes below this value"
2843         default_value: 100
2844         field: mc.braking_boost_disengage_speed
2845         condition: USE_MR_BRAKING_MODE
2846         min: 0
2847         max: 1000
2848       - name: nav_mc_braking_bank_angle
2849         description: "max angle that MR is allowed to bank in BOOST mode"
2850         default_value: 40
2851         field: mc.braking_bank_angle
2852         condition: USE_MR_BRAKING_MODE
2853         min: 15
2854         max: 60
2855       - name: nav_mc_pos_deceleration_time
2856         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"
2857         default_value: 120
2858         field: mc.posDecelerationTime
2859         min: 0
2860         max: 255
2861       - name: nav_mc_pos_expo
2862         description: "Expo for PosHold control"
2863         default_value: 10
2864         field: mc.posResponseExpo
2865         min: 0
2866         max: 255
2867       - name: nav_mc_wp_slowdown
2868         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."
2869         default_value: ON
2870         field: mc.slowDownForTurning
2871         type: bool
2872       - name: nav_fw_bank_angle
2873         description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
2874         default_value: 35
2875         field: fw.max_bank_angle
2876         min: 5
2877         max: 80
2878       - name: nav_fw_auto_climb_rate
2879         description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2880         default_value: 500
2881         field: fw.max_auto_climb_rate
2882         min: 10
2883         max: 2000
2884       - name: nav_fw_manual_climb_rate
2885         description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2886         default_value: 300
2887         field: fw.max_manual_climb_rate
2888         min: 10
2889         max: 2500
2890       - name: nav_fw_climb_angle
2891         description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2892         default_value: 20
2893         field: fw.max_climb_angle
2894         min: 5
2895         max: 80
2896       - name: nav_fw_dive_angle
2897         description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2898         default_value: 15
2899         field: fw.max_dive_angle
2900         min: 5
2901         max: 80
2902       - name: nav_fw_pitch2thr_smoothing
2903         description:  "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
2904         default_value: 6
2905         field: fw.pitch_to_throttle_smooth
2906         min: 0
2907         max: 9
2908       - name: fw_min_throttle_down_pitch
2909         description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
2910         default_value: 0
2911         field: fw.minThrottleDownPitchAngle
2912         min: 0
2913         max: 450
2914       - name: nav_fw_pitch2thr_threshold
2915         description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
2916         default_value: 50
2917         field: fw.pitch_to_throttle_thresh
2918         min: 0
2919         max: 900
2920       - name: nav_fw_loiter_radius
2921         description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
2922         default_value: 7500
2923         field: fw.loiter_radius
2924         min: 0
2925         max: 30000
2926       - name: fw_loiter_direction
2927         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."
2928         default_value: "RIGHT"
2929         field: fw.loiter_direction
2930         table: direction
2931       - name: nav_fw_cruise_speed
2932         description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
2933         default_value: 0
2934         field: fw.cruise_speed
2935         min: 0
2936         max: 65535
2937       - name: nav_fw_control_smoothness
2938         description: "How smoothly the autopilot controls the airplane to correct the navigation error"
2939         default_value: 0
2940         field: fw.control_smoothness
2941         min: 0
2942         max: 9
2943       - name: nav_fw_land_dive_angle
2944         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"
2945         default_value: 2
2946         field: fw.land_dive_angle
2947         min: -20
2948         max: 20
2949       - name: nav_fw_launch_velocity
2950         description: "Forward velocity threshold for swing-launch detection [cm/s]"
2951         default_value: 300
2952         field: fw.launch_velocity_thresh
2953         min: 100
2954         max: 10000
2955       - name: nav_fw_launch_accel
2956         description: "Forward acceleration threshold for bungee launch or throw launch [cm/s/s], 1G = 981 cm/s/s"
2957         default_value: 1863
2958         field: fw.launch_accel_thresh
2959         min: 1350
2960         max: 20000
2961       - name: nav_fw_launch_max_angle
2962         description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
2963         default_value: 45
2964         field: fw.launch_max_angle
2965         min: 5
2966         max: 180
2967       - name: nav_fw_launch_detect_time
2968         description: "Time for which thresholds have to breached to consider launch happened [ms]"
2969         default_value: 40
2970         field: fw.launch_time_thresh
2971         min: 10
2972         max: 1000
2973       - name: nav_fw_launch_idle_motor_delay
2974         description: "Delay between raising throttle and motor starting at idle throttle (ms)"
2975         default_value: 0
2976         field: fw.launch_idle_motor_timer
2977         min: 0
2978         max: 60000
2979       - name: nav_fw_launch_wiggle_to_wake_idle
2980         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."
2981         field: fw.launch_wiggle_wake_idle
2982         type: uint8_t
2983         default_value: 0
2984         min: 0
2985         max: 2
2986       - name: nav_fw_launch_motor_delay
2987         description: "Delay between detected launch and launch sequence start and throttling up (ms)"
2988         default_value: 500
2989         field: fw.launch_motor_timer
2990         min: 0
2991         max: 5000
2992       - name: nav_fw_launch_spinup_time
2993         description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
2994         default_value: 100
2995         field: fw.launch_motor_spinup_time
2996         min: 0
2997         max: 1000
2998       - name: nav_fw_launch_end_time
2999         description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
3000         default_value: 3000
3001         field: fw.launch_end_time
3002         min: 0
3003         max: 5000
3004       - name: nav_fw_launch_min_time
3005         description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
3006         default_value: 0
3007         field: fw.launch_min_time
3008         min: 0
3009         max: 60000
3010       - name: nav_fw_launch_timeout
3011         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)"
3012         default_value: 5000
3013         field: fw.launch_timeout
3014         max: 60000
3015       - name: nav_fw_launch_max_altitude
3016         description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
3017         default_value: 0
3018         field: fw.launch_max_altitude
3019         min: 0
3020         max: 60000
3021       - name: nav_fw_launch_climb_angle
3022         description: "Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
3023         default_value: 18
3024         field: fw.launch_climb_angle
3025         min: 5
3026         max: 45
3027       - name: nav_fw_launch_manual_throttle
3028         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)."
3029         default_value: OFF
3030         field: fw.launch_manual_throttle
3031         type: bool
3032       - name: nav_fw_launch_land_abort_deadband
3033         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."
3034         default_value: 100
3035         field: fw.launch_land_abort_deadband
3036         min: 2
3037         max: 250
3038       - name: nav_fw_allow_manual_thr_increase
3039         description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
3040         default_value: OFF
3041         field: fw.allow_manual_thr_increase
3042         type: bool
3043       - name: nav_use_fw_yaw_control
3044         description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
3045         default_value: OFF
3046         field: fw.useFwNavYawControl
3047         type: bool
3048       - name: nav_fw_yaw_deadband
3049         description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
3050         default_value: 0
3051         field: fw.yawControlDeadband
3052         min: 0
3053         max: 90
3055   - name: PG_TELEMETRY_CONFIG
3056     type: telemetryConfig_t
3057     headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/sim.h"]
3058     condition: USE_TELEMETRY
3059     members:
3060       - name: telemetry_switch
3061         description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
3062         default_value: OFF
3063         type: bool
3064       - name: telemetry_inverted
3065         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."
3066         default_value: OFF
3067         type: bool
3068       - name: frsky_pitch_roll
3069         description: "S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
3070         default_value: OFF
3071         type: bool
3072       - name: frsky_use_legacy_gps_mode_sensor_ids
3073         description: "S.Port telemetry: If `ON`, send the legacy telemetry IDs for modes (Tmp1) and GNSS (Tmp2). These are old IDs, deprecated, and will be removed in INAV 10.0. Tools and scripts using these IDs should be updated to use the new IDs of **470** for Modes and **480** for GNSS. Default: 'OFF'"
3074         default_value: OFF
3075         type: bool
3076       - name: report_cell_voltage
3077         description: "S.Port and IBUS telemetry: Send the average cell voltage if set to ON"
3078         default_value: OFF
3079         type: bool
3080       - name: hott_alarm_sound_interval
3081         description: "Battery alarm delay in seconds for Hott telemetry"
3082         default_value: 5
3083         field: hottAlarmSoundInterval
3084         min: 0
3085         max: 120
3086       - name: telemetry_halfduplex
3087         description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
3088         default_value: ON
3089         field: halfDuplex
3090         type: bool
3091       - name: smartport_fuel_unit
3092         description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]"
3093         default_value: "MAH"
3094         field: smartportFuelUnit
3095         condition: USE_TELEMETRY_SMARTPORT
3096         type: uint8_t
3097         table: smartport_fuel_unit
3098       - name: ibus_telemetry_type
3099         description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
3100         default_value: 0
3101         field: ibusTelemetryType
3102         min: 0
3103         max: 255
3104       - name: ltm_update_rate
3105         description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details."
3106         default_value: "NORMAL"
3107         field: ltmUpdateRate
3108         condition: USE_TELEMETRY_LTM
3109         table: ltm_rates
3110       - name: sim_ground_station_number
3111         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."
3112         default_value: ""
3113         field: simGroundStationNumber
3114         condition: USE_TELEMETRY_SIM
3115       - name: sim_pin
3116         description: "PIN code for the SIM module"
3117         default_value: "0000"
3118         field: simPin
3119         condition: USE_TELEMETRY_SIM
3120       - name: sim_transmit_interval
3121         description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
3122         default_value: 60
3123         field: simTransmitInterval
3124         condition: USE_TELEMETRY_SIM
3125         type: uint16_t
3126         min: SIM_MIN_TRANSMIT_INTERVAL
3127         max: 65535
3128       - name: sim_transmit_flags
3129         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`"
3130         default_value: :SIM_TX_FLAG_FAILSAFE
3131         field: simTransmitFlags
3132         condition: USE_TELEMETRY_SIM
3133         max: 63
3134       - name: acc_event_threshold_high
3135         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."
3136         default_value: 0
3137         field: accEventThresholdHigh
3138         condition: USE_TELEMETRY_SIM
3139         type: uint16_t
3140         min: 0
3141         max: 65535
3142       - name: acc_event_threshold_low
3143         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."
3144         default_value: 0
3145         field: accEventThresholdLow
3146         condition: USE_TELEMETRY_SIM
3147         type: uint16_t
3148         min: 0
3149         max: 900
3150       - name: acc_event_threshold_neg_x
3151         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."
3152         default_value: 0
3153         field: accEventThresholdNegX
3154         condition: USE_TELEMETRY_SIM
3155         type: uint16_t
3156         min: 0
3157         max: 65535
3158       - name: sim_low_altitude
3159         description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
3160         default_value: -32767
3161         field: simLowAltitude
3162         condition: USE_TELEMETRY_SIM
3163         type: int16_t
3164         min: INT16_MIN
3165         max: INT16_MAX
3166       - name: mavlink_ext_status_rate
3167         field: mavlink.extended_status_rate
3168         description: "Rate of the extended status message for MAVLink telemetry"
3169         type: uint8_t
3170         min: 0
3171         max: 255
3172         default_value: 2
3173       - name: mavlink_rc_chan_rate
3174         description: "Rate of the RC channels message for MAVLink telemetry"
3175         field: mavlink.rc_channels_rate
3176         type: uint8_t
3177         min: 0
3178         max: 255
3179         default_value: 1
3180       - name: mavlink_pos_rate
3181         description: "Rate of the position message for MAVLink telemetry"
3182         field: mavlink.position_rate
3183         type: uint8_t
3184         min: 0
3185         max: 255
3186         default_value: 2
3187       - name: mavlink_extra1_rate
3188         description: "Rate of the extra1 message for MAVLink telemetry"
3189         field: mavlink.extra1_rate
3190         type: uint8_t
3191         min: 0
3192         max: 255
3193         default_value: 2
3194       - name: mavlink_extra2_rate
3195         description: "Rate of the extra2 message for MAVLink telemetry"
3196         field: mavlink.extra2_rate
3197         type: uint8_t
3198         min: 0
3199         max: 255
3200         default_value: 2
3201       - name: mavlink_extra3_rate
3202         description: "Rate of the extra3 message for MAVLink telemetry"
3203         field: mavlink.extra3_rate
3204         type: uint8_t
3205         min: 0
3206         max: 255
3207         default_value: 1
3208       - name: mavlink_version
3209         field: mavlink.version
3210         description: "Version of MAVLink to use"
3211         type: uint8_t
3212         min: 1
3213         max: 2
3214         default_value: 2
3215       - name: mavlink_min_txbuffer
3216         field: mavlink.min_txbuff
3217         description: "Minimum percent of TX buffer space free, before attempting to transmit telemetry. Requuires RADIO_STATUS messages to be processed. 0 = always transmits."
3218         default_value: 33
3219         min: 0
3220         max: 100
3221       - name: mavlink_radio_type
3222         description: "Mavlink radio type. Affects how RSSI and LQ are reported on OSD."
3223         field: mavlink.radio_type
3224         table: mavlink_radio_type
3225         default_value: "GENERIC"
3226         type: uint8_t
3228   - name: PG_OSD_CONFIG
3229     type: osdConfig_t
3230     headers: ["io/osd.h", "drivers/osd.h"]
3231     condition: USE_OSD
3232     members:
3233       - name: osd_telemetry
3234         description: "To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`"
3235         table: osd_telemetry
3236         field: telemetry
3237         type: uint8_t
3238         default_value: "OFF"
3239       - name: osd_video_system
3240         description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT`"
3241         default_value: "AUTO"
3242         table: osd_video_system
3243         field: video_system
3244         type: uint8_t
3245       - name: osd_row_shiftdown
3246         description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
3247         default_value: 0
3248         field: row_shiftdown
3249         min: 0
3250         max: 1
3251       - name: osd_msp_displayport_fullframe_interval
3252         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)"
3253         default_value: 10
3254         min: -1
3255         max: 600
3256         type: int16_t
3257         field: msp_displayport_fullframe_interval
3258       - name: osd_units
3259         description: "IMPERIAL, METRIC, UK"
3260         default_value: "METRIC"
3261         field: units
3262         table: osd_unit
3263         type: uint8_t
3264       - name: osd_stats_energy_unit
3265         description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)"
3266         default_value: "MAH"
3267         field: stats_energy_unit
3268         table: osd_stats_energy_unit
3269         type: uint8_t
3270       - name: osd_stats_page_auto_swap_time
3271         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."
3272         default_value: 3
3273         field: stats_page_auto_swap_time
3274         min: 0
3275         max: 10
3276       - name: osd_stats_show_metric_efficiency
3277         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."
3278         default_value: OFF
3279         type: bool
3280         field: stats_show_metric_efficiency
3281       - name: osd_rssi_alarm
3282         description: "Value below which to make the OSD RSSI indicator blink"
3283         default_value: 20
3284         field: rssi_alarm
3285         min: 0
3286         max: 100
3287       - name: osd_time_alarm
3288         description: "Value above which to make the OSD flight time indicator blink (minutes)"
3289         default_value: 10
3290         field: time_alarm
3291         min: 0
3292         max: 600
3293       - name: osd_alt_alarm
3294         description: "Value above which to make the OSD relative altitude indicator blink (meters)"
3295         default_value: 100
3296         field: alt_alarm
3297         min: 0
3298         max: 10000
3299       - name: osd_dist_alarm
3300         description: "Value above which to make the OSD distance from home indicator blink (meters)"
3301         default_value: 1000
3302         field: dist_alarm
3303         min: 0
3304         max: 50000
3305       - name: osd_neg_alt_alarm
3306         description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
3307         default_value: 5
3308         field: neg_alt_alarm
3309         min: 0
3310         max: 10000
3311       - name: osd_current_alarm
3312         description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
3313         default_value: 0
3314         field: current_alarm
3315         min: 0
3316         max: 255
3317       - name: osd_gforce_alarm
3318         description: "Value above which the OSD g force indicator will blink (g)"
3319         default_value: 5
3320         field: gforce_alarm
3321         min: 0
3322         max: 20
3323       - name: osd_gforce_axis_alarm_min
3324         description: "Value under which the OSD axis g force indicators will blink (g)"
3325         default_value: -5
3326         field: gforce_axis_alarm_min
3327         min: -20
3328         max: 20
3329       - name: osd_gforce_axis_alarm_max
3330         description: "Value above which the OSD axis g force indicators will blink (g)"
3331         default_value: 5
3332         field: gforce_axis_alarm_max
3333         min: -20
3334         max: 20
3335       - name: osd_imu_temp_alarm_min
3336         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3337         default_value: -200
3338         field: imu_temp_alarm_min
3339         min: -550
3340         max: 1250
3341       - name: osd_imu_temp_alarm_max
3342         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3343         default_value: 600
3344         field: imu_temp_alarm_max
3345         min: -550
3346         max: 1250
3347       - name: osd_esc_temp_alarm_max
3348         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3349         default_value: 900
3350         field: esc_temp_alarm_max
3351         min: -550
3352         max: 1500
3353       - name: osd_esc_temp_alarm_min
3354         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3355         default_value: -200
3356         field: esc_temp_alarm_min
3357         min: -550
3358         max: 1500
3359       - name: osd_baro_temp_alarm_min
3360         description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3361         default_value: -200
3362         field: baro_temp_alarm_min
3363         condition: USE_BARO
3364         min: -550
3365         max: 1250
3366       - name: osd_baro_temp_alarm_max
3367         description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3368         default_value: 600
3369         field: baro_temp_alarm_max
3370         condition: USE_BARO
3371         min: -550
3372         max: 1250
3373       - name: osd_snr_alarm
3374         condition: USE_SERIALRX_CRSF || USE_RX_MSP
3375         description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
3376         default_value: 4
3377         field: snr_alarm
3378         min: -20
3379         max: 99
3380       - name: osd_link_quality_alarm
3381         condition: USE_SERIALRX_CRSF || USE_RX_MSP
3382         description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
3383         default_value: 70
3384         field: link_quality_alarm
3385         min: 0
3386         max: 100
3387       - name: osd_rssi_dbm_alarm
3388         condition: USE_SERIALRX_CRSF || USE_RX_MSP
3389         description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
3390         default_value: 0
3391         field: rssi_dbm_alarm
3392         min: -130
3393         max: 0
3394       - name: osd_rssi_dbm_max
3395         condition: USE_SERIALRX_CRSF || USE_RX_MSP
3396         description: "RSSI dBm upper end of curve. Perfect rssi (max) = 100%"
3397         default_value: -30
3398         field: rssi_dbm_max
3399         min: -50
3400         max: 0
3401       - name: osd_rssi_dbm_min
3402         condition: USE_SERIALRX_CRSF || USE_RX_MSP
3403         description: "RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%"
3404         default_value: -120
3405         field: rssi_dbm_min
3406         min: -130
3407         max: 0
3408       - name: osd_temp_label_align
3409         description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
3410         default_value: "LEFT"
3411         field: temp_label_align
3412         condition: USE_TEMPERATURE_SENSOR
3413         table: osd_alignment
3414         type: uint8_t
3415       - name: osd_airspeed_alarm_min
3416         condition: USE_PITOT
3417         description: "Airspeed under which the airspeed OSD element will start blinking (cm/s)"
3418         default_value: 0
3419         field: airspeed_alarm_min
3420         min: 0
3421         max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3422       - name: osd_airspeed_alarm_max
3423         condition: USE_PITOT
3424         description: "Airspeed above which the airspeed OSD element will start blinking (cm/s)"
3425         default_value: 0
3426         field: airspeed_alarm_max
3427         min: 0
3428         max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3429       - name: osd_ahi_reverse_roll
3430         description: "Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement."
3431         field: ahi_reverse_roll
3432         type: bool
3433         default_value: OFF
3434       - name: osd_ahi_max_pitch
3435         description: "Max pitch, in degrees, for OSD artificial horizon"
3436         default_value: 20
3437         field: ahi_max_pitch
3438         min: 10
3439         max: 90
3440         default_value: 20
3441       - name: osd_crosshairs_style
3442         description: "To set the visual type for the crosshair"
3443         default_value: "DEFAULT"
3444         field: crosshairs_style
3445         table: osd_crosshairs_style
3446         type: uint8_t
3447       - name: osd_crsf_lq_format
3448         description: "To select LQ format"
3449         default_value: "TYPE1"
3450         field: crsf_lq_format
3451         table: osd_crsf_lq_format
3452         type: uint8_t
3453       - name: osd_horizon_offset
3454         description: "To vertically adjust the whole OSD and AHI and scrolling bars"
3455         default_value: 0
3456         field: horizon_offset
3457         min: -2
3458         max: 2
3459       - name: osd_camera_uptilt
3460         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)."
3461         default_value: 0
3462         field: camera_uptilt
3463         min: -40
3464         max: 80
3465       - name: osd_ahi_camera_uptilt_comp
3466         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)."
3467         default_value: OFF
3468         field: ahi_camera_uptilt_comp
3469         type: bool
3470       - name: osd_camera_fov_h
3471         description: "Horizontal field of view for the camera in degres"
3472         default_value: 135
3473         field: camera_fov_h
3474         min: 60
3475         max: 150
3476       - name: osd_camera_fov_v
3477         description: "Vertical field of view for the camera in degres"
3478         default_value: 85
3479         field: camera_fov_v
3480         min: 30
3481         max: 120
3482       - name: osd_hud_margin_h
3483         description: "Left and right margins for the hud area"
3484         default_value: 3
3485         field: hud_margin_h
3486         min: 0
3487         max: 4
3488       - name: osd_hud_margin_v
3489         description: "Top and bottom margins for the hud area"
3490         default_value: 3
3491         field: hud_margin_v
3492         min: 1
3493         max: 3
3494       - name: osd_hud_homing
3495         description: "To display little arrows around the crossair showing where the home point is in the hud"
3496         default_value: OFF
3497         field: hud_homing
3498         type: bool
3499       - name: osd_hud_homepoint
3500         description: "To 3D-display the home point location in the hud"
3501         default_value: OFF
3502         field: hud_homepoint
3503         type: bool
3504       - name: osd_hud_radar_disp
3505         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"
3506         default_value: 0
3507         field: hud_radar_disp
3508         min: 0
3509         max: 4
3510       - name: osd_hud_radar_range_min
3511         description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
3512         default_value: 3
3513         field: hud_radar_range_min
3514         min: 1
3515         max: 30
3516       - name: osd_hud_radar_range_max
3517         description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
3518         default_value: 4000
3519         field: hud_radar_range_max
3520         min: 100
3521         max: 9990
3522       - name: osd_hud_radar_alt_difference_display_time
3523         description: "Time in seconds to display the altitude difference in radar"
3524         field: hud_radar_alt_difference_display_time
3525         min: 0
3526         max: 10
3527         default_value: 3
3528       - name: osd_hud_radar_distance_display_time
3529         description: "Time in seconds to display the distance in radar"
3530         field: hud_radar_distance_display_time
3531         min: 1
3532         max: 10
3533         default_value: 3
3534       - name: osd_radar_peers_display_time
3535         description: "Time in seconds to display next peer "
3536         field: radar_peers_display_time
3537         min: 1
3538         max: 10
3539         default_value: 3
3540       - name: osd_hud_wp_disp
3541         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)"
3542         default_value: 0
3543         field: hud_wp_disp
3544         min: 0
3545         max: 3
3546       - name: osd_left_sidebar_scroll
3547         description: "Scroll type for the left sidebar"
3548         field: left_sidebar_scroll
3549         table: osd_sidebar_scroll
3550         type: uint8_t
3551         default_value: NONE
3552       - name: osd_right_sidebar_scroll
3553         description: "Scroll type for the right sidebar"
3554         field: right_sidebar_scroll
3555         table: osd_sidebar_scroll
3556         type: uint8_t
3557         default_value: NONE
3558       - name: osd_sidebar_scroll_arrows
3559         description: "Show arrows for scrolling the sidebars"
3560         field: sidebar_scroll_arrows
3561         type: bool
3562         default_value: OFF
3563       - name: osd_main_voltage_decimals
3564         description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
3565         default_value: 1
3566         field: main_voltage_decimals
3567         min: 1
3568         max: 2
3569       - name: osd_decimals_altitude
3570         description: "Number of decimals for the altitude displayed in the OSD [3-5]."
3571         default_value: 3
3572         field: decimals_altitude
3573         type: uint8_t
3574         min: 3
3575         max: 5
3576       - name: osd_decimals_distance
3577         description: "Number of decimals for distance displayed in the OSD [3-5]. This includes distance from home, total distance, and distance remaining."
3578         default_value: 3
3579         field: decimals_distance
3580         type: uint8_t
3581         min: 3
3582         max: 5
3583       - name: osd_coordinate_digits
3584         description: "Number of digits for the coordinates displayed in the OSD [8-11]."
3585         field: coordinate_digits
3586         min: 8
3587         max: 11
3588         default_value: 9
3589       - name: osd_adsb_distance_warning
3590         description: "Distance in meters of ADSB aircraft that is displayed"
3591         default_value: 20000
3592         condition: USE_ADSB
3593         field: adsb_distance_warning
3594         min: 1
3595         max: 64000
3596         type: uint16_t
3597       - name: osd_adsb_distance_alert
3598         description: "Distance inside which ADSB data flashes for proximity warning"
3599         default_value: 3000
3600         condition: USE_ADSB
3601         field: adsb_distance_alert
3602         min: 1
3603         max: 64000
3604         type: uint16_t
3605       - name: osd_adsb_ignore_plane_above_me_limit
3606         description: "Ignore adsb planes above, limit, 0 disabled (meters)"
3607         default_value: 0
3608         condition: USE_ADSB
3609         field: adsb_ignore_plane_above_me_limit
3610         min: 0
3611         max: 64000
3612         type: uint16_t
3613       - name: osd_estimations_wind_compensation
3614         description: "Use wind estimation for remaining flight time/distance estimation"
3615         default_value: ON
3616         condition: USE_WIND_ESTIMATOR
3617         field: estimations_wind_compensation
3618         type: bool
3619       - name: osd_estimations_wind_mps
3620         description: "Wind speed estimation in m/s"
3621         default_value: OFF
3622         condition: USE_WIND_ESTIMATOR
3623         field: estimations_wind_mps
3624         type: bool
3625       - name: osd_failsafe_switch_layout
3626         description: "If enabled the OSD automatically switches to the first layout during failsafe"
3627         default_value: OFF
3628         type: bool
3629       - name: osd_plus_code_digits
3630         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."
3631         field: plus_code_digits
3632         default_value: 11
3633         min: 10
3634         max: 13
3635       - name: osd_plus_code_short
3636         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."
3637         field: plus_code_short
3638         default_value: "0"
3639         table: osd_plus_code_short
3640       - name: osd_ahi_style
3641         description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
3642         field: ahi_style
3643         default_value: "DEFAULT"
3644         table: osd_ahi_style
3645         type: uint8_t
3646       - name: osd_force_grid
3647         field: force_grid
3648         type: bool
3649         default_value: OFF
3650         description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
3651       - name: osd_ahi_bordered
3652         field: ahi_bordered
3653         type: bool
3654         description: Shows a border/corners around the AHI region (pixel OSD only)
3655         default_value: OFF
3656       - name: osd_ahi_width
3657         field: ahi_width
3658         max: 255
3659         description: AHI width in pixels (pixel OSD only)
3660         default_value: 132
3661       - name: osd_ahi_height
3662         field: ahi_height
3663         max: 255
3664         description: AHI height in pixels (pixel OSD only)
3665         default_value: 162
3666       - name: osd_ahi_vertical_offset
3667         field: ahi_vertical_offset
3668         min: -128
3669         max: 127
3670         description: AHI vertical offset from center (pixel OSD only)
3671         default_value: -18
3672       - name: osd_sidebar_horizontal_offset
3673         field: sidebar_horizontal_offset
3674         min: -128
3675         max: 127
3676         default_value: 0
3677         description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
3678       - name: osd_left_sidebar_scroll_step
3679         field: left_sidebar_scroll_step
3680         max: 255
3681         default_value: 0
3682         description: How many units each sidebar step represents. 0 means the default value for the scroll type.
3683       - name: osd_right_sidebar_scroll_step
3684         field: right_sidebar_scroll_step
3685         max: 255
3686         default_value: 0
3687         description: Same as left_sidebar_scroll_step, but for the right sidebar
3688       - name: osd_sidebar_height
3689         field: sidebar_height
3690         min: 0
3691         max: 5
3692         default_value: 3
3693         description: Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
3694       - name: osd_ahi_pitch_interval
3695         field: ahi_pitch_interval
3696         min: 0
3697         max: 30
3698         default_value: 0
3699         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)
3700       - name: osd_home_position_arm_screen
3701         type: bool
3702         default_value: ON
3703         description: Should home position coordinates be displayed on the arming screen.
3704       - name: osd_pan_servo_index
3705         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.
3706         field: pan_servo_index
3707         min: 0
3708         max: 16
3709         default_value: 0
3710       - name: osd_pan_servo_pwm2centideg
3711         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.
3712         field: pan_servo_pwm2centideg
3713         default_value: 0
3714         min: -36
3715         max: 36
3716       - name: osd_pan_servo_offcentre_warning
3717         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.
3718         field: pan_servo_offcentre_warning
3719         min: 0
3720         max: 45
3721         default_value: 10
3722       - name: osd_pan_servo_indicator_show_degrees
3723         description: Show the degress of offset from centre on the pan servo OSD display element.
3724         field: pan_servo_indicator_show_degrees
3725         type: bool
3726         default_value: OFF
3727       - name: osd_esc_rpm_precision
3728         description: Number of characters used to display the RPM value.
3729         field: esc_rpm_precision
3730         min: 3
3731         max: 6
3732         default_value: 3
3733       - name: osd_mah_precision
3734         description: Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity
3735         field: mAh_precision
3736         default: 4
3737         min: 3
3738         max: 6
3739         default_value: 4
3740       - name: osd_use_pilot_logo
3741         description: Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511
3742         field: use_pilot_logo
3743         type: bool
3744         default_value: OFF
3745       - name: osd_inav_to_pilot_logo_spacing
3746         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.
3747         field: inav_to_pilot_logo_spacing
3748         min: 0
3749         max: 20
3750         default_value: 8
3751       - name: osd_arm_screen_display_time
3752         description: Amount of time to display the arm screen [ms]
3753         field: arm_screen_display_time
3754         min: 1000
3755         max: 5000
3756         default_value: 1500
3757       - name: osd_system_msg_display_time
3758         description: System message display cycle time for multiple messages (milliseconds).
3759         field: system_msg_display_time
3760         default_value: 1000
3761         min: 500
3762         max: 5000
3763       - name: osd_highlight_djis_missing_font_symbols
3764         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.
3765         field: highlight_djis_missing_characters
3766         default_value: ON
3767         type: bool
3768       - name: osd_switch_indicator_zero_name
3769         description: "Character to use for OSD switch incicator 0."
3770         field: osd_switch_indicator0_name
3771         type: string
3772         max: 5
3773         default_value: "FLAP"
3774       - name: osd_switch_indicator_one_name
3775         description: "Character to use for OSD switch incicator 1."
3776         field: osd_switch_indicator1_name
3777         type: string
3778         max: 5
3779         default_value: "GEAR"
3780       - name: osd_switch_indicator_two_name
3781         description: "Character to use for OSD switch incicator 2."
3782         field: osd_switch_indicator2_name
3783         type: string
3784         max: 5
3785         default_value: "CAM"
3786       - name: osd_switch_indicator_three_name
3787         description: "Character to use for OSD switch incicator 3."
3788         field: osd_switch_indicator3_name
3789         type: string
3790         max: 5
3791         default_value: "LIGT"
3792       - name: osd_switch_indicator_zero_channel
3793         description: "RC Channel to use for OSD switch indicator 0."
3794         field: osd_switch_indicator0_channel
3795         min: 5
3796         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3797         default_value: 5
3798       - name: osd_switch_indicator_one_channel
3799         description: "RC Channel to use for OSD switch indicator 1."
3800         field: osd_switch_indicator1_channel
3801         min: 5
3802         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3803         default_value: 5
3804       - name: osd_switch_indicator_two_channel
3805         description: "RC Channel to use for OSD switch indicator 2."
3806         field: osd_switch_indicator2_channel
3807         min: 5
3808         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3809         default_value: 5
3810       - name: osd_switch_indicator_three_channel
3811         description: "RC Channel to use for OSD switch indicator 3."
3812         field: osd_switch_indicator3_channel
3813         min: 5
3814         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3815         default_value: 5
3816       - name: osd_switch_indicators_align_left
3817         description: "Align text to left of switch indicators"
3818         field: osd_switch_indicators_align_left
3819         type: bool
3820         default_value: ON
3821   - name: PG_OSD_COMMON_CONFIG
3822     type: osdCommonConfig_t
3823     headers: ["io/osd_common.h"]
3824     condition: USE_OSD || USE_DJI_HD_OSD
3825     members:
3826       - name: osd_speed_source
3827         description: "Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR"
3828         default_value: "GROUND"
3829         field: speedSource
3830         table: osdSpeedSource
3831         type: uint8_t
3833   - name: PG_SYSTEM_CONFIG
3834     type: systemConfig_t
3835     headers: ["fc/config.h"]
3836     members:
3837       - name: i2c_speed
3838         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)"
3839         default_value: "400KHZ"
3840         condition: USE_I2C
3841         table: i2c_speed
3842       - name: debug_mode
3843         description: "Defines debug values exposed in debug variables (developer / debugging setting)"
3844         default_value: "NONE"
3845         table: debug_modes
3846       - name: ground_test_mode
3847         description: "For developer ground test use. Disables motors, sets heading status = Trusted on FW."
3848         condition: USE_DEV_TOOLS
3849         default_value: OFF
3850         field: groundTestMode
3851         type: bool
3852       - name: throttle_tilt_comp_str
3853         description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
3854         default_value: 0
3855         field: throttle_tilt_compensation_strength
3856         min: 0
3857         max: 100
3858       - name: name
3859         description: "Craft name"
3860         default_value: ""
3861         type: string
3862         field: craftName
3863         max: MAX_NAME_LENGTH
3864       - name: pilot_name
3865         description: "Pilot name"
3866         default_value: ""
3867         type: string
3868         field: pilotName
3869         max: MAX_NAME_LENGTH
3871   - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
3872     type: modeActivationOperatorConfig_t
3873     headers: ["fc/rc_modes.h"]
3874     members:
3875       - name: mode_range_logic_operator
3876         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."
3877         default_value: "OR"
3878         field: modeActivationOperator
3879         table: aux_operator
3880         type: uint8_t
3882   - name: PG_STATS_CONFIG
3883     type: statsConfig_t
3884     headers: ["fc/stats.h"]
3885     condition: USE_STATS
3886     members:
3887       - name: stats
3888         description: "General switch of the statistics recording feature (a.k.a. odometer)"
3889         default_value: OFF
3890         field: stats_enabled
3891         type: bool
3892       - name: stats_total_time
3893         description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
3894         default_value: 0
3895         max: INT32_MAX
3896       - name: stats_total_dist
3897         description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
3898         default_value: 0
3899         max: INT32_MAX
3900       - name: stats_total_energy
3901         description: "Total energy consumption [in mWh]. The value is updated on every disarm when \"stats\" are enabled."
3902         max: INT32_MAX
3903         condition: USE_ADC
3904         default_value: 0
3906   - name: PG_TIME_CONFIG
3907     type: timeConfig_t
3908     headers: ["common/time.h"]
3909     members:
3910       - name: tz_offset
3911         description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
3912         default_value: 0
3913         min: -720
3914         max: 840
3915       - name: tz_automatic_dst
3916         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`."
3917         default_value: "OFF"
3918         type: uint8_t
3919         table: tz_automatic_dst
3921   - name: PG_DISPLAY_CONFIG
3922     type: displayConfig_t
3923     headers: ["drivers/display.h"]
3924     members:
3925       - name: display_force_sw_blink
3926         description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
3927         default_value: OFF
3928         field: force_sw_blink
3929         type: bool
3931   - name: PG_VTX_CONFIG
3932     type: vtxConfig_t
3933     headers: ["io/vtx_control.h"]
3934     condition: USE_VTX_CONTROL
3935     members:
3936       - name: vtx_halfduplex
3937         description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
3938         default_value: ON
3939         field: halfDuplex
3940         type: bool
3941       - name: vtx_smartaudio_early_akk_workaround
3942         description: "Enable workaround for early AKK SAudio-enabled VTX bug."
3943         default_value: ON
3944         field: smartAudioEarlyAkkWorkaroundEnable
3945         type: bool
3946       - name: vtx_smartaudio_alternate_softserial_method
3947         description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier."
3948         default_value: ON
3949         field: smartAudioAltSoftSerialMethod
3950         type: bool
3951       - name: vtx_softserial_shortstop
3952         description: "Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes."
3953         default_value: OFF
3954         field: softSerialShortStop
3955         type: bool
3956       - name: vtx_smartaudio_stopbits
3957         description: "Set stopbit count for serial (TBS Sixty9 SmartAudio 2.1 require value of 1 bit)"
3958         default_value: 2
3959         field: smartAudioStopBits
3960         min: 1
3961         max: 2
3963   - name: PG_VTX_SETTINGS_CONFIG
3964     type: vtxSettingsConfig_t
3965     headers: ["drivers/vtx_common.h", "io/vtx.h"]
3966     condition: USE_VTX_SMARTAUDIO || USE_VTX_TRAMP
3967     members:
3968       - name: vtx_band
3969         description: "Configure the VTX band. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
3970         default_value: 1
3971         field: band
3972         min: VTX_SETTINGS_MIN_BAND
3973         max: VTX_SETTINGS_MAX_BAND
3974       - name: vtx_channel
3975         description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
3976         default_value: 1
3977         field: channel
3978         min: VTX_SETTINGS_MIN_CHANNEL
3979         max: VTX_SETTINGS_MAX_CHANNEL
3980       - name: vtx_power
3981         description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
3982         default_value: 1
3983         field: power
3984         min: VTX_SETTINGS_MIN_POWER
3985         max: VTX_SETTINGS_MAX_POWER
3986       - name: vtx_low_power_disarm
3987         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."
3988         default_value: "OFF"
3989         field: lowPowerDisarm
3990         table: vtx_low_power_disarm
3991         type: uint8_t
3992       - name: vtx_pit_mode_chan
3993         description: "Pit mode channel."
3994         field: pitModeChan
3995         min: VTX_SETTINGS_MIN_CHANNEL
3996         max: VTX_SETTINGS_MAX_CHANNEL
3997         default_value: 1
3998       - name: vtx_max_power_override
3999         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"
4000         default_value: 0
4001         field: maxPowerOverride
4002         min: 0
4003         max: 10000
4004       - name: vtx_frequency_group
4005         field: frequencyGroup
4006         description: "VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz."
4007         table: vtx_frequency_groups
4008         min: 0
4009         max: 2
4010         default_value: FREQUENCYGROUP_5G8
4012   - name: PG_PINIOBOX_CONFIG
4013     type: pinioBoxConfig_t
4014     headers: ["io/piniobox.h"]
4015     condition: USE_PINIOBOX
4016     members:
4017       - name: pinio_box1
4018         field: permanentId[0]
4019         description: "Mode assignment for PINIO#1"
4020         default_value: "target specific"
4021         min: 0
4022         max: 255
4023         default_value: :BOX_PERMANENT_ID_NONE
4024         type: uint8_t
4025       - name: pinio_box2
4026         field: permanentId[1]
4027         default_value: "target specific"
4028         description: "Mode assignment for PINIO#1"
4029         min: 0
4030         max: 255
4031         default_value: :BOX_PERMANENT_ID_NONE
4032         type: uint8_t
4033       - name: pinio_box3
4034         field: permanentId[2]
4035         default_value: "target specific"
4036         description: "Mode assignment for PINIO#1"
4037         min: 0
4038         max: 255
4039         default_value: :BOX_PERMANENT_ID_NONE
4040         type: uint8_t
4041       - name: pinio_box4
4042         field: permanentId[3]
4043         default_value: "target specific"
4044         description: "Mode assignment for PINIO#1"
4045         min: 0
4046         max: 255
4047         default_value: :BOX_PERMANENT_ID_NONE
4048         type: uint8_t
4050   - name: PG_LOG_CONFIG
4051     type: logConfig_t
4052     headers: ["common/log.h"]
4053     condition: USE_LOG
4054     members:
4055         - name: log_level
4056           field: level
4057           table: log_level
4058           description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
4059           default_value: "ERROR"
4060         - name: log_topics
4061           field: topics
4062           min: 0
4063           max: UINT32_MAX
4064           description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
4065           default_value: 0
4067   - name: PG_ESC_SENSOR_CONFIG
4068     type: escSensorConfig_t
4069     headers: ["sensors/esc_sensor.h"]
4070     condition: USE_ESC_SENSOR
4071     members:
4072         - name: esc_sensor_listen_only
4073           default_value: OFF
4074           description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
4075           field: listenOnly
4076           type: bool
4077           default_value: OFF
4079   - name: PG_SMARTPORT_MASTER_CONFIG
4080     type: smartportMasterConfig_t
4081     headers: ["io/smartport_master.h"]
4082     condition: USE_SMARTPORT_MASTER
4083     members:
4084       - name: smartport_master_halfduplex
4085         field: halfDuplex
4086         type: bool
4087         default_value: ON
4088       - name: smartport_master_inverted
4089         field: inverted
4090         type: bool
4091         default_value: OFF
4093   - name: PG_DJI_OSD_CONFIG
4094     type: djiOsdConfig_t
4095     headers: ["io/osd_dji_hd.h"]
4096     condition: USE_DJI_HD_OSD
4097     members:
4098         - name: dji_use_name_for_messages
4099           description: "Re-purpose the craft name field for messages."
4100           default_value: ON
4101           field: use_name_for_messages
4102           type: bool
4103         - name: dji_esc_temp_source
4104           description: "Re-purpose the ESC temperature field for IMU/BARO temperature"
4105           default_value: "ESC"
4106           field: esc_temperature_source
4107           table: djiOsdTempSource
4108           type: uint8_t
4109         - name: dji_message_speed_source
4110           description: "Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR"
4111           default_value: "3D"
4112           field: messageSpeedSource
4113           table: osdSpeedSource
4114           type: uint8_t
4115         - name: dji_rssi_source
4116           description: "Source of the DJI RSSI field: RSSI, CRSF_LQ"
4117           default_value: "RSSI"
4118           field: rssi_source
4119           table: djiRssiSource
4120           type: uint8_t
4121         - name: dji_use_adjustments
4122           description: "Show inflight adjustments in craft name field"
4123           default_value: OFF
4124           type: bool
4125           field: useAdjustments
4126         - name: dji_cn_alternating_duration
4127           description: "Alternating duration of craft name elements, in tenths of a second"
4128           default_value: 30
4129           min: 1
4130           max: 150
4131           field: craftNameAlternatingDuration
4132           type: uint8_t
4134   - name: PG_BEEPER_CONFIG
4135     type: beeperConfig_t
4136     headers: [ "fc/config.h" ]
4137     members:
4138       - name: dshot_beeper_enabled
4139         description: "Whether using DShot motors as beepers is enabled"
4140         default_value: ON
4141         field: dshot_beeper_enabled
4142         type: bool
4143       - name: dshot_beeper_tone
4144         description: "Sets the DShot beeper tone"
4145         min: 1
4146         max: 5
4147         default_value: 1
4148         field: dshot_beeper_tone
4149         type: uint8_t
4150       - name: beeper_pwm_mode
4151         field: pwmMode
4152         type: bool
4153         default_value: OFF
4154         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"
4156   - name: PG_POWER_LIMITS_CONFIG
4157     type: powerLimitsConfig_t
4158     headers: ["flight/power_limits.h"]
4159     condition: USE_POWER_LIMITS
4160     members:
4161       - name: limit_pi_p
4162         description: "Throttle attenuation PI control P term"
4163         default_value: 100
4164         field: piP
4165         max: 10000
4166       - name: limit_pi_i
4167         description: "Throttle attenuation PI control I term"
4168         default_value: 100
4169         field: piI
4170         max: 10000
4171       - name: limit_attn_filter_cutoff
4172         description: "Throttle attenuation PI control output filter cutoff frequency"
4173         default_value: 1.2
4174         field: attnFilterCutoff
4175         max: 100
4177   - name: PG_LEDPIN_CONFIG
4178     type: ledPinConfig_t
4179     headers: ["drivers/light_ws2811strip.h"]
4180     members:
4181       - name: led_pin_pwm_mode
4182         condition: USE_LED_STRIP
4183         description: "PWM mode of LED pin."
4184         default_value: "SHARED_LOW"
4185         field: led_pin_pwm_mode
4186         table: led_pin_pwm_mode
4188   - name: PG_OSD_JOYSTICK_CONFIG
4189     type: osdJoystickConfig_t
4190     headers: ["io/osd_joystick.h"]
4191     condition: USE_RCDEVICE && USE_LED_STRIP
4192     members:
4193       - name: osd_joystick_enabled
4194         description: "Enable OSD Joystick emulation"
4195         default_value: OFF
4196         field: osd_joystick_enabled
4197         type: bool
4198       - name: osd_joystick_down
4199         description: "PWM value for DOWN key"
4200         default_value: 0
4201         field: osd_joystick_down
4202         min: 0
4203         max: 100
4204       - name: osd_joystick_up
4205         description: "PWM value for UP key"
4206         default_value: 48
4207         field: osd_joystick_up
4208         min: 0
4209         max: 100
4210       - name: osd_joystick_left
4211         description: "PWM value for LEFT key"
4212         default_value: 63
4213         field: osd_joystick_left
4214         min: 0
4215         max: 100
4216       - name: osd_joystick_right
4217         description: "PWM value for RIGHT key"
4218         default_value: 28
4219         field: osd_joystick_right
4220         min: 0
4221         max: 100
4222       - name: osd_joystick_enter
4223         description: "PWM value for ENTER key"
4224         default_value: 75
4225         field: osd_joystick_enter
4226         min: 0
4227         max: 100
4229   - name: PG_FW_AUTOLAND_CONFIG
4230     type: navFwAutolandConfig_t
4231     headers: ["navigation/navigation.h"]
4232     condition: USE_FW_AUTOLAND
4233     members:
4234       - name: nav_fw_land_approach_length
4235         description: "Length of the final approach"
4236         default_value: 35000
4237         field: approachLength
4238         min: 100
4239         max: 100000
4240       - name: nav_fw_land_final_approach_pitch2throttle_mod
4241         description: "Modifier for pitch to throttle ratio at final approach. In Percent."
4242         default_value: 100
4243         field: finalApproachPitchToThrottleMod
4244         min: 100
4245         max: 400
4246       - name: nav_fw_land_glide_alt
4247         description: "Initial altitude of the glide phase"
4248         default_value: 200
4249         field: glideAltitude
4250         min: 100
4251         max: 5000
4252       - name: nav_fw_land_flare_alt
4253         description: "Initial altitude of the flare phase"
4254         default_value: 150
4255         field: flareAltitude
4256         min: 0
4257         max: 10000
4258       - name: nav_fw_land_glide_pitch
4259         description: "Pitch value for glide phase. In degrees."
4260         default_value: 0
4261         field: glidePitch
4262         min: -15
4263         max: 45
4264       - name: nav_fw_land_flare_pitch
4265         description: "Pitch value for flare phase. In degrees"
4266         default_value: 8
4267         field: flarePitch
4268         min: -15
4269         max: 45
4270       - name: nav_fw_land_max_tailwind
4271         description: "Max. tailwind (in cm/s) if no landing direction with downwind is available"
4272         default_value: 140
4273         field: maxTailwind
4274         min: 0
4275         max: 3000
4276   - name: PG_GIMBAL_CONFIG
4277     type: gimbalConfig_t
4278     headers: ["drivers/gimbal_common.h"]
4279     condition: USE_SERIAL_GIMBAL
4280     members:
4281       - name: gimbal_pan_channel
4282         description: "Gimbal pan rc channel index. 0 is no channel."
4283         default_value: 0
4284         field: panChannel
4285         min: 0
4286         max: 32
4287       - name: gimbal_roll_channel
4288         description: "Gimbal roll rc channel index. 0 is no channel."
4289         default_value: 0
4290         field: rollChannel
4291         min: 0
4292         max: 32
4293       - name: gimbal_tilt_channel
4294         description: "Gimbal tilt rc channel index. 0 is no channel."
4295         default_value: 0
4296         field: tiltChannel
4297         min: 0
4298         max: 32
4299       - name: gimbal_sensitivity
4300         description: "Gimbal sensitivity is similar to gain and will affect how quickly the gimbal will react."
4301         default_value: 0
4302         field: sensitivity
4303         min: -16
4304         max: 15
4305       - name: gimbal_pan_trim
4306         field: panTrim
4307         description: "Trim gimbal pan center position."
4308         default_value: 0
4309         min: -500
4310         max: 500
4311       - name: gimbal_tilt_trim
4312         field: tiltTrim
4313         description: "Trim gimbal tilt center position."
4314         default_value: 0
4315         min: -500
4316         max: 500
4317       - name: gimbal_roll_trim
4318         field: rollTrim
4319         description: "Trim gimbal roll center position."
4320         default_value: 0
4321         min: -500
4322         max: 500
4323   - name: PG_GIMBAL_SERIAL_CONFIG
4324     type: gimbalSerialConfig_t
4325     headers: ["io/gimbal_serial.h"]
4326     condition: USE_SERIAL_GIMBAL
4327     members:
4328     - name: gimbal_serial_single_uart
4329       description: "Gimbal serial and headtracker device share same UART. FC RX goes to headtracker device, FC TX goes to gimbal."
4330       type: bool
4331       default_value: OFF
4332       field: singleUart
4333   - name: PG_HEADTRACKER_CONFIG
4334     type: headTrackerConfig_t
4335     headers: ["drivers/headtracker_common.h"]
4336     condition: USE_HEADTRACKER
4337     members:
4338     - name: headtracker_type
4339       description: "Type of headtrackr dervice"
4340       default_value: "NONE"
4341       field: devType
4342       type: uint8_t
4343       table: headtracker_dev_type
4344     - name: headtracker_pan_ratio
4345       description: "Head pan movement vs camera movement ratio"
4346       type: float
4347       default_value: 1
4348       field: pan_ratio
4349       min: 0
4350       max: 5
4351     - name: headtracker_tilt_ratio
4352       description: "Head tilt movement vs camera movement ratio"
4353       type: float
4354       default_value: 1
4355       field: tilt_ratio
4356       min: 0
4357       max: 5
4358     - name: headtracker_roll_ratio
4359       description: "Head roll movement vs camera movement ratio"
4360       type: float
4361       default_value: 1
4362       field: roll_ratio
4363       min: 0
4364       max: 5