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