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