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