Merge remote-tracking branch 'upstream/master' into abo_fw_alt_vel_control
[inav.git] / src / main / fc / settings.yaml
blob61b0c23bbe468e91c8c4b15024b162fd1aaea6d1
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","AUTOMOTIVE", "AIR_1G", "AIR_2G", "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: "NONE"
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
841       - name: failsafe_gps_fix_estimation_delay
842         description: "Controls whether waypoint mission is allowed to proceed with gps fix estimation. Sets the time delay in seconds between gps fix lost event and RTH activation. Minimum delay is 7 seconds. If set to -1 the mission will continue until the end. With default setting(7), waypoint mission is aborted and switched to RTH with 7 seconds delay. RTH is done with GPS Fix estimation."
843         condition: USE_GPS_FIX_ESTIMATION
844         default_value: 7
845         min: -1
846         max: 600
848   - name: PG_LIGHTS_CONFIG
849     type: lightsConfig_t
850     headers: ["io/lights.h"]
851     condition: USE_LIGHTS
852     members:
853       - name: failsafe_lights
854         description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
855         default_value: ON
856         field: failsafe.enabled
857         type: bool
858       - name: failsafe_lights_flash_period
859         description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
860         default_value: 1000
861         field: failsafe.flash_period
862         min: 40
863         max: 65535
864       - name: failsafe_lights_flash_on_time
865         description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
866         default_value: 100
867         field: failsafe.flash_on_time
868         min: 20
869         max: 65535
871   - name: PG_BOARD_ALIGNMENT
872     type: boardAlignment_t
873     headers: ["sensors/boardalignment.h"]
874     members:
875       - name: align_board_roll
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: rollDeciDegrees
879         min: -1800
880         max: 3600
881       - name: align_board_pitch
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: pitchDeciDegrees
885         min: -1800
886         max: 3600
887       - name: align_board_yaw
888         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
889         default_value: :zero
890         field: yawDeciDegrees
891         min: -1800
892         max: 3600
894   - name: PG_BATTERY_METERS_CONFIG
895     type: batteryMetersConfig_t
896     headers: ["sensors/battery_config_structs.h"]
897     members:
898       - name: vbat_meter_type
899         description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
900         condition: USE_ADC
901         default_value: ADC
902         field: voltage.type
903         table: voltage_sensor
904         type: uint8_t
905       - name: vbat_scale
906         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."
907         default_value: :target
908         field: voltage.scale
909         condition: USE_ADC
910         min: 0
911         max: 65535
912       - name: current_meter_scale
913         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."
914         default_value: :target
915         field: current.scale
916         min: -10000
917         max: 10000
918       - name: current_meter_offset
919         description: "This sets the output offset voltage of the current sensor in millivolts."
920         default_value: :target
921         field: current.offset
922         min: -32768
923         max: 32767
924       - name: current_meter_type
925         description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position."
926         default_value: "ADC"
927         field: current.type
928         table: current_sensor
929         type: uint8_t
930       - name: bat_voltage_src
931         description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`"
932         default_value: "RAW"
933         field: voltageSource
934         table: bat_voltage_source
935         type: uint8_t
936       - name: cruise_power
937         description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
938         default_value: 0
939         field: cruise_power
940         min: 0
941         max: 4294967295
942       - name: idle_power
943         description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
944         default_value: 0
945         field: idle_power
946         min: 0
947         max: 65535
948       - name: rth_energy_margin
949         description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
950         default_value: 5
951         min: 0
952         max: 100
953       - name: thr_comp_weight
954         description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
955         default_value: 1
956         field: throttle_compensation_weight
957         min: 0
958         max: 2
960   - name: PG_BATTERY_PROFILES
961     type: batteryProfile_t
962     headers: ["sensors/battery_config_structs.h"]
963     value_type: BATTERY_CONFIG_VALUE
964     members:
965       - name: bat_cells
966         description: "Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected."
967         default_value: 0
968         field: cells
969         condition: USE_ADC
970         min: 0
971         max: 12
972       - name: vbat_cell_detect_voltage
973         description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units."
974         default_value: 425
975         field: voltage.cellDetect
976         condition: USE_ADC
977         min: 100
978         max: 500
979       - name: vbat_max_cell_voltage
980         description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
981         default_value: 420
982         field: voltage.cellMax
983         condition: USE_ADC
984         min: 100
985         max: 500
986       - name: vbat_min_cell_voltage
987         description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
988         default_value: 330
989         field: voltage.cellMin
990         condition: USE_ADC
991         min: 100
992         max: 500
993       - name: vbat_warning_cell_voltage
994         description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
995         default_value: 350
996         field: voltage.cellWarning
997         condition: USE_ADC
998         min: 100
999         max: 500
1000       - name: battery_capacity
1001         description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
1002         default_value: 0
1003         field: capacity.value
1004         min: 0
1005         max: 4294967295
1006       - name: battery_capacity_warning
1007         description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
1008         default_value: 0
1009         field: capacity.warning
1010         min: 0
1011         max: 4294967295
1012       - name: battery_capacity_critical
1013         description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
1014         default_value: 0
1015         field: capacity.critical
1016         min: 0
1017         max: 4294967295
1018       - name: battery_capacity_unit
1019         description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)."
1020         default_value: "MAH"
1021         field: capacity.unit
1022         table: bat_capacity_unit
1023         type: uint8_t
1024       - name: controlrate_profile
1025         description: "Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile"
1026         default_value: 0
1027         field: controlRateProfile
1028         min: 0
1029         max: MAX_CONTROL_RATE_PROFILE_COUNT
1031       - name: throttle_scale
1032         description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
1033         default_value: 1.0
1034         field: motor.throttleScale
1035         min: 0
1036         max: 1
1037       - name: throttle_idle
1038         description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
1039         default_value: 8
1040         field: motor.throttleIdle
1041         min: 0
1042         max: 30
1043       - name: turtle_mode_power_factor
1044         field: motor.turtleModePowerFactor
1045         default_value: 55
1046         description: "Turtle mode power factor"
1047         condition: USE_DSHOT
1048         min: 0
1049         max: 100
1050       - name: failsafe_throttle
1051         description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
1052         default_value: 1000
1053         min: PWM_RANGE_MIN
1054         max: PWM_RANGE_MAX
1055       - name: nav_mc_hover_thr
1056         description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
1057         default_value: 1300
1058         field: nav.mc.hover_throttle
1059         min: 1000
1060         max: 2000
1061       - name: nav_fw_cruise_thr
1062         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 )"
1063         default_value: 1400
1064         field: nav.fw.cruise_throttle
1065         min: 1000
1066         max: 2000
1067       - name: nav_fw_min_thr
1068         description: "Minimum throttle for flying wing in GPS assisted modes"
1069         default_value: 1200
1070         field: nav.fw.min_throttle
1071         min: 1000
1072         max: 2000
1073       - name: nav_fw_max_thr
1074         description: "Maximum throttle for flying wing in GPS assisted modes"
1075         default_value: 1700
1076         field: nav.fw.max_throttle
1077         min: 1000
1078         max: 2000
1079       - name: nav_fw_pitch2thr
1080         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)"
1081         default_value: 10
1082         field: nav.fw.pitch_to_throttle
1083         min: 0
1084         max: 100
1085       - name: nav_fw_launch_thr
1086         description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
1087         default_value: 1700
1088         field: nav.fw.launch_throttle
1089         min: 1000
1090         max: 2000
1091       - name: nav_fw_launch_idle_thr
1092         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)"
1093         default_value: 1000
1094         field: nav.fw.launch_idle_throttle
1095         min: 1000
1096         max: 2000
1097       - name: limit_cont_current
1098         description: "Continous current limit (dA), set to 0 to disable"
1099         condition: USE_POWER_LIMITS
1100         default_value: 0
1101         field: powerLimits.continuousCurrent
1102         max: 4000
1103       - name: limit_burst_current
1104         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"
1105         condition: USE_POWER_LIMITS
1106         default_value: 0
1107         field: powerLimits.burstCurrent
1108         max: 4000
1109       - name: limit_burst_current_time
1110         description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced"
1111         condition: USE_POWER_LIMITS
1112         default_value: 0
1113         field: powerLimits.burstCurrentTime
1114         max: 3000
1115       - name: limit_burst_current_falldown_time
1116         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`"
1117         condition: USE_POWER_LIMITS
1118         default_value: 0
1119         field: powerLimits.burstCurrentFalldownTime
1120         max: 3000
1121       - name: limit_cont_power
1122         description: "Continous power limit (dW), set to 0 to disable"
1123         condition: USE_POWER_LIMITS && USE_ADC
1124         default_value: 0
1125         field: powerLimits.continuousPower
1126         max: 40000
1127       - name: limit_burst_power
1128         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"
1129         condition: USE_POWER_LIMITS && USE_ADC
1130         default_value: 0
1131         field: powerLimits.burstPower
1132         max: 40000
1133       - name: limit_burst_power_time
1134         description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced"
1135         condition: USE_POWER_LIMITS && USE_ADC
1136         default_value: 0
1137         field: powerLimits.burstPowerTime
1138         max: 3000
1139       - name: limit_burst_power_falldown_time
1140         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`"
1141         condition: USE_POWER_LIMITS && USE_ADC
1142         default_value: 0
1143         field: powerLimits.burstPowerFalldownTime
1144         max: 3000
1146   - name: PG_MIXER_PROFILE
1147     type: mixerProfile_t
1148     headers: ["flight/mixer_profile.h"]
1149     value_type: MIXER_CONFIG_VALUE
1150     members:
1151       - name: motor_direction_inverted
1152         description: "Use if you need to inverse yaw motor direction."
1153         default_value: OFF
1154         field: mixer_config.motorDirectionInverted
1155         type: bool
1156       - name: platform_type
1157         description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
1158         default_value: "MULTIROTOR"
1159         field: mixer_config.platformType
1160         type: uint8_t
1161         table: platform_type
1162       - name: has_flaps
1163         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"
1164         default_value: OFF
1165         field: mixer_config.hasFlaps
1166         type: bool
1167       - name: model_preview_type
1168         description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
1169         default_value: -1
1170         field: mixer_config.appliedMixerPreset
1171         min: -1
1172         max: INT16_MAX
1173       - name: motorstop_on_low
1174         description: "If enabled, motor will stop when throttle is low on this mixer_profile"
1175         default_value: OFF
1176         field: mixer_config.motorstopOnLow
1177         type: bool
1178       - name: mixer_pid_profile_linking
1179         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."
1180         default_value: OFF
1181         field: mixer_config.PIDProfileLinking
1182         type: bool
1183       - name: mixer_automated_switch
1184         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"
1185         default_value: OFF
1186         field: mixer_config.automated_switch
1187         type: bool
1188       - name: mixer_switch_trans_timer
1189         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."
1190         default_value: 0
1191         field: mixer_config.switchTransitionTimer
1192         min: 0
1193         max: 200
1194       - name: tailsitter_orientation_offset
1195         description: "Apply a 90 deg pitch offset in sensor aliment for tailsitter flying mode"
1196         default_value: OFF
1197         field: mixer_config.tailsitterOrientationOffset
1198         type: bool
1202   - name: PG_REVERSIBLE_MOTORS_CONFIG
1203     type: reversibleMotorsConfig_t
1204     members:
1205       - name: 3d_deadband_low
1206         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)"
1207         default_value: 1406
1208         field: deadband_low
1209         min: PWM_RANGE_MIN
1210         max: PWM_RANGE_MAX
1211       - name: 3d_deadband_high
1212         description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
1213         default_value: 1514
1214         field: deadband_high
1215         min: PWM_RANGE_MIN
1216         max: PWM_RANGE_MAX
1217       - name: 3d_neutral
1218         description: "Neutral (stop) throttle value for 3D mode"
1219         default_value: 1460
1220         field: neutral
1221         min: PWM_RANGE_MIN
1222         max: PWM_RANGE_MAX
1224   - name: PG_SERVO_CONFIG
1225     type: servoConfig_t
1226     headers: ["flight/servos.h"]
1227     members:
1228       - name: servo_protocol
1229         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)"
1230         default_value: "PWM"
1231         field: servo_protocol
1232         table: servo_protocol
1233       - name: servo_center_pulse
1234         description: "Servo midpoint"
1235         default_value: 1500
1236         field: servoCenterPulse
1237         min: PWM_RANGE_MIN
1238         max: PWM_RANGE_MAX
1239       - name: servo_pwm_rate
1240         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."
1241         default_value: 50
1242         field: servoPwmRate
1243         min: 50
1244         max: 498
1245       - name: servo_lpf_hz
1246         description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
1247         default_value: 20
1248         field: servo_lowpass_freq
1249         min: 0
1250         max: 400
1251       - name: flaperon_throw_offset
1252         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."
1253         default_value: 200
1254         min: FLAPERON_THROW_MIN
1255         max: FLAPERON_THROW_MAX
1256       - name: tri_unarmed_servo
1257         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."
1258         default_value: ON
1259         type: bool
1260       - name: servo_autotrim_rotation_limit
1261         description: "Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`."
1262         default_value: 15
1263         min: 1
1264         max: 60
1266   - name: PG_CONTROL_RATE_PROFILES
1267     type: controlRateConfig_t
1268     headers: ["fc/controlrate_profile_config_struct.h"]
1269     value_type: CONTROL_RATE_VALUE
1270     members:
1271       - name: thr_mid
1272         description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
1273         default_value: 50
1274         field: throttle.rcMid8
1275         min: 0
1276         max: 100
1277       - name: thr_expo
1278         description: "Throttle exposition value"
1279         default_value: 0
1280         field: throttle.rcExpo8
1281         min: 0
1282         max: 100
1283       - name: tpa_rate
1284         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."
1285         default_value: 0
1286         field: throttle.dynPID
1287         min: 0
1288         max: 100
1289       - name: tpa_breakpoint
1290         description: "See tpa_rate."
1291         default_value: 1500
1292         field: throttle.pa_breakpoint
1293         min: PWM_RANGE_MIN
1294         max: PWM_RANGE_MAX
1295       - name: tpa_on_yaw
1296         description: "Throttle PID attenuation also reduces influence on YAW for multi-rotor, Should be set to ON for tilting rotors."
1297         type: bool
1298         field: throttle.dynPID_on_YAW
1299         default_value: OFF
1300       - name: fw_tpa_time_constant
1301         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."
1302         default_value: 1500
1303         field: throttle.fixedWingTauMs
1304         min: 0
1305         max: 5000
1306       - name: rc_expo
1307         description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
1308         default_value: 70
1309         field: stabilized.rcExpo8
1310         min: 0
1311         max: 100
1312       - name: rc_yaw_expo
1313         description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
1314         default_value: 20
1315         field: stabilized.rcYawExpo8
1316         min: 0
1317         max: 100
1318       # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
1319       # Rate 180 (1800dps) is max. value gyro can measure reliably
1320       - name: roll_rate
1321         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."
1322         default_value: 20
1323         field: stabilized.rates[FD_ROLL]
1324         min: ROLL_PITCH_RATE_MIN
1325         max: ROLL_PITCH_RATE_MAX
1326       - name: pitch_rate
1327         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."
1328         default_value: 20
1329         field: stabilized.rates[FD_PITCH]
1330         min: ROLL_PITCH_RATE_MIN
1331         max: ROLL_PITCH_RATE_MAX
1332       - name: yaw_rate
1333         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."
1334         default_value: 20
1335         field: stabilized.rates[FD_YAW]
1336         min: 1
1337         max: 180
1338       - name: manual_rc_expo
1339         description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
1340         default_value: 35
1341         field: manual.rcExpo8
1342         min: 0
1343         max: 100
1344       - name: manual_rc_yaw_expo
1345         description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
1346         default_value: 20
1347         field: manual.rcYawExpo8
1348         min: 0
1349         max: 100
1350       - name: manual_roll_rate
1351         description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
1352         default_value: 100
1353         field: manual.rates[FD_ROLL]
1354         min: MANUAL_RATE_MIN
1355         max: MANUAL_RATE_MAX
1356       - name: manual_pitch_rate
1357         description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
1358         default_value: 100
1359         field: manual.rates[FD_PITCH]
1360         min: MANUAL_RATE_MIN
1361         max: MANUAL_RATE_MAX
1362       - name: manual_yaw_rate
1363         description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
1364         default_value: 100
1365         field: manual.rates[FD_YAW]
1366         min: MANUAL_RATE_MIN
1367         max: MANUAL_RATE_MAX
1368       - name: fpv_mix_degrees
1369         field: misc.fpvCamAngleDegrees
1370         min: 0
1371         max: 50
1372         default_value: 0
1373       - name: rate_dynamics_center_sensitivity
1374         field: rateDynamics.sensitivityCenter
1375         default_value: 100
1376         min: 25
1377         max: 175
1378         description: "The center stick sensitivity for Rate Dynamics"
1379         condition: USE_RATE_DYNAMICS
1380       - name: rate_dynamics_end_sensitivity
1381         field: rateDynamics.sensitivityEnd
1382         default_value: 100
1383         min: 25
1384         max: 175
1385         description: "The end stick sensitivity for Rate Dynamics"
1386         condition: USE_RATE_DYNAMICS
1387       - name: rate_dynamics_center_correction
1388         field: rateDynamics.correctionCenter
1389         default_value: 10
1390         min: 10
1391         max: 95
1392         description: "The center stick correction for Rate Dynamics"
1393         condition: USE_RATE_DYNAMICS
1394       - name: rate_dynamics_end_correction
1395         field: rateDynamics.correctionEnd
1396         default_value: 10
1397         min: 10
1398         max: 95
1399         description: "The end  stick correction for Rate Dynamics"
1400         condition: USE_RATE_DYNAMICS
1401       - name: rate_dynamics_center_weight
1402         field: rateDynamics.weightCenter
1403         default_value: 0
1404         min: 0
1405         max: 95
1406         description: "The center stick weight for Rate Dynamics"
1407         condition: USE_RATE_DYNAMICS
1408       - name: rate_dynamics_end_weight
1409         field: rateDynamics.weightEnd
1410         default_value: 0
1411         min: 0
1412         max: 95
1413         description: "The end  stick weight for Rate Dynamics"
1414         condition: USE_RATE_DYNAMICS
1416   - name: PG_SERIAL_CONFIG
1417     type: serialConfig_t
1418     headers: ["io/serial.h"]
1419     members:
1420       - name: reboot_character
1421         description: "Special character used to trigger reboot"
1422         default_value: 82
1423         min: 48
1424         max: 126
1426   - name: PG_IMU_CONFIG
1427     type: imuConfig_t
1428     headers: ["flight/imu.h"]
1429     members:
1430       - name: ahrs_dcm_kp
1431         description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
1432         default_value: 2000
1433         field: dcm_kp_acc
1434         max: UINT16_MAX
1435       - name: ahrs_dcm_ki
1436         description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
1437         default_value: 50
1438         field: dcm_ki_acc
1439         max: UINT16_MAX
1440       - name: ahrs_dcm_kp_mag
1441         description: "Inertial Measurement Unit KP Gain for compass measurements"
1442         default_value: 2000
1443         field: dcm_kp_mag
1444         max: UINT16_MAX
1445       - name: ahrs_dcm_ki_mag
1446         description: "Inertial Measurement Unit KI Gain for compass measurements"
1447         default_value: 50
1448         field: dcm_ki_mag
1449         max: UINT16_MAX
1450       - name: small_angle
1451         description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
1452         default_value: 25
1453         min: 0
1454         max: 180
1455       - name: ahrs_acc_ignore_rate
1456         description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy"
1457         default_value: 15
1458         field: acc_ignore_rate
1459         min: 0
1460         max: 30
1461       - name: ahrs_acc_ignore_slope
1462         description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
1463         default_value: 5
1464         field: acc_ignore_slope
1465         min: 0
1466         max: 10
1467       - name: ahrs_gps_yaw_windcomp
1468         description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)"
1469         default_value: ON
1470         field: gps_yaw_windcomp
1471         type: bool
1472       - name: ahrs_inertia_comp_method
1473         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"
1474         default_value: ADAPTIVE
1475         field: inertia_comp_method
1476         table: imu_inertia_comp_method
1477       - name: ahrs_gps_yaw_weight
1478         description: "Arhs gps yaw weight when mag is avaliable, 0 means no gps yaw, 100 means equal weight as compass"
1479         default_value: 100
1480         field: gps_yaw_weight
1481         min: 0
1482         max: 500
1484   - name: PG_ARMING_CONFIG
1485     type: armingConfig_t
1486     members:
1487       - name: fixed_wing_auto_arm
1488         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."
1489         default_value: OFF
1490         type: bool
1491       - name: disarm_kill_switch
1492         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."
1493         default_value: ON
1494         type: bool
1495       - name: switch_disarm_delay
1496         description: "Delay before disarming when requested by switch (ms) [0-1000]"
1497         default_value: 250
1498         field: switchDisarmDelayMs
1499         min: 0
1500         max: 1000
1501       - name: prearm_timeout
1502         description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
1503         default_value: 10000
1504         field: prearmTimeoutMs
1505         min: 0
1506         max: 10000
1508   - name: PG_GENERAL_SETTINGS
1509     headers: ["config/general_settings.h"]
1510     type: generalSettings_t
1511     members:
1512       - name: applied_defaults
1513         description: "Internal (configurator) hint. Should not be changed manually"
1514         default_value: 0
1515         field: appliedDefaults
1516         type: uint8_t
1517         min: 0
1518         max: 99
1520   - name: PG_EZ_TUNE
1521     headers: ["flight/ez_tune.h"]
1522     type: ezTuneSettings_t
1523     value_type: EZ_TUNE_VALUE
1524     members:
1525       - name: ez_enabled
1526         description: "Enables EzTune feature"
1527         default_value: OFF
1528         field: enabled
1529         type: bool
1530       - name: ez_filter_hz
1531         description: "EzTune filter cutoff frequency"
1532         default_value: 110
1533         field: filterHz
1534         min: 10
1535         max: 300
1536       - name: ez_axis_ratio
1537         description: "EzTune axis ratio"
1538         default_value: 110
1539         field: axisRatio
1540         min: 25
1541         max: 175
1542       - name: ez_response
1543         description: "EzTune response"
1544         default_value: 100
1545         field: response
1546         min: 0
1547         max: 200
1548       - name: ez_damping
1549         description: "EzTune damping"
1550         default_value: 100
1551         field: damping
1552         min: 0
1553         max: 200
1554       - name: ez_stability
1555         description: "EzTune stability"
1556         default_value: 100
1557         field: stability
1558         min: 0
1559         max: 200
1560       - name: ez_aggressiveness
1561         description: "EzTune aggressiveness"
1562         default_value: 100
1563         field: aggressiveness
1564         min: 0
1565         max: 200
1566       - name: ez_rate
1567         description: "EzTune rate"
1568         default_value: 100
1569         field: rate
1570         min: 0
1571         max: 200
1572       - name: ez_expo
1573         description: "EzTune expo"
1574         default_value: 100
1575         field: expo
1576         min: 0
1577         max: 200
1579   - name: PG_RPM_FILTER_CONFIG
1580     headers: ["flight/rpm_filter.h"]
1581     condition: USE_RPM_FILTER
1582     type: rpmFilterConfig_t
1583     members:
1584       - name: rpm_gyro_filter_enabled
1585         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"
1586         default_value: OFF
1587         field: gyro_filter_enabled
1588         type: bool
1589       - name: rpm_gyro_harmonics
1590         description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
1591         default_value: 1
1592         field: gyro_harmonics
1593         type: uint8_t
1594         min: 1
1595         max: 3
1596       - name: rpm_gyro_min_hz
1597         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`"
1598         default_value: 100
1599         field: gyro_min_hz
1600         type: uint8_t
1601         min: 30
1602         max: 200
1603       - name: rpm_gyro_q
1604         description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
1605         default_value: 500
1606         field: gyro_q
1607         type: uint16_t
1608         min: 1
1609         max: 3000
1610   - name: PG_GPS_CONFIG
1611     headers: [ "io/gps.h" ]
1612     type: gpsConfig_t
1613     condition: USE_GPS
1614     members:
1615       - name: gps_provider
1616         description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)."
1617         default_value: "UBLOX"
1618         field: provider
1619         table: gps_provider
1620         type: uint8_t
1621       - name: gps_sbas_mode
1622         description: "Which SBAS mode to be used"
1623         default_value: "NONE"
1624         field: sbasMode
1625         table: gps_sbas_mode
1626         type: uint8_t
1627       - name: gps_dyn_model
1628         description: "GPS navigation model: Pedestrian, Automotive, Air<1g, Air<2g, Air<4g. Default is AIR_2G. Use pedestrian/Automotive with caution, can cause flyaways with fast flying."
1629         default_value: "AIR_2G"
1630         field: dynModel
1631         table: gps_dyn_model
1632         type: uint8_t
1633       - name: gps_auto_config
1634         description: "Enable automatic configuration of UBlox GPS receivers."
1635         default_value: ON
1636         field: autoConfig
1637         type: bool
1638       - name: gps_auto_baud
1639         description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS"
1640         default_value: ON
1641         field: autoBaud
1642         type: bool
1643       - name: gps_auto_baud_max_supported
1644         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"
1645         default_value: "230400"
1646         table: gps_auto_baud_max
1647         field: autoBaudMax
1648         type: uint8_t
1649       - name: gps_ublox_use_galileo
1650         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]."
1651         default_value: OFF
1652         field: ubloxUseGalileo
1653         type: bool
1654       - name: gps_ublox_use_beidou
1655         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]."
1656         default_value: OFF
1657         field: ubloxUseBeidou
1658         type: bool
1659       - name: gps_ublox_use_glonass
1660         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]."
1661         default_value: OFF
1662         field: ubloxUseGlonass
1663         type: bool
1664       - name: gps_min_sats
1665         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."
1666         default_value: 6
1667         field: gpsMinSats
1668         min: 5
1669         max: 10
1670       - name: gps_ublox_nav_hz
1671         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."
1672         default_value: 10
1673         field: ubloxNavHz
1674         type: uint8_t
1675         min: 5
1676         max: 200
1679   - name: PG_RC_CONTROLS_CONFIG
1680     type: rcControlsConfig_t
1681     headers: ["fc/rc_controls.h"]
1682     members:
1683       - name: deadband
1684         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."
1685         default_value: 5
1686         min: 0
1687         max: 32
1688       - name: yaw_deadband
1689         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."
1690         default_value: 5
1691         min: 0
1692         max: 100
1693       - name: pos_hold_deadband
1694         description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
1695         default_value: 10
1696         min: 2
1697         max: 250
1698       - name: control_deadband
1699         description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered."
1700         default_value: 10
1701         min: 2
1702         max: 250
1703       - name: alt_hold_deadband
1704         description: "Defines the deadband of throttle during alt_hold [r/c points]"
1705         default_value: 50
1706         min: 10
1707         max: 250
1708       - name: 3d_deadband_throttle
1709         description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
1710         default_value: 50
1711         field: mid_throttle_deadband
1712         min: 0
1713         max: 200
1714       - name: airmode_type
1715         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."
1716         default_value: "STICK_CENTER"
1717         field: airmodeHandlingType
1718         table: airmodeHandlingType
1719       - name: airmode_throttle_threshold
1720         description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
1721         default_value: 1150
1722         field: airmodeThrottleThreshold
1723         min: 1000
1724         max: 2000
1726   - name: PG_PID_PROFILE
1727     type: pidProfile_t
1728     headers: ["flight/pid.h"]
1729     value_type: PROFILE_VALUE
1730     members:
1731       - name: mc_p_pitch
1732         description: "Multicopter rate stabilisation P-gain for PITCH"
1733         default_value: 40
1734         field: bank_mc.pid[PID_PITCH].P
1735         min: RPYL_PID_MIN
1736         max: RPYL_PID_MAX
1737       - name: mc_i_pitch
1738         description: "Multicopter rate stabilisation I-gain for PITCH"
1739         default_value: 30
1740         field: bank_mc.pid[PID_PITCH].I
1741         min: RPYL_PID_MIN
1742         max: RPYL_PID_MAX
1743       - name: mc_d_pitch
1744         description: "Multicopter rate stabilisation D-gain for PITCH"
1745         default_value: 23
1746         field: bank_mc.pid[PID_PITCH].D
1747         min: RPYL_PID_MIN
1748         max: RPYL_PID_MAX
1749       - name: mc_cd_pitch
1750         description: "Multicopter Control Derivative gain for PITCH (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1751         default_value: 60
1752         field: bank_mc.pid[PID_PITCH].FF
1753         min: RPYL_PID_MIN
1754         max: RPYL_PID_MAX
1755       - name: mc_p_roll
1756         description: "Multicopter rate stabilisation P-gain for ROLL"
1757         default_value: 40
1758         field: bank_mc.pid[PID_ROLL].P
1759         min: RPYL_PID_MIN
1760         max: RPYL_PID_MAX
1761       - name: mc_i_roll
1762         description: "Multicopter rate stabilisation I-gain for ROLL"
1763         default_value: 30
1764         field: bank_mc.pid[PID_ROLL].I
1765         min: RPYL_PID_MIN
1766         max: RPYL_PID_MAX
1767       - name: mc_d_roll
1768         description: "Multicopter rate stabilisation D-gain for ROLL"
1769         default_value: 23
1770         field: bank_mc.pid[PID_ROLL].D
1771         min: RPYL_PID_MIN
1772         max: RPYL_PID_MAX
1773       - name: mc_cd_roll
1774         description: "Multicopter Control Derivative gain for ROLL (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1775         default_value: 60
1776         field: bank_mc.pid[PID_ROLL].FF
1777         min: RPYL_PID_MIN
1778         max: RPYL_PID_MAX
1779       - name: mc_p_yaw
1780         description: "Multicopter rate stabilisation P-gain for YAW"
1781         default_value: 85
1782         field: bank_mc.pid[PID_YAW].P
1783         min: RPYL_PID_MIN
1784         max: RPYL_PID_MAX
1785       - name: mc_i_yaw
1786         description: "Multicopter rate stabilisation I-gain for YAW"
1787         default_value: 45
1788         field: bank_mc.pid[PID_YAW].I
1789         min: RPYL_PID_MIN
1790         max: RPYL_PID_MAX
1791       - name: mc_d_yaw
1792         description: "Multicopter rate stabilisation D-gain for YAW"
1793         default_value: 0
1794         field: bank_mc.pid[PID_YAW].D
1795         min: RPYL_PID_MIN
1796         max: RPYL_PID_MAX
1797       - name: mc_cd_yaw
1798         description: "Multicopter Control Derivative gain for YAW (known as 'Feed Forward' in Betaflight). The CD intoduces a term to the PID controller that is the magnitude of the Setpoint change. Fast inputs produce a high CD gain to help push the MC into a move; in advance of the P-gain if set high enough."
1799         default_value: 60
1800         field: bank_mc.pid[PID_YAW].FF
1801         min: RPYL_PID_MIN
1802         max: RPYL_PID_MAX
1803       - name: mc_p_level
1804         description: "Multicopter attitude stabilisation P-gain"
1805         default_value: 20
1806         field: bank_mc.pid[PID_LEVEL].P
1807         min: RPYL_PID_MIN
1808         max: RPYL_PID_MAX
1809       - name: mc_i_level
1810         description: "Multicopter attitude stabilisation low-pass filter cutoff"
1811         default_value: 15
1812         field: bank_mc.pid[PID_LEVEL].I
1813         min: RPYL_PID_MIN
1814         max: RPYL_PID_MAX
1815       - name: mc_d_level
1816         description: "Multicopter attitude stabilisation HORIZON transition point"
1817         default_value: 75
1818         field: bank_mc.pid[PID_LEVEL].D
1819         min: RPYL_PID_MIN
1820         max: RPYL_PID_MAX
1821       - name: fw_p_pitch
1822         description: "Fixed-wing rate stabilisation P-gain for PITCH"
1823         default_value: 5
1824         field: bank_fw.pid[PID_PITCH].P
1825         min: RPYL_PID_MIN
1826         max: RPYL_PID_MAX
1827       - name: fw_i_pitch
1828         description: "Fixed-wing rate stabilisation I-gain for PITCH"
1829         default_value: 7
1830         field: bank_fw.pid[PID_PITCH].I
1831         min: RPYL_PID_MIN
1832         max: RPYL_PID_MAX
1833       - name: fw_d_pitch
1834         description: "Fixed wing rate stabilisation D-gain for PITCH"
1835         default_value: 0
1836         field: bank_fw.pid[PID_PITCH].D
1837         min: RPYL_PID_MIN
1838         max: RPYL_PID_MAX
1839       - name: fw_ff_pitch
1840         description: "Fixed-wing rate stabilisation FF-gain for PITCH"
1841         default_value: 50
1842         field: bank_fw.pid[PID_PITCH].FF
1843         min: RPYL_PID_MIN
1844         max: RPYL_PID_MAX
1845       - name: fw_p_roll
1846         description: "Fixed-wing rate stabilisation P-gain for ROLL"
1847         default_value: 5
1848         field: bank_fw.pid[PID_ROLL].P
1849         min: RPYL_PID_MIN
1850         max: RPYL_PID_MAX
1851       - name: fw_i_roll
1852         description: "Fixed-wing rate stabilisation I-gain for ROLL"
1853         default_value: 7
1854         field: bank_fw.pid[PID_ROLL].I
1855         min: RPYL_PID_MIN
1856         max: RPYL_PID_MAX
1857       - name: fw_d_roll
1858         description: "Fixed wing rate stabilisation D-gain for ROLL"
1859         default_value: 0
1860         field: bank_fw.pid[PID_ROLL].D
1861         min: RPYL_PID_MIN
1862         max: RPYL_PID_MAX
1863       - name: fw_ff_roll
1864         description: "Fixed-wing rate stabilisation FF-gain for ROLL"
1865         default_value: 50
1866         field: bank_fw.pid[PID_ROLL].FF
1867         min: RPYL_PID_MIN
1868         max: RPYL_PID_MAX
1869       - name: fw_p_yaw
1870         description: "Fixed-wing rate stabilisation P-gain for YAW"
1871         default_value: 6
1872         field: bank_fw.pid[PID_YAW].P
1873         min: RPYL_PID_MIN
1874         max: RPYL_PID_MAX
1875       - name: fw_i_yaw
1876         description: "Fixed-wing rate stabilisation I-gain for YAW"
1877         default_value: 10
1878         field: bank_fw.pid[PID_YAW].I
1879         min: RPYL_PID_MIN
1880         max: RPYL_PID_MAX
1881       - name: fw_d_yaw
1882         description: "Fixed wing rate stabilisation D-gain for YAW"
1883         default_value: 0
1884         field: bank_fw.pid[PID_YAW].D
1885         min: RPYL_PID_MIN
1886         max: RPYL_PID_MAX
1887       - name: fw_ff_yaw
1888         description: "Fixed-wing rate stabilisation FF-gain for YAW"
1889         default_value: 60
1890         field: bank_fw.pid[PID_YAW].FF
1891         min: RPYL_PID_MIN
1892         max: RPYL_PID_MAX
1893       - name: fw_p_level
1894         description: "Fixed-wing attitude stabilisation P-gain"
1895         default_value: 20
1896         field: bank_fw.pid[PID_LEVEL].P
1897         min: RPYL_PID_MIN
1898         max: RPYL_PID_MAX
1899       - name: fw_i_level
1900         description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
1901         default_value: 5
1902         field: bank_fw.pid[PID_LEVEL].I
1903         min: RPYL_PID_MIN
1904         max: RPYL_PID_MAX
1905       - name: fw_d_level
1906         description: "Fixed-wing attitude stabilisation HORIZON transition point"
1907         default_value: 75
1908         field: bank_fw.pid[PID_LEVEL].D
1909         min: RPYL_PID_MIN
1910         max: RPYL_PID_MAX
1911       - name: max_angle_inclination_rll
1912         description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
1913         default_value: 300
1914         field: max_angle_inclination[FD_ROLL]
1915         min: 100
1916         max: 900
1917       - name: max_angle_inclination_pit
1918         description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
1919         default_value: 300
1920         field: max_angle_inclination[FD_PITCH]
1921         min: 100
1922         max: 900
1923       - name: dterm_lpf_hz
1924         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"
1925         default_value: 110
1926         min: 0
1927         max: 500
1928       - name: dterm_lpf_type
1929         description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
1930         default_value: "PT2"
1931         field: dterm_lpf_type
1932         table: filter_type_full
1933       - name: yaw_lpf_hz
1934         description: "Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
1935         default_value: 0
1936         min: 0
1937         max: 200
1938       - name: fw_reference_airspeed
1939         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."
1940         default_value: 1500
1941         field: fixedWingReferenceAirspeed
1942         min: 300
1943         max: 6000
1944       - name: fw_turn_assist_yaw_gain
1945         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"
1946         default_value: 1
1947         field: fixedWingCoordinatedYawGain
1948         min: 0
1949         max: 2
1950       - name: fw_turn_assist_pitch_gain
1951         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"
1952         default_value: 1
1953         field: fixedWingCoordinatedPitchGain
1954         min: 0
1955         max: 2
1956       - name: fw_iterm_limit_stick_position
1957         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"
1958         default_value: 0.5
1959         field: fixedWingItermLimitOnStickPosition
1960         min: 0
1961         max: 1
1962       - name: fw_yaw_iterm_freeze_bank_angle
1963         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."
1964         default_value: 0
1965         field: fixedWingYawItermBankFreeze
1966         min: 0
1967         max: 90
1968       - name: pidsum_limit
1969         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"
1970         default_value: 500
1971         field: pidSumLimit
1972         min: PID_SUM_LIMIT_MIN
1973         max: PID_SUM_LIMIT_MAX
1974       - name: pidsum_limit_yaw
1975         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"
1976         default_value: 350
1977         field: pidSumLimitYaw
1978         min: PID_SUM_LIMIT_MIN
1979         max: PID_SUM_LIMIT_MAX
1980       - name: iterm_windup
1981         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)"
1982         default_value: 50
1983         field: itermWindupPointPercent
1984         min: 0
1985         max: 90
1986       - name: pid_iterm_limit_percent
1987         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."
1988         default_value: 33
1989         field: pidItermLimitPercent
1990         min: 0
1991         max: 200
1992       - name: rate_accel_limit_roll_pitch
1993         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."
1994         default_value: 0
1995         field: axisAccelerationLimitRollPitch
1996         max: 500000
1997       - name: rate_accel_limit_yaw
1998         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."
1999         default_value: 10000
2000         field: axisAccelerationLimitYaw
2001         max: 500000
2002       - name: heading_hold_rate_limit
2003         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."
2004         min: HEADING_HOLD_RATE_LIMIT_MIN
2005         max: HEADING_HOLD_RATE_LIMIT_MAX
2006         default_value: 90
2007       - name: nav_mc_pos_z_p
2008         description: "P gain of altitude PID controller (Multirotor)"
2009         field: bank_mc.pid[PID_POS_Z].P
2010         min: 0
2011         max: 255
2012         default_value: 50
2013       - name: nav_mc_vel_z_p
2014         description: "P gain of velocity PID controller"
2015         field: bank_mc.pid[PID_VEL_Z].P
2016         min: 0
2017         max: 255
2018         default_value: 100
2019       - name: nav_mc_vel_z_i
2020         description: "I gain of velocity PID controller"
2021         field: bank_mc.pid[PID_VEL_Z].I
2022         min: 0
2023         max: 255
2024         default_value: 50
2025       - name: nav_mc_vel_z_d
2026         description: "D gain of velocity PID controller"
2027         field: bank_mc.pid[PID_VEL_Z].D
2028         min: 0
2029         max: 255
2030         default_value: 10
2031       - name: nav_mc_pos_xy_p
2032         description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
2033         field: bank_mc.pid[PID_POS_XY].P
2034         min: 0
2035         max: 255
2036         default_value: 65
2037       - name: nav_mc_vel_xy_p
2038         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"
2039         field: bank_mc.pid[PID_VEL_XY].P
2040         min: 0
2041         max: 255
2042         default_value: 40
2043       - name: nav_mc_vel_xy_i
2044         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"
2045         field: bank_mc.pid[PID_VEL_XY].I
2046         min: 0
2047         max: 255
2048         default_value: 15
2049       - name: nav_mc_vel_xy_d
2050         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."
2051         field: bank_mc.pid[PID_VEL_XY].D
2052         min: 0
2053         max: 255
2054         default_value: 100
2055       - name: nav_mc_vel_xy_ff
2056         field: bank_mc.pid[PID_VEL_XY].FF
2057         min: 0
2058         max: 255
2059         default_value: 40
2060       - name: nav_mc_heading_p
2061         description: "P gain of Heading Hold controller (Multirotor)"
2062         default_value: 60
2063         field: bank_mc.pid[PID_HEADING].P
2064         min: 0
2065         max: 255
2066       - name: nav_mc_vel_xy_dterm_lpf_hz
2067         field: navVelXyDTermLpfHz
2068         min: 0
2069         max: 100
2070         default_value: 2
2071       - name: nav_mc_vel_xy_dterm_attenuation
2072         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."
2073         field: navVelXyDtermAttenuation
2074         min: 0
2075         max: 100
2076         default_value: 90
2077       - name: nav_mc_vel_xy_dterm_attenuation_start
2078         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
2079         default_value: 10
2080         field: navVelXyDtermAttenuationStart
2081         min: 0
2082         max: 100
2083       - name: nav_mc_vel_xy_dterm_attenuation_end
2084         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
2085         default_value: 60
2086         field: navVelXyDtermAttenuationEnd
2087         min: 0
2088         max: 100
2089       - name: nav_fw_pos_z_p
2090         description: "P gain of altitude PID controller (Fixedwing)"
2091         default_value: 40
2092         field: bank_fw.pid[PID_POS_Z].P
2093         min: 0
2094         max: 255
2095       - name: nav_fw_pos_z_i
2096         description: "I gain of altitude PID controller (Fixedwing)"
2097         default_value: 5
2098         field: bank_fw.pid[PID_POS_Z].I
2099         min: 0
2100         max: 255
2101       - name: nav_fw_pos_z_d
2102         description: "D gain of altitude PID controller (Fixedwing)"
2103         default_value: 10
2104         field: bank_fw.pid[PID_POS_Z].D
2105         min: 0
2106         max: 255
2107       - name: nav_fw_alt_control_response
2108         description: "Adjusts the deceleration response of fixed wing altitude control as the target altitude is approached. Decrease value to help avoid overshooting the target altitude."
2109         default_value: 20
2110         field: fwAltControlResponseFactor
2111         min: 5
2112         max: 100
2113       - name: nav_fw_pos_xy_p
2114         description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
2115         default_value: 75
2116         field: bank_fw.pid[PID_POS_XY].P
2117         min: 0
2118         max: 255
2119       - name: nav_fw_pos_xy_i
2120         description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2121         default_value: 5
2122         field: bank_fw.pid[PID_POS_XY].I
2123         min: 0
2124         max: 255
2125       - name: nav_fw_pos_xy_d
2126         description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2127         default_value: 8
2128         field: bank_fw.pid[PID_POS_XY].D
2129         min: 0
2130         max: 255
2131       - name: nav_fw_heading_p
2132         description: "P gain of Heading Hold controller (Fixedwing)"
2133         default_value: 60
2134         field: bank_fw.pid[PID_HEADING].P
2135         min: 0
2136         max: 255
2137       - name: nav_fw_pos_hdg_p
2138         description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
2139         default_value: 30
2140         field: bank_fw.pid[PID_POS_HEADING].P
2141         min: 0
2142         max: 255
2143       - name: nav_fw_pos_hdg_i
2144         description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2145         default_value: 2
2146         field: bank_fw.pid[PID_POS_HEADING].I
2147         min: 0
2148         max: 255
2149       - name: nav_fw_pos_hdg_d
2150         description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2151         default_value: 0
2152         field: bank_fw.pid[PID_POS_HEADING].D
2153         min: 0
2154         max: 255
2155       - name: nav_fw_pos_hdg_pidsum_limit
2156         description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
2157         default_value: 350
2158         field: navFwPosHdgPidsumLimit
2159         min: PID_SUM_LIMIT_MIN
2160         max: PID_SUM_LIMIT_MAX
2161       - name: mc_iterm_relax
2162         field: iterm_relax
2163         table: iterm_relax
2164         default_value: RP
2165       - name: mc_iterm_relax_cutoff
2166         field: iterm_relax_cutoff
2167         min: 1
2168         max: 100
2169         default_value: 15
2170       - name: d_boost_min
2171         field: dBoostMin
2172         condition: USE_D_BOOST
2173         min: 0
2174         max: 1
2175         default_value: 0.5
2176       - name: d_boost_max
2177         field: dBoostMax
2178         condition: USE_D_BOOST
2179         min: 1
2180         max: 3
2181         default_value: 1.25
2182       - name: d_boost_max_at_acceleration
2183         field: dBoostMaxAtAlleceleration
2184         condition: USE_D_BOOST
2185         min: 1000
2186         max: 16000
2187         default_value: 7500
2188       - name: d_boost_gyro_delta_lpf_hz
2189         field: dBoostGyroDeltaLpfHz
2190         condition: USE_D_BOOST
2191         min: 10
2192         max: 250
2193         default_value: 80
2194       - name: antigravity_gain
2195         description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
2196         default_value: 1
2197         field: antigravityGain
2198         condition: USE_ANTIGRAVITY
2199         min: 1
2200         max: 20
2201       - name: antigravity_accelerator
2202         description: ""
2203         default_value: 1
2204         field: antigravityAccelerator
2205         condition: USE_ANTIGRAVITY
2206         min: 1
2207         max: 20
2208       - name: antigravity_cutoff_lpf_hz
2209         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"
2210         default_value: 15
2211         field: antigravityCutoff
2212         condition: USE_ANTIGRAVITY
2213         min: 1
2214         max: 30
2215       - name: pid_type
2216         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`"
2217         field: pidControllerType
2218         table: pidTypeTable
2219         default_value: AUTO
2220       - name: mc_cd_lpf_hz
2221         description: "Cutoff frequency for Control Derivative. This controls the cutoff for the LPF that is applied to the CD (Feed Forward) signal to the PID controller. Lower value will produce a smoother CD gain to the controller, but it will be more delayed. Higher values will produce CD gain that may have more noise in the signal depending on your RC link but wil be less delayed."
2222         default_value: 30
2223         field: controlDerivativeLpfHz
2224         min: 0
2225         max: 200
2226       - name: fw_level_pitch_trim
2227         description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
2228         default_value: 0
2229         field: fixedWingLevelTrim
2230         min: -10
2231         max: 10
2232       - name: smith_predictor_strength
2233         description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2234         default_value: 0.5
2235         field: smithPredictorStrength
2236         condition: USE_SMITH_PREDICTOR
2237         min: 0
2238         max: 1
2239       - name: smith_predictor_delay
2240         description: "Expected delay of the gyro signal. In milliseconds"
2241         default_value: 0
2242         field: smithPredictorDelay
2243         condition: USE_SMITH_PREDICTOR
2244         min: 0
2245         max: 8
2246       - name: smith_predictor_lpf_hz
2247         description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2248         default_value: 50
2249         field: smithPredictorFilterHz
2250         condition: USE_SMITH_PREDICTOR
2251         min: 1
2252         max: 500
2253       - name: fw_level_pitch_gain
2254         description: "I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations"
2255         default_value: 5
2256         field: fixedWingLevelTrimGain
2257         min: 0
2258         max: 20
2260   - name: PG_PID_AUTOTUNE_CONFIG
2261     type: pidAutotuneConfig_t
2262     condition: USE_AUTOTUNE_FIXED_WING
2263     members:
2264       - name: fw_autotune_min_stick
2265         description: "Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input."
2266         default_value: 50
2267         field: fw_min_stick
2268         min: 0
2269         max: 100
2270       - name: fw_autotune_rate_adjustment
2271         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."
2272         default_value: "AUTO"
2273         field: fw_rate_adjustment
2274         table: autotune_rate_adjustment
2275         type: uint8_t
2276       - name: fw_autotune_max_rate_deflection
2277         description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
2278         default_value: 80
2279         field: fw_max_rate_deflection
2280         min: 50
2281         max: 100
2283   - name: PG_POSITION_ESTIMATION_CONFIG
2284     type: positionEstimationConfig_t
2285     members:
2286       - name: inav_auto_mag_decl
2287         description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
2288         default_value: ON
2289         field: automatic_mag_declination
2290         type: bool
2291       - name: inav_gravity_cal_tolerance
2292         description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
2293         default_value: 5
2294         field: gravity_calibration_tolerance
2295         min: 0
2296         max: 255
2297       - name: inav_use_gps_velned
2298         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."
2299         default_value: ON
2300         field: use_gps_velned
2301         type: bool
2302       - name: inav_use_gps_no_baro
2303         field: use_gps_no_baro
2304         type: bool
2305         default_value: OFF
2306       - name: inav_allow_dead_reckoning
2307         description: "Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
2308         default_value: OFF
2309         field: allow_dead_reckoning
2310         type: bool
2311       - name: inav_allow_gps_fix_estimation
2312         description: "Defines if inav will estimate GPS fix with magnetometer and barometer on GPS outages. Enables navigation and RTH without GPS fix on fixed wing. Also see failsafe_gps_fix_estimation_delay."
2313         condition: USE_GPS_FIX_ESTIMATION
2314         default_value: OFF
2315         field: allow_gps_fix_estimation
2316         type: bool
2317       - name: inav_reset_altitude
2318         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)"
2319         default_value: "FIRST_ARM"
2320         field: reset_altitude_type
2321         table: reset_type
2322       - name: inav_reset_home
2323         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"
2324         default_value: "FIRST_ARM"
2325         field: reset_home_type
2326         table: reset_type
2327       - name: inav_max_surface_altitude
2328         description: "Max allowed altitude for surface following mode. [cm]"
2329         default_value: 200
2330         field: max_surface_altitude
2331         min: 0
2332         max: 1000
2333       - name: inav_w_z_surface_p
2334         field: w_z_surface_p
2335         min: 0
2336         max: 100
2337         default_value: 3.5 
2338       - name: inav_w_z_surface_v
2339         field: w_z_surface_v
2340         min: 0
2341         max: 100
2342         default_value: 6.1
2343       - name: inav_w_xy_flow_p
2344         field: w_xy_flow_p
2345         min: 0
2346         max: 100
2347         default_value: 1.0
2348       - name: inav_w_xy_flow_v
2349         field: w_xy_flow_v
2350         min: 0
2351         max: 100
2352         default_value: 2.0
2353       - name: inav_w_z_baro_p
2354         description: "Weight of barometer measurements in estimated altitude and climb rate. Setting is used on both airplanes and multirotors."
2355         field: w_z_baro_p
2356         min: 0
2357         max: 10
2358         default_value: 0.35
2359       - name: inav_w_z_gps_p
2360         description: "Weight of GPS altitude measurements in estimated altitude. Setting is used on both airplanes and multirotors."
2361         field: w_z_gps_p
2362         min: 0
2363         max: 10
2364         default_value: 0.2
2365       - name: inav_w_z_gps_v
2366         description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors."
2367         field: w_z_gps_v
2368         min: 0
2369         max: 10
2370         default_value: 0.1
2371       - name: inav_w_xy_gps_p
2372         description: "Weight of GPS coordinates in estimated UAV position and speed."
2373         default_value: 1.0
2374         field: w_xy_gps_p
2375         min: 0
2376         max: 10
2377       - name: inav_w_xy_gps_v
2378         description: "Weight of GPS velocity data in estimated UAV speed"
2379         default_value: 2.0
2380         field: w_xy_gps_v
2381         min: 0
2382         max: 10
2383       - name: inav_w_z_res_v
2384         description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
2385         default_value: 0.5
2386         field: w_z_res_v
2387         min: 0
2388         max: 10
2389       - name: inav_w_xy_res_v
2390         description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
2391         default_value: 0.5
2392         field: w_xy_res_v
2393         min: 0
2394         max: 10
2395       - name: inav_w_acc_bias
2396         description: "Weight for accelerometer drift estimation"
2397         default_value: 0.01
2398         field: w_acc_bias
2399         min: 0
2400         max: 1
2401       - name: inav_max_eph_epv
2402         description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
2403         default_value: 1000
2404         field: max_eph_epv
2405         min: 0
2406         max: 9999
2407       - name: inav_baro_epv
2408         description: "Uncertainty value for barometric sensor [cm]"
2409         default_value: 100
2410         field: baro_epv
2411         min: 0
2412         max: 9999
2414   - name: PG_NAV_CONFIG
2415     type: navConfig_t
2416     headers: ["navigation/navigation.h"]
2417     members:
2418       - name: nav_disarm_on_landing
2419         description: "If set to ON, INAV disarms the FC after landing"
2420         default_value: ON
2421         field: general.flags.disarm_on_landing
2422         type: bool
2423       - name: nav_land_detect_sensitivity
2424         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."
2425         default_value: 5
2426         field: general.land_detect_sensitivity
2427         min: 1
2428         max: 15
2429       - name: nav_landing_bump_detection
2430         description: "Allows immediate landing detection based on G bump at touchdown when set to ON. Requires a barometer and currently only works for multirotors."
2431         default_value: OFF
2432         field: general.flags.landing_bump_detection
2433         type: bool
2434       - name: nav_mc_althold_throttle
2435         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."
2436         default_value: "STICK"
2437         field: mc.althold_throttle_type
2438         table: nav_mc_althold_throttle
2439       - name: nav_extra_arming_safety
2440         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"
2441         default_value: "ALLOW_BYPASS"
2442         field: general.flags.extra_arming_safety
2443         table: nav_extra_arming_safety
2444       - name: nav_user_control_mode
2445         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."
2446         default_value: "ATTI"
2447         field: general.flags.user_control_mode
2448         table: nav_user_control_mode
2449       - name: nav_position_timeout
2450         description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
2451         default_value: 5
2452         field: general.pos_failure_timeout
2453         min: 0
2454         max: 10
2455       - name: nav_wp_load_on_boot
2456         description: "If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup."
2457         default_value: OFF
2458         field: general.waypoint_load_on_boot
2459         type: bool
2460       - name: nav_wp_radius
2461         description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
2462         default_value: 100
2463         field: general.waypoint_radius
2464         min: 10
2465         max: 10000
2466       - name: nav_wp_enforce_altitude
2467         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."
2468         default_value: 0
2469         field: general.waypoint_enforce_altitude
2470         min: 0
2471         max: 2000
2472       - name: nav_wp_max_safe_distance
2473         description: "First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check."
2474         default_value: 100
2475         field: general.waypoint_safe_distance
2476         min: 0
2477         max: 1500
2478       - name: nav_wp_mission_restart
2479         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."
2480         default_value: "RESUME"
2481         field: general.flags.waypoint_mission_restart
2482         table: nav_wp_mission_restart
2483       - name: nav_wp_multi_mission_index
2484         description: "Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions."
2485         default_value: 1
2486         field: general.waypoint_multi_mission_index
2487         condition: USE_MULTI_MISSION
2488         min: 1
2489         max: 9
2490       - name: nav_fw_wp_tracking_accuracy
2491         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."
2492         default_value: 0
2493         field: fw.wp_tracking_accuracy
2494         min: 0
2495         max: 10
2496       - name: nav_fw_wp_tracking_max_angle
2497         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."
2498         default_value: 60
2499         field: fw.wp_tracking_max_angle
2500         min: 30
2501         max: 80
2502       - name: nav_fw_wp_turn_smoothing
2503         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)."
2504         default_value: "OFF"
2505         field: fw.wp_turn_smoothing
2506         table: nav_fw_wp_turn_smoothing
2507       - name: nav_auto_speed
2508         description: "Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]"
2509         default_value: 300
2510         field: general.auto_speed
2511         min: 10
2512         max: 2000
2513       - name: nav_min_ground_speed
2514         description: "Minimum ground speed for navigation flight modes [m/s]. Default 7 m/s."
2515         default_value: 7
2516         field: general.min_ground_speed
2517         min: 6
2518         max: 50
2519       - name: nav_max_auto_speed
2520         description: "Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]"
2521         default_value: 1000
2522         field: general.max_auto_speed
2523         min: 10
2524         max: 2000
2525       - name: nav_manual_speed
2526         description: "Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
2527         default_value: 500
2528         field: general.max_manual_speed
2529         min: 10
2530         max: 2000
2531       - name: nav_land_minalt_vspd
2532         description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
2533         default_value: 50
2534         field: general.land_minalt_vspd
2535         min: 50
2536         max: 500
2537       - name: nav_land_maxalt_vspd
2538         description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"
2539         default_value: 200
2540         field: general.land_maxalt_vspd
2541         min: 100
2542         max: 2000
2543       - name: nav_land_slowdown_minalt
2544         description: "Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]"
2545         default_value: 500
2546         field: general.land_slowdown_minalt
2547         min: 50
2548         max: 1000
2549       - name: nav_land_slowdown_maxalt
2550         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]"
2551         default_value: 2000
2552         field: general.land_slowdown_maxalt
2553         min: 500
2554         max: 4000
2555       - name: nav_emerg_landing_speed
2556         description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
2557         default_value: 500
2558         field: general.emerg_descent_rate
2559         min: 100
2560         max: 2000
2561       - name: nav_min_rth_distance
2562         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."
2563         default_value: 500
2564         field: general.min_rth_distance
2565         min: 0
2566         max: 5000
2567       - name: nav_overrides_motor_stop
2568         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"
2569         default_value: "ALL_NAV"
2570         field: general.flags.nav_overrides_motor_stop
2571         table: nav_overrides_motor_stop
2572       - name: nav_fw_soaring_motor_stop
2573         description: "Stops motor when Soaring mode enabled."
2574         default_value: OFF
2575         field: general.flags.soaring_motor_stop
2576         type: bool
2577       - name: nav_fw_soaring_pitch_deadband
2578         description: "Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within deadband allowing pitch to free float whilst soaring."
2579         default_value: 5
2580         field: fw.soaring_pitch_deadband
2581         min: 0
2582         max: 15
2583       - name: nav_rth_climb_first
2584         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)"
2585         default_value: "ON"
2586         field: general.flags.rth_climb_first
2587         table: nav_rth_climb_first
2588       - name: nav_rth_climb_first_stage_mode
2589         description: "This determines how rth_climb_first_stage_altitude is used. Default is AT_LEAST."
2590         default_value: "AT_LEAST"
2591         field: general.flags.rth_climb_first_stage_mode
2592         table: nav_rth_climb_first_stage_modes
2593       - name: nav_rth_climb_first_stage_altitude
2594         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."
2595         default_value: 0
2596         field: general.rth_climb_first_stage_altitude
2597         max: 65000
2598       - name: nav_rth_climb_ignore_emerg
2599         description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
2600         default_value: OFF
2601         field: general.flags.rth_climb_ignore_emerg
2602         type: bool
2603       - name: nav_rth_tail_first
2604         description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
2605         default_value: OFF
2606         field: general.flags.rth_tail_first
2607         type: bool
2608       - name: nav_rth_allow_landing
2609         description: "If set to ON drone will land as a last phase of RTH."
2610         default_value: "ALWAYS"
2611         field: general.flags.rth_allow_landing
2612         table: nav_rth_allow_landing
2613       - name: nav_rth_fs_landing_delay
2614         description: "If landing is active on Failsafe and this is above 0. The aircraft will hover or loiter for X seconds before performing the landing. If the battery enters the warning or critical levels, the land will proceed. Default = 0 [seconds]"
2615         default_value: 0
2616         min: 0
2617         max: 1800
2618         field: general.rth_fs_landing_delay
2619       - name: nav_rth_alt_mode
2620         description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details"
2621         default_value: "AT_LEAST"
2622         field: general.flags.rth_alt_control_mode
2623         table: nav_rth_alt_mode
2624       - name: nav_rth_alt_control_override
2625         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)"
2626         default_value: OFF
2627         field: general.flags.rth_alt_control_override
2628         type: bool
2629       - name: nav_rth_abort_threshold
2630         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]"
2631         default_value: 50000
2632         field: general.rth_abort_threshold
2633         max: 65000
2634         min: 0
2635       - name: nav_max_terrain_follow_alt
2636         field: general.max_terrain_follow_altitude
2637         default_value: "100"
2638         description: "Max allowed above the ground altitude for terrain following mode"
2639         max: 1000
2640         default_value: 100
2641       - name: nav_max_altitude
2642         field: general.max_altitude
2643         description: "Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled"
2644         default_value: 0
2645         max: 65000
2646         min: 0
2647       - name: nav_rth_altitude
2648         description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
2649         default_value: 1000
2650         field: general.rth_altitude
2651         max: 65000
2652       - name: nav_rth_home_altitude
2653         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]"
2654         default_value: 0
2655         field: general.rth_home_altitude
2656         max: 65000
2657       - name: nav_rth_linear_descent_start_distance
2658         description: The distance [m] away from home to start the linear descent. 0 = immediately (original linear descent behaviour)
2659         default_value: 0
2660         min: 0
2661         max: 10000
2662         field: general.rth_linear_descent_start_distance
2663       - name: nav_rth_use_linear_descent
2664         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`.
2665         default_value: OFF
2666         type: bool
2667         field: general.flags.rth_use_linear_descent
2668       - name: nav_rth_trackback_mode
2669         description: "Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only."
2670         default_value: "OFF"
2671         field: general.flags.rth_trackback_mode
2672         table: rth_trackback_mode
2673       - name: nav_rth_trackback_distance
2674         description: "Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m]."
2675         default_value: 500
2676         field: general.rth_trackback_distance
2677         max: 2000
2678         min: 50
2679       - name: safehome_max_distance
2680         description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
2681         default_value: 20000
2682         field: general.safehome_max_distance
2683         min: 0
2684         max: 65000
2685       - name: safehome_usage_mode
2686         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."
2687         default_value: "RTH"
2688         field: general.flags.safehome_usage_mode
2689         table: safehome_usage_mode
2690       - name: nav_mission_planner_reset
2691         description: "With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling the mode switch ON-OFF-ON."
2692         default_value: ON
2693         field: general.flags.mission_planner_reset
2694         type: bool
2695       - name: nav_cruise_yaw_rate
2696         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]"
2697         default_value: 60
2698         field: general.cruise_yaw_rate
2699         min: 0
2700         max: 120
2701       - name: nav_mc_bank_angle
2702         description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
2703         default_value: 30
2704         field: mc.max_bank_angle
2705         min: 15
2706         max: 45
2707       - name: nav_mc_auto_climb_rate
2708         description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2709         default_value: 500
2710         field: mc.max_auto_climb_rate
2711         min: 10
2712         max: 2000
2713       - name: nav_mc_manual_climb_rate
2714         description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2715         default_value: 200
2716         field: mc.max_manual_climb_rate
2717         min: 10
2718         max: 2000
2719       - name: nav_auto_disarm_delay
2720         description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)"
2721         default_value: 1000
2722         field: general.auto_disarm_delay
2723         min: 100
2724         max: 10000
2725       - name: nav_mc_braking_speed_threshold
2726         description: "min speed in cm/s above which braking can happen"
2727         default_value: 100
2728         field: mc.braking_speed_threshold
2729         condition: USE_MR_BRAKING_MODE
2730         min: 0
2731         max: 1000
2732       - name: nav_mc_braking_disengage_speed
2733         description: "braking is disabled when speed goes below this value"
2734         default_value: 75
2735         field: mc.braking_disengage_speed
2736         condition: USE_MR_BRAKING_MODE
2737         min: 0
2738         max: 1000
2739       - name: nav_mc_braking_timeout
2740         description: "timeout in ms for braking"
2741         default_value: 2000
2742         field: mc.braking_timeout
2743         condition: USE_MR_BRAKING_MODE
2744         min: 100
2745         max: 5000
2746       - name: nav_mc_braking_boost_factor
2747         description: "acceleration factor for BOOST phase"
2748         default_value: 100
2749         field: mc.braking_boost_factor
2750         condition: USE_MR_BRAKING_MODE
2751         min: 0
2752         max: 200
2753       - name: nav_mc_braking_boost_timeout
2754         description: "how long in ms BOOST phase can happen"
2755         default_value: 750
2756         field: mc.braking_boost_timeout
2757         condition: USE_MR_BRAKING_MODE
2758         min: 0
2759         max: 5000
2760       - name: nav_mc_braking_boost_speed_threshold
2761         description: "BOOST can be enabled when speed is above this value"
2762         default_value: 150
2763         field: mc.braking_boost_speed_threshold
2764         condition: USE_MR_BRAKING_MODE
2765         min: 100
2766         max: 1000
2767       - name: nav_mc_braking_boost_disengage_speed
2768         description: "BOOST will be disabled when speed goes below this value"
2769         default_value: 100
2770         field: mc.braking_boost_disengage_speed
2771         condition: USE_MR_BRAKING_MODE
2772         min: 0
2773         max: 1000
2774       - name: nav_mc_braking_bank_angle
2775         description: "max angle that MR is allowed to bank in BOOST mode"
2776         default_value: 40
2777         field: mc.braking_bank_angle
2778         condition: USE_MR_BRAKING_MODE
2779         min: 15
2780         max: 60
2781       - name: nav_mc_pos_deceleration_time
2782         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"
2783         default_value: 120
2784         field: mc.posDecelerationTime
2785         min: 0
2786         max: 255
2787       - name: nav_mc_pos_expo
2788         description: "Expo for PosHold control"
2789         default_value: 10
2790         field: mc.posResponseExpo
2791         min: 0
2792         max: 255
2793       - name: nav_mc_wp_slowdown
2794         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."
2795         default_value: ON
2796         field: mc.slowDownForTurning
2797         type: bool
2798       - name: nav_fw_bank_angle
2799         description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
2800         default_value: 35
2801         field: fw.max_bank_angle
2802         min: 5
2803         max: 80
2804       - name: nav_fw_manual_climb_rate
2805         description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2806         default_value: 300
2807         field: fw.max_manual_climb_rate
2808         min: 10
2809         max: 2500
2810       - name: nav_fw_climb_angle
2811         description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2812         default_value: 20
2813         field: fw.max_climb_angle
2814         min: 5
2815         max: 80
2816       - name: nav_fw_dive_angle
2817         description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2818         default_value: 15
2819         field: fw.max_dive_angle
2820         min: 5
2821         max: 80
2822       - name: nav_fw_pitch2thr_smoothing
2823         description:  "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
2824         default_value: 6
2825         field: fw.pitch_to_throttle_smooth
2826         min: 0
2827         max: 9
2828       - name: fw_min_throttle_down_pitch
2829         description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
2830         default_value: 0
2831         field: fw.minThrottleDownPitchAngle
2832         min: 0
2833         max: 450
2834       - name: nav_fw_pitch2thr_threshold
2835         description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
2836         default_value: 50
2837         field: fw.pitch_to_throttle_thresh
2838         min: 0
2839         max: 900
2840       - name: nav_fw_loiter_radius
2841         description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
2842         default_value: 7500
2843         field: fw.loiter_radius
2844         min: 0
2845         max: 30000
2846       - name: fw_loiter_direction
2847         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."
2848         default_value: "RIGHT"
2849         field: fw.loiter_direction
2850         table: direction
2851       - name: nav_fw_cruise_speed
2852         description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
2853         default_value: 0
2854         field: fw.cruise_speed
2855         min: 0
2856         max: 65535
2857       - name: nav_fw_control_smoothness
2858         description: "How smoothly the autopilot controls the airplane to correct the navigation error"
2859         default_value: 0
2860         field: fw.control_smoothness
2861         min: 0
2862         max: 9
2863       - name: nav_fw_land_dive_angle
2864         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"
2865         default_value: 2
2866         field: fw.land_dive_angle
2867         min: -20
2868         max: 20
2869       - name: nav_fw_launch_velocity
2870         description: "Forward velocity threshold for swing-launch detection [cm/s]"
2871         default_value: 300
2872         field: fw.launch_velocity_thresh
2873         min: 100
2874         max: 10000
2875       - name: nav_fw_launch_accel
2876         description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s"
2877         default_value: 1863
2878         field: fw.launch_accel_thresh
2879         min: 1000
2880         max: 20000
2881       - name: nav_fw_launch_max_angle
2882         description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
2883         default_value: 45
2884         field: fw.launch_max_angle
2885         min: 5
2886         max: 180
2887       - name: nav_fw_launch_detect_time
2888         description: "Time for which thresholds have to breached to consider launch happened [ms]"
2889         default_value: 40
2890         field: fw.launch_time_thresh
2891         min: 10
2892         max: 1000
2893       - name: nav_fw_launch_idle_motor_delay
2894         description: "Delay between raising throttle and motor starting at idle throttle (ms)"
2895         default_value: 0
2896         field: fw.launch_idle_motor_timer
2897         min: 0
2898         max: 60000
2899       - name: nav_fw_launch_motor_delay
2900         description: "Delay between detected launch and launch sequence start and throttling up (ms)"
2901         default_value: 500
2902         field: fw.launch_motor_timer
2903         min: 0
2904         max: 5000
2905       - name: nav_fw_launch_spinup_time
2906         description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
2907         default_value: 100
2908         field: fw.launch_motor_spinup_time
2909         min: 0
2910         max: 1000
2911       - name: nav_fw_launch_end_time
2912         description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
2913         default_value: 3000
2914         field: fw.launch_end_time
2915         min: 0
2916         max: 5000
2917       - name: nav_fw_launch_min_time
2918         description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
2919         default_value: 0
2920         field: fw.launch_min_time
2921         min: 0
2922         max: 60000
2923       - name: nav_fw_launch_timeout
2924         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)"
2925         default_value: 5000
2926         field: fw.launch_timeout
2927         max: 60000
2928       - name: nav_fw_launch_max_altitude
2929         description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
2930         default_value: 0
2931         field: fw.launch_max_altitude
2932         min: 0
2933         max: 60000
2934       - name: nav_fw_launch_climb_angle
2935         description: "Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
2936         default_value: 18
2937         field: fw.launch_climb_angle
2938         min: 5
2939         max: 45
2940       - name: nav_fw_launch_manual_throttle
2941         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)."
2942         default_value: OFF
2943         field: fw.launch_manual_throttle
2944         type: bool
2945       - name: nav_fw_launch_land_abort_deadband
2946         description: "Launch and landing abort stick deadband in [r/c points], applied after r/c deadband and expo. The Roll/Pitch stick needs to be deflected beyond this deadband to abort the launch or landing."
2947         default_value: 100
2948         field: fw.launch_land_abort_deadband
2949         min: 2
2950         max: 250
2951       - name: nav_fw_allow_manual_thr_increase
2952         description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
2953         default_value: OFF
2954         field: fw.allow_manual_thr_increase
2955         type: bool
2956       - name: nav_use_fw_yaw_control
2957         description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
2958         default_value: OFF
2959         field: fw.useFwNavYawControl
2960         type: bool
2961       - name: nav_fw_yaw_deadband
2962         description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
2963         default_value: 0
2964         field: fw.yawControlDeadband
2965         min: 0
2966         max: 90
2968   - name: PG_TELEMETRY_CONFIG
2969     type: telemetryConfig_t
2970     headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/sim.h"]
2971     condition: USE_TELEMETRY
2972     members:
2973       - name: telemetry_switch
2974         description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
2975         default_value: OFF
2976         type: bool
2977       - name: telemetry_inverted
2978         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."
2979         default_value: OFF
2980         type: bool
2981       - name: frsky_pitch_roll
2982         description: "S.Port telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
2983         default_value: OFF
2984         type: bool
2985       - name: report_cell_voltage
2986         description: "S.Port and IBUS telemetry: Send the average cell voltage if set to ON"
2987         default_value: OFF
2988         type: bool
2989       - name: hott_alarm_sound_interval
2990         description: "Battery alarm delay in seconds for Hott telemetry"
2991         default_value: 5
2992         field: hottAlarmSoundInterval
2993         min: 0
2994         max: 120
2995       - name: telemetry_halfduplex
2996         description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
2997         default_value: ON
2998         field: halfDuplex
2999         type: bool
3000       - name: smartport_fuel_unit
3001         description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]"
3002         default_value: "MAH"
3003         field: smartportFuelUnit
3004         condition: USE_TELEMETRY_SMARTPORT
3005         type: uint8_t
3006         table: smartport_fuel_unit
3007       - name: ibus_telemetry_type
3008         description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
3009         default_value: 0
3010         field: ibusTelemetryType
3011         min: 0
3012         max: 255
3013       - name: ltm_update_rate
3014         description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details."
3015         default_value: "NORMAL"
3016         field: ltmUpdateRate
3017         condition: USE_TELEMETRY_LTM
3018         table: ltm_rates
3019       - name: sim_ground_station_number
3020         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."
3021         default_value: ""
3022         field: simGroundStationNumber
3023         condition: USE_TELEMETRY_SIM
3024       - name: sim_pin
3025         description: "PIN code for the SIM module"
3026         default_value: "0000"
3027         field: simPin
3028         condition: USE_TELEMETRY_SIM
3029       - name: sim_transmit_interval
3030         description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
3031         default_value: 60
3032         field: simTransmitInterval
3033         condition: USE_TELEMETRY_SIM
3034         type: uint16_t
3035         min: SIM_MIN_TRANSMIT_INTERVAL
3036         max: 65535
3037       - name: sim_transmit_flags
3038         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`"
3039         default_value: :SIM_TX_FLAG_FAILSAFE
3040         field: simTransmitFlags
3041         condition: USE_TELEMETRY_SIM
3042         max: 63
3043       - name: acc_event_threshold_high
3044         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."
3045         default_value: 0
3046         field: accEventThresholdHigh
3047         condition: USE_TELEMETRY_SIM
3048         type: uint16_t
3049         min: 0
3050         max: 65535
3051       - name: acc_event_threshold_low
3052         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."
3053         default_value: 0
3054         field: accEventThresholdLow
3055         condition: USE_TELEMETRY_SIM
3056         type: uint16_t
3057         min: 0
3058         max: 900
3059       - name: acc_event_threshold_neg_x
3060         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."
3061         default_value: 0
3062         field: accEventThresholdNegX
3063         condition: USE_TELEMETRY_SIM
3064         type: uint16_t
3065         min: 0
3066         max: 65535
3067       - name: sim_low_altitude
3068         description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
3069         default_value: -32767
3070         field: simLowAltitude
3071         condition: USE_TELEMETRY_SIM
3072         type: int16_t
3073         min: INT16_MIN
3074         max: INT16_MAX
3075       - name: mavlink_ext_status_rate
3076         field: mavlink.extended_status_rate
3077         type: uint8_t
3078         min: 0
3079         max: 255
3080         default_value: 2
3081       - name: mavlink_rc_chan_rate
3082         field: mavlink.rc_channels_rate
3083         type: uint8_t
3084         min: 0
3085         max: 255
3086         default_value: 5
3087       - name: mavlink_pos_rate
3088         field: mavlink.position_rate
3089         type: uint8_t
3090         min: 0
3091         max: 255
3092         default_value: 2
3093       - name: mavlink_extra1_rate
3094         field: mavlink.extra1_rate
3095         type: uint8_t
3096         min: 0
3097         max: 255
3098         default_value: 10
3099       - name: mavlink_extra2_rate
3100         field: mavlink.extra2_rate
3101         type: uint8_t
3102         min: 0
3103         max: 255
3104         default_value: 2
3105       - name: mavlink_extra3_rate
3106         field: mavlink.extra3_rate
3107         type: uint8_t
3108         min: 0
3109         max: 255
3110         default_value: 1
3111       - name: mavlink_version
3112         field: mavlink.version
3113         description: "Version of MAVLink to use"
3114         type: uint8_t
3115         min: 1
3116         max: 2
3117         default_value: 2
3119   - name: PG_LED_STRIP_CONFIG
3120     type: ledStripConfig_t
3121     headers: ["common/color.h", "io/ledstrip.h"]
3122     condition: USE_LED_STRIP
3123     members:
3124       - name: ledstrip_visual_beeper
3125         description: ""
3126         default_value: OFF
3127         type: bool
3129   - name: PG_OSD_CONFIG
3130     type: osdConfig_t
3131     headers: ["io/osd.h", "drivers/osd.h"]
3132     condition: USE_OSD
3133     members:
3134       - name: osd_telemetry
3135         description: "To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`"
3136         table: osd_telemetry
3137         field: telemetry
3138         type: uint8_t
3139         default_value: "OFF"
3140       - name: osd_video_system
3141         description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT`"
3142         default_value: "AUTO"
3143         table: osd_video_system
3144         field: video_system
3145         type: uint8_t
3146       - name: osd_row_shiftdown
3147         description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
3148         default_value: 0
3149         field: row_shiftdown
3150         min: 0
3151         max: 1
3152       - name: osd_msp_displayport_fullframe_interval
3153         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)"
3154         default_value: 10
3155         min: -1
3156         max: 600
3157         type: int16_t
3158         field: msp_displayport_fullframe_interval
3159       - name: osd_units
3160         description: "IMPERIAL, METRIC, UK"
3161         default_value: "METRIC"
3162         field: units
3163         table: osd_unit
3164         type: uint8_t
3165       - name: osd_stats_energy_unit
3166         description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)"
3167         default_value: "MAH"
3168         field: stats_energy_unit
3169         table: osd_stats_energy_unit
3170         type: uint8_t
3171       - name: osd_stats_min_voltage_unit
3172         description: "Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats."
3173         default_value: "BATTERY"
3174         field: stats_min_voltage_unit
3175         table: osd_stats_min_voltage_unit
3176         type: uint8_t
3177       - name: osd_stats_page_auto_swap_time
3178         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."
3179         default_value: 3
3180         field: stats_page_auto_swap_time
3181         min: 0
3182         max: 10
3183       - name: osd_rssi_alarm
3184         description: "Value below which to make the OSD RSSI indicator blink"
3185         default_value: 20
3186         field: rssi_alarm
3187         min: 0
3188         max: 100
3189       - name: osd_time_alarm
3190         description: "Value above which to make the OSD flight time indicator blink (minutes)"
3191         default_value: 10
3192         field: time_alarm
3193         min: 0
3194         max: 600
3195       - name: osd_alt_alarm
3196         description: "Value above which to make the OSD relative altitude indicator blink (meters)"
3197         default_value: 100
3198         field: alt_alarm
3199         min: 0
3200         max: 10000
3201       - name: osd_dist_alarm
3202         description: "Value above which to make the OSD distance from home indicator blink (meters)"
3203         default_value: 1000
3204         field: dist_alarm
3205         min: 0
3206         max: 50000
3207       - name: osd_neg_alt_alarm
3208         description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
3209         default_value: 5
3210         field: neg_alt_alarm
3211         min: 0
3212         max: 10000
3213       - name: osd_current_alarm
3214         description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
3215         default_value: 0
3216         field: current_alarm
3217         min: 0
3218         max: 255
3219       - name: osd_gforce_alarm
3220         description: "Value above which the OSD g force indicator will blink (g)"
3221         default_value: 5
3222         field: gforce_alarm
3223         min: 0
3224         max: 20
3225       - name: osd_gforce_axis_alarm_min
3226         description: "Value under which the OSD axis g force indicators will blink (g)"
3227         default_value: -5
3228         field: gforce_axis_alarm_min
3229         min: -20
3230         max: 20
3231       - name: osd_gforce_axis_alarm_max
3232         description: "Value above which the OSD axis g force indicators will blink (g)"
3233         default_value: 5
3234         field: gforce_axis_alarm_max
3235         min: -20
3236         max: 20
3237       - name: osd_imu_temp_alarm_min
3238         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3239         default_value: -200
3240         field: imu_temp_alarm_min
3241         min: -550
3242         max: 1250
3243       - name: osd_imu_temp_alarm_max
3244         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3245         default_value: 600
3246         field: imu_temp_alarm_max
3247         min: -550
3248         max: 1250
3249       - name: osd_esc_temp_alarm_max
3250         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3251         default_value: 900
3252         field: esc_temp_alarm_max
3253         min: -550
3254         max: 1500
3255       - name: osd_esc_temp_alarm_min
3256         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3257         default_value: -200
3258         field: esc_temp_alarm_min
3259         min: -550
3260         max: 1500
3261       - name: osd_baro_temp_alarm_min
3262         description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3263         default_value: -200
3264         field: baro_temp_alarm_min
3265         condition: USE_BARO
3266         min: -550
3267         max: 1250
3268       - name: osd_baro_temp_alarm_max
3269         description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3270         default_value: 600
3271         field: baro_temp_alarm_max
3272         condition: USE_BARO
3273         min: -550
3274         max: 1250
3275       - name: osd_snr_alarm
3276         condition: USE_SERIALRX_CRSF
3277         description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
3278         default_value: 4
3279         field: snr_alarm
3280         min: -20
3281         max: 10
3282       - name: osd_link_quality_alarm
3283         condition: USE_SERIALRX_CRSF
3284         description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
3285         default_value: 70
3286         field: link_quality_alarm
3287         min: 0
3288         max: 100
3289       - name: osd_rssi_dbm_alarm
3290         condition: USE_SERIALRX_CRSF
3291         description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
3292         default_value: 0
3293         field: rssi_dbm_alarm
3294         min: -130
3295         max: 0
3296       - name: osd_rssi_dbm_max
3297         condition: USE_SERIALRX_CRSF
3298         description: "RSSI dBm upper end of curve. Perfect rssi (max) = 100%"
3299         default_value: -30
3300         field: rssi_dbm_max
3301         min: -50
3302         max: 0
3303       - name: osd_rssi_dbm_min
3304         condition: USE_SERIALRX_CRSF
3305         description: "RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%"
3306         default_value: -120
3307         field: rssi_dbm_min
3308         min: -130
3309         max: 0
3310       - name: osd_temp_label_align
3311         description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
3312         default_value: "LEFT"
3313         field: temp_label_align
3314         condition: USE_TEMPERATURE_SENSOR
3315         table: osd_alignment
3316         type: uint8_t
3317       - name: osd_airspeed_alarm_min
3318         condition: USE_PITOT
3319         description: "Airspeed under which the airspeed OSD element will start blinking (cm/s)"
3320         default_value: 0
3321         field: airspeed_alarm_min
3322         min: 0
3323         max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3324       - name: osd_airspeed_alarm_max
3325         condition: USE_PITOT
3326         description: "Airspeed above which the airspeed OSD element will start blinking (cm/s)"
3327         default_value: 0
3328         field: airspeed_alarm_max
3329         min: 0
3330         max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3331       - name: osd_ahi_reverse_roll
3332         description: "Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement."
3333         field: ahi_reverse_roll
3334         type: bool
3335         default_value: OFF
3336       - name: osd_ahi_max_pitch
3337         description: "Max pitch, in degrees, for OSD artificial horizon"
3338         default_value: 20
3339         field: ahi_max_pitch
3340         min: 10
3341         max: 90
3342         default_value: 20
3343       - name: osd_crosshairs_style
3344         description: "To set the visual type for the crosshair"
3345         default_value: "DEFAULT"
3346         field: crosshairs_style
3347         table: osd_crosshairs_style
3348         type: uint8_t
3349       - name: osd_crsf_lq_format
3350         description: "To select LQ format"
3351         default_value: "TYPE1"
3352         field: crsf_lq_format
3353         table: osd_crsf_lq_format
3354         type: uint8_t
3355       - name: osd_horizon_offset
3356         description: "To vertically adjust the whole OSD and AHI and scrolling bars"
3357         default_value: 0
3358         field: horizon_offset
3359         min: -2
3360         max: 2
3361       - name: osd_camera_uptilt
3362         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)."
3363         default_value: 0
3364         field: camera_uptilt
3365         min: -40
3366         max: 80
3367       - name: osd_ahi_camera_uptilt_comp
3368         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)."
3369         default_value: OFF
3370         field: ahi_camera_uptilt_comp
3371         type: bool
3372       - name: osd_camera_fov_h
3373         description: "Horizontal field of view for the camera in degres"
3374         default_value: 135
3375         field: camera_fov_h
3376         min: 60
3377         max: 150
3378       - name: osd_camera_fov_v
3379         description: "Vertical field of view for the camera in degres"
3380         default_value: 85
3381         field: camera_fov_v
3382         min: 30
3383         max: 120
3384       - name: osd_hud_margin_h
3385         description: "Left and right margins for the hud area"
3386         default_value: 3
3387         field: hud_margin_h
3388         min: 0
3389         max: 4
3390       - name: osd_hud_margin_v
3391         description: "Top and bottom margins for the hud area"
3392         default_value: 3
3393         field: hud_margin_v
3394         min: 1
3395         max: 3
3396       - name: osd_hud_homing
3397         description: "To display little arrows around the crossair showing where the home point is in the hud"
3398         default_value: OFF
3399         field: hud_homing
3400         type: bool
3401       - name: osd_hud_homepoint
3402         description: "To 3D-display the home point location in the hud"
3403         default_value: OFF
3404         field: hud_homepoint
3405         type: bool
3406       - name: osd_hud_radar_disp
3407         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"
3408         default_value: 0
3409         field: hud_radar_disp
3410         min: 0
3411         max: 4
3412       - name: osd_hud_radar_range_min
3413         description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
3414         default_value: 3
3415         field: hud_radar_range_min
3416         min: 1
3417         max: 30
3418       - name: osd_hud_radar_range_max
3419         description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
3420         default_value: 4000
3421         field: hud_radar_range_max
3422         min: 100
3423         max: 9990
3424       - name: osd_hud_radar_alt_difference_display_time
3425         description: "Time in seconds to display the altitude difference in radar"
3426         field: hud_radar_alt_difference_display_time
3427         min: 0
3428         max: 10
3429         default_value: 3
3430       - name: osd_hud_radar_distance_display_time
3431         description: "Time in seconds to display the distance in radar"
3432         field: hud_radar_distance_display_time
3433         min: 1
3434         max: 10
3435         default_value: 3
3436       - name: osd_hud_wp_disp
3437         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)"
3438         default_value: 0
3439         field: hud_wp_disp
3440         min: 0
3441         max: 3
3442       - name: osd_left_sidebar_scroll
3443         field: left_sidebar_scroll
3444         table: osd_sidebar_scroll
3445         type: uint8_t
3446         default_value: NONE
3447       - name: osd_right_sidebar_scroll
3448         field: right_sidebar_scroll
3449         table: osd_sidebar_scroll
3450         type: uint8_t
3451         default_value: NONE
3452       - name: osd_sidebar_scroll_arrows
3453         field: sidebar_scroll_arrows
3454         type: bool
3455         default_value: OFF
3456       - name: osd_main_voltage_decimals
3457         description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
3458         default_value: 1
3459         field: main_voltage_decimals
3460         min: 1
3461         max: 2
3462       - name: osd_coordinate_digits
3463         field: coordinate_digits
3464         min: 8
3465         max: 11
3466         default_value: 9
3468       - name: osd_adsb_distance_warning
3469         description: "Distance in meters of ADSB aircraft that is displayed"
3470         default_value: 20000
3471         condition: USE_ADSB
3472         field: adsb_distance_warning
3473         min: 1
3474         max: 64000
3475         type: uint16_t
3476       - name: osd_adsb_distance_alert
3477         description: "Distance inside which ADSB data flashes for proximity warning"
3478         default_value: 3000
3479         condition: USE_ADSB
3480         field: adsb_distance_alert
3481         min: 1
3482         max: 64000
3483         type: uint16_t
3484       - name: osd_adsb_ignore_plane_above_me_limit
3485         description: "Ignore adsb planes above, limit, 0 disabled (meters)"
3486         default_value: 0
3487         condition: USE_ADSB
3488         field: adsb_ignore_plane_above_me_limit
3489         min: 0
3490         max: 64000
3491         type: uint16_t
3493       - name: osd_estimations_wind_compensation
3494         description: "Use wind estimation for remaining flight time/distance estimation"
3495         default_value: ON
3496         condition: USE_WIND_ESTIMATOR
3497         field: estimations_wind_compensation
3498         type: bool
3500       - name: osd_failsafe_switch_layout
3501         description: "If enabled the OSD automatically switches to the first layout during failsafe"
3502         default_value: OFF
3503         type: bool
3505       - name: osd_plus_code_digits
3506         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."
3507         field: plus_code_digits
3508         default_value: 11
3509         min: 10
3510         max: 13
3511       - name: osd_plus_code_short
3512         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."
3513         field: plus_code_short
3514         default_value: "0"
3515         table: osd_plus_code_short
3517       - name: osd_ahi_style
3518         description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
3519         field: ahi_style
3520         default_value: "DEFAULT"
3521         table: osd_ahi_style
3522         type: uint8_t
3524       - name: osd_force_grid
3525         field: force_grid
3526         type: bool
3527         default_value: OFF
3528         description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
3530       - name: osd_ahi_bordered
3531         field: ahi_bordered
3532         type: bool
3533         description: Shows a border/corners around the AHI region (pixel OSD only)
3534         default_value: OFF
3536       - name: osd_ahi_width
3537         field: ahi_width
3538         max: 255
3539         description: AHI width in pixels (pixel OSD only)
3540         default_value: 132
3542       - name: osd_ahi_height
3543         field: ahi_height
3544         max: 255
3545         description: AHI height in pixels (pixel OSD only)
3546         default_value: 162
3548       - name: osd_ahi_vertical_offset
3549         field: ahi_vertical_offset
3550         min: -128
3551         max: 127
3552         description: AHI vertical offset from center (pixel OSD only)
3553         default_value: -18
3555       - name: osd_sidebar_horizontal_offset
3556         field: sidebar_horizontal_offset
3557         min: -128
3558         max: 127
3559         default_value: 0
3560         description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
3562       - name: osd_left_sidebar_scroll_step
3563         field: left_sidebar_scroll_step
3564         max: 255
3565         default_value: 0
3566         description: How many units each sidebar step represents. 0 means the default value for the scroll type.
3568       - name: osd_right_sidebar_scroll_step
3569         field: right_sidebar_scroll_step
3570         max: 255
3571         default_value: 0
3572         description: Same as left_sidebar_scroll_step, but for the right sidebar
3574       - name: osd_sidebar_height
3575         field: sidebar_height
3576         min: 0
3577         max: 5
3578         default_value: 3
3579         description: Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
3581       - name: osd_ahi_pitch_interval
3582         field: ahi_pitch_interval
3583         min: 0
3584         max: 30
3585         default_value: 0
3586         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)
3588       - name: osd_home_position_arm_screen
3589         type: bool
3590         default_value: ON
3591         description: Should home position coordinates be displayed on the arming screen.
3593       - name: osd_pan_servo_index
3594         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.
3595         field: pan_servo_index
3596         min: 0
3597         max: 16
3598         default_value: 0
3600       - name: osd_pan_servo_pwm2centideg
3601         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.
3602         field: pan_servo_pwm2centideg
3603         default_value: 0
3604         min: -36
3605         max: 36
3607       - name: osd_pan_servo_offcentre_warning
3608         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.
3609         field: pan_servo_offcentre_warning
3610         min: 0
3611         max: 45
3612         default_value: 10
3614       - name: osd_pan_servo_indicator_show_degrees
3615         description: Show the degress of offset from centre on the pan servo OSD display element.
3616         field: pan_servo_indicator_show_degrees
3617         type: bool
3618         default_value: OFF
3620       - name: osd_esc_rpm_precision
3621         description: Number of characters used to display the RPM value.
3622         field: esc_rpm_precision
3623         min: 3
3624         max: 6
3625         default_value: 3
3627       - name: osd_mah_precision
3628         description: Number of digits used for mAh precision. Currently used by mAh Used and Battery Remaining Capacity
3629         field: mAh_precision
3630         min: 4
3631         max: 6
3632         default_value: 4
3634       - name: osd_use_pilot_logo
3635         description: Use custom pilot logo with/instead of the INAV logo. The pilot logo must be characters 473 to 511
3636         field: use_pilot_logo
3637         type: bool
3638         default_value: OFF
3640       - name: osd_inav_to_pilot_logo_spacing
3641         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.
3642         field: inav_to_pilot_logo_spacing
3643         min: 0
3644         max: 20
3645         default_value: 8
3647       - name: osd_arm_screen_display_time
3648         description: Amount of time to display the arm screen [ms]
3649         field: arm_screen_display_time
3650         min: 1000
3651         max: 5000
3652         default_value: 1500
3654       - name: osd_switch_indicator_zero_name
3655         description: "Character to use for OSD switch incicator 0."
3656         field: osd_switch_indicator0_name
3657         type: string
3658         max: 5
3659         default_value: "FLAP"
3661       - name: osd_switch_indicator_one_name
3662         description: "Character to use for OSD switch incicator 1."
3663         field: osd_switch_indicator1_name
3664         type: string
3665         max: 5
3666         default_value: "GEAR"
3668       - name: osd_switch_indicator_two_name
3669         description: "Character to use for OSD switch incicator 2."
3670         field: osd_switch_indicator2_name
3671         type: string
3672         max: 5
3673         default_value: "CAM"
3675       - name: osd_switch_indicator_three_name
3676         description: "Character to use for OSD switch incicator 3."
3677         field: osd_switch_indicator3_name
3678         type: string
3679         max: 5
3680         default_value: "LIGT"
3682       - name: osd_switch_indicator_zero_channel
3683         description: "RC Channel to use for OSD switch indicator 0."
3684         field: osd_switch_indicator0_channel
3685         min: 5
3686         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3687         default_value: 5
3689       - name: osd_switch_indicator_one_channel
3690         description: "RC Channel to use for OSD switch indicator 1."
3691         field: osd_switch_indicator1_channel
3692         min: 5
3693         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3694         default_value: 5
3696       - name: osd_switch_indicator_two_channel
3697         description: "RC Channel to use for OSD switch indicator 2."
3698         field: osd_switch_indicator2_channel
3699         min: 5
3700         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3701         default_value: 5
3703       - name: osd_switch_indicator_three_channel
3704         description: "RC Channel to use for OSD switch indicator 3."
3705         field: osd_switch_indicator3_channel
3706         min: 5
3707         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3708         default_value: 5
3710       - name: osd_switch_indicators_align_left
3711         description: "Align text to left of switch indicators"
3712         field: osd_switch_indicators_align_left
3713         type: bool
3714         default_value: ON
3716       - name: osd_system_msg_display_time
3717         description: System message display cycle time for multiple messages (milliseconds).
3718         field: system_msg_display_time
3719         default_value: 1000
3720         min: 500
3721         max: 5000
3723   - name: PG_OSD_COMMON_CONFIG
3724     type: osdCommonConfig_t
3725     headers: ["io/osd_common.h"]
3726     condition: USE_OSD || USE_DJI_HD_OSD
3727     members:
3728       - name: osd_speed_source
3729         description: "Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR"
3730         default_value: "GROUND"
3731         field: speedSource
3732         table: osdSpeedSource
3733         type: uint8_t
3735   - name: PG_SYSTEM_CONFIG
3736     type: systemConfig_t
3737     headers: ["fc/config.h"]
3738     members:
3739       - name: i2c_speed
3740         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)"
3741         default_value: "400KHZ"
3742         condition: USE_I2C
3743         table: i2c_speed
3744       - name: cpu_underclock
3745         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"
3746         default_value: OFF
3747         field: cpuUnderclock
3748         condition: USE_UNDERCLOCK
3749         type: bool
3750       - name: debug_mode
3751         description: "Defines debug values exposed in debug variables (developer / debugging setting)"
3752         default_value: "NONE"
3753         table: debug_modes
3754       - name: ground_test_mode
3755         description: "For developer ground test use. Disables motors, sets heading status = Trusted on FW."
3756         condition: USE_DEV_TOOLS
3757         default_value: OFF
3758         field: groundTestMode
3759         type: bool
3760       - name: throttle_tilt_comp_str
3761         description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
3762         default_value: 0
3763         field: throttle_tilt_compensation_strength
3764         min: 0
3765         max: 100
3766       - name: name
3767         description: "Craft name"
3768         default_value: ""
3769         type: string
3770         field: craftName
3771         max: MAX_NAME_LENGTH
3772       - name: pilot_name
3773         description: "Pilot name"
3774         default_value: ""
3775         type: string
3776         field: pilotName
3777         max: MAX_NAME_LENGTH
3779   - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
3780     type: modeActivationOperatorConfig_t
3781     headers: ["fc/rc_modes.h"]
3782     members:
3783       - name: mode_range_logic_operator
3784         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."
3785         default_value: "OR"
3786         field: modeActivationOperator
3787         table: aux_operator
3788         type: uint8_t
3790   - name: PG_STATS_CONFIG
3791     type: statsConfig_t
3792     headers: ["fc/stats.h"]
3793     condition: USE_STATS
3794     members:
3795       - name: stats
3796         description: "General switch of the statistics recording feature (a.k.a. odometer)"
3797         default_value: OFF
3798         field: stats_enabled
3799         type: bool
3800       - name: stats_total_time
3801         description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
3802         default_value: 0
3803         max: INT32_MAX
3804       - name: stats_total_dist
3805         description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
3806         default_value: 0
3807         max: INT32_MAX
3808       - name: stats_total_energy
3809         description: "Total energy consumption [in mWh]. The value is updated on every disarm when \"stats\" are enabled."
3810         max: INT32_MAX
3811         condition: USE_ADC
3812         default_value: 0
3814   - name: PG_TIME_CONFIG
3815     type: timeConfig_t
3816     headers: ["common/time.h"]
3817     members:
3818       - name: tz_offset
3819         description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
3820         default_value: 0
3821         min: -720
3822         max: 840
3823       - name: tz_automatic_dst
3824         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`."
3825         default_value: "OFF"
3826         type: uint8_t
3827         table: tz_automatic_dst
3829   - name: PG_DISPLAY_CONFIG
3830     type: displayConfig_t
3831     headers: ["drivers/display.h"]
3832     members:
3833       - name: display_force_sw_blink
3834         description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
3835         default_value: OFF
3836         field: force_sw_blink
3837         type: bool
3839   - name: PG_VTX_CONFIG
3840     type: vtxConfig_t
3841     headers: ["io/vtx_control.h"]
3842     condition: USE_VTX_CONTROL
3843     members:
3844       - name: vtx_halfduplex
3845         description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
3846         default_value: ON
3847         field: halfDuplex
3848         type: bool
3849       - name: vtx_smartaudio_early_akk_workaround
3850         description: "Enable workaround for early AKK SAudio-enabled VTX bug."
3851         default_value: ON
3852         field: smartAudioEarlyAkkWorkaroundEnable
3853         type: bool
3854       - name: vtx_smartaudio_alternate_softserial_method
3855         description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier."
3856         default_value: ON
3857         field: smartAudioAltSoftSerialMethod
3858         type: bool
3859       - name: vtx_softserial_shortstop
3860         description: "Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes."
3861         default_value: OFF
3862         field: softSerialShortStop
3863         type: bool
3864       - name: vtx_smartaudio_stopbits
3865         description: "Set stopbit count for serial (TBS Sixty9 SmartAudio 2.1 require value of 1 bit)"
3866         default_value: 2
3867         field: smartAudioStopBits
3868         min: 1
3869         max: 2
3871   - name: PG_VTX_SETTINGS_CONFIG
3872     type: vtxSettingsConfig_t
3873     headers: ["drivers/vtx_common.h", "io/vtx.h"]
3874     condition: USE_VTX_SMARTAUDIO || USE_VTX_TRAMP
3875     members:
3876       - name: vtx_band
3877         description: "Configure the VTX band. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
3878         default_value: 1
3879         field: band
3880         min: VTX_SETTINGS_MIN_BAND
3881         max: VTX_SETTINGS_MAX_BAND
3882       - name: vtx_channel
3883         description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
3884         default_value: 1
3885         field: channel
3886         min: VTX_SETTINGS_MIN_CHANNEL
3887         max: VTX_SETTINGS_MAX_CHANNEL
3888       - name: vtx_power
3889         description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
3890         default_value: 1
3891         field: power
3892         min: VTX_SETTINGS_MIN_POWER
3893         max: VTX_SETTINGS_MAX_POWER
3894       - name: vtx_low_power_disarm
3895         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."
3896         default_value: "OFF"
3897         field: lowPowerDisarm
3898         table: vtx_low_power_disarm
3899         type: uint8_t
3900       - name: vtx_pit_mode_chan
3901         field: pitModeChan
3902         min: VTX_SETTINGS_MIN_CHANNEL
3903         max: VTX_SETTINGS_MAX_CHANNEL
3904         default_value: 1
3905       - name: vtx_max_power_override
3906         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"
3907         default_value: 0
3908         field: maxPowerOverride
3909         min: 0
3910         max: 10000
3911       - name: vtx_frequency_group
3912         field: frequencyGroup
3913         description: "VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz."
3914         table: vtx_frequency_groups
3915         min: 0
3916         max: 2
3917         default_value: FREQUENCYGROUP_5G8
3919   - name: PG_PINIOBOX_CONFIG
3920     type: pinioBoxConfig_t
3921     headers: ["io/piniobox.h"]
3922     condition: USE_PINIOBOX
3923     members:
3924       - name: pinio_box1
3925         field: permanentId[0]
3926         description: "Mode assignment for PINIO#1"
3927         default_value: "target specific"
3928         min: 0
3929         max: 255
3930         default_value: :BOX_PERMANENT_ID_NONE
3931         type: uint8_t
3932       - name: pinio_box2
3933         field: permanentId[1]
3934         default_value: "target specific"
3935         description: "Mode assignment for PINIO#1"
3936         min: 0
3937         max: 255
3938         default_value: :BOX_PERMANENT_ID_NONE
3939         type: uint8_t
3940       - name: pinio_box3
3941         field: permanentId[2]
3942         default_value: "target specific"
3943         description: "Mode assignment for PINIO#1"
3944         min: 0
3945         max: 255
3946         default_value: :BOX_PERMANENT_ID_NONE
3947         type: uint8_t
3948       - name: pinio_box4
3949         field: permanentId[3]
3950         default_value: "target specific"
3951         description: "Mode assignment for PINIO#1"
3952         min: 0
3953         max: 255
3954         default_value: :BOX_PERMANENT_ID_NONE
3955         type: uint8_t
3957   - name: PG_LOG_CONFIG
3958     type: logConfig_t
3959     headers: ["common/log.h"]
3960     condition: USE_LOG
3961     members:
3962         - name: log_level
3963           field: level
3964           table: log_level
3965           description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
3966           default_value: "ERROR"
3967         - name: log_topics
3968           field: topics
3969           min: 0
3970           max: UINT32_MAX
3971           description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
3972           default_value: 0
3974   - name: PG_ESC_SENSOR_CONFIG
3975     type: escSensorConfig_t
3976     headers: ["sensors/esc_sensor.h"]
3977     condition: USE_ESC_SENSOR
3978     members:
3979         - name: esc_sensor_listen_only
3980           default_value: OFF
3981           description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
3982           field: listenOnly
3983           type: bool
3984           default_value: OFF
3986   - name: PG_SMARTPORT_MASTER_CONFIG
3987     type: smartportMasterConfig_t
3988     headers: ["io/smartport_master.h"]
3989     condition: USE_SMARTPORT_MASTER
3990     members:
3991       - name: smartport_master_halfduplex
3992         field: halfDuplex
3993         type: bool
3994         default_value: ON
3995       - name: smartport_master_inverted
3996         field: inverted
3997         type: bool
3998         default_value: OFF
4000   - name: PG_DJI_OSD_CONFIG
4001     type: djiOsdConfig_t
4002     headers: ["io/osd_dji_hd.h"]
4003     condition: USE_DJI_HD_OSD
4004     members:
4005         - name: dji_workarounds
4006           description: "Enables workarounds for different versions of MSP protocol used"
4007           field: proto_workarounds
4008           min: 0
4009           max: UINT8_MAX
4010           default_value: 1
4011         - name: dji_use_name_for_messages
4012           description: "Re-purpose the craft name field for messages."
4013           default_value: ON
4014           field: use_name_for_messages
4015           type: bool
4016         - name: dji_esc_temp_source
4017           description: "Re-purpose the ESC temperature field for IMU/BARO temperature"
4018           default_value: "ESC"
4019           field: esc_temperature_source
4020           table: djiOsdTempSource
4021           type: uint8_t
4022         - name: dji_message_speed_source
4023           description: "Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR"
4024           default_value: "3D"
4025           field: messageSpeedSource
4026           table: osdSpeedSource
4027           type: uint8_t
4028         - name: dji_rssi_source
4029           description: "Source of the DJI RSSI field: RSSI, CRSF_LQ"
4030           default_value: "RSSI"
4031           field: rssi_source
4032           table: djiRssiSource
4033           type: uint8_t
4034         - name: dji_use_adjustments
4035           description: "Show inflight adjustments in craft name field"
4036           default_value: OFF
4037           type: bool
4038           field: useAdjustments
4039         - name: dji_cn_alternating_duration
4040           description: "Alternating duration of craft name elements, in tenths of a second"
4041           default_value: 30
4042           min: 1
4043           max: 150
4044           field: craftNameAlternatingDuration
4045           type: uint8_t
4047   - name: PG_BEEPER_CONFIG
4048     type: beeperConfig_t
4049     headers: [ "fc/config.h" ]
4050     members:
4051       - name: dshot_beeper_enabled
4052         description: "Whether using DShot motors as beepers is enabled"
4053         default_value: ON
4054         field: dshot_beeper_enabled
4055         type: bool
4056       - name: dshot_beeper_tone
4057         description: "Sets the DShot beeper tone"
4058         min: 1
4059         max: 5
4060         default_value: 1
4061         field: dshot_beeper_tone
4062         type: uint8_t
4063       - name: beeper_pwm_mode
4064         field: pwmMode
4065         type: bool
4066         default_value: OFF
4067         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"
4069   - name: PG_POWER_LIMITS_CONFIG
4070     type: powerLimitsConfig_t
4071     headers: ["flight/power_limits.h"]
4072     condition: USE_POWER_LIMITS
4073     members:
4074       - name: limit_pi_p
4075         description: "Throttle attenuation PI control P term"
4076         default_value: 100
4077         field: piP
4078         max: 10000
4079       - name: limit_pi_i
4080         description: "Throttle attenuation PI control I term"
4081         default_value: 100
4082         field: piI
4083         max: 10000
4084       - name: limit_attn_filter_cutoff
4085         description: "Throttle attenuation PI control output filter cutoff frequency"
4086         default_value: 1.2
4087         field: attnFilterCutoff
4088         max: 100
4090   - name: PG_LEDPIN_CONFIG
4091     type: ledPinConfig_t
4092     headers: ["drivers/light_ws2811strip.h"]
4093     members:
4094       - name: led_pin_pwm_mode
4095         condition: USE_LED_STRIP
4096         description: "PWM mode of LED pin."
4097         default_value: "SHARED_LOW"
4098         field: led_pin_pwm_mode
4099         table: led_pin_pwm_mode
4101   - name: PG_OSD_JOYSTICK_CONFIG
4102     type: osdJoystickConfig_t
4103     headers: ["io/osd_joystick.h"]
4104     condition: USE_RCDEVICE && USE_LED_STRIP
4105     members:
4106       - name: osd_joystick_enabled
4107         description: "Enable OSD Joystick emulation"
4108         default_value: OFF
4109         field: osd_joystick_enabled
4110         type: bool
4111       - name: osd_joystick_down
4112         description: "PWM value for DOWN key"
4113         default_value: 0
4114         field: osd_joystick_down
4115         min: 0
4116         max: 100
4117       - name: osd_joystick_up
4118         description: "PWM value for UP key"
4119         default_value: 48
4120         field: osd_joystick_up
4121         min: 0
4122         max: 100
4123       - name: osd_joystick_left
4124         description: "PWM value for LEFT key"
4125         default_value: 63
4126         field: osd_joystick_left
4127         min: 0
4128         max: 100
4129       - name: osd_joystick_right
4130         description: "PWM value for RIGHT key"
4131         default_value: 28
4132         field: osd_joystick_right
4133         min: 0
4134         max: 100
4135       - name: osd_joystick_enter
4136         description: "PWM value for ENTER key"
4137         default_value: 75
4138         field: osd_joystick_enter
4139         min: 0
4140         max: 100
4142   - name: PG_FW_AUTOLAND_CONFIG
4143     type: navFwAutolandConfig_t
4144     headers: ["navigation/navigation.h"]
4145     condition: USE_FW_AUTOLAND
4146     members: 
4147       - name: nav_fw_land_approach_length
4148         description: "Length of the final approach"
4149         default_value: 35000
4150         field: approachLength
4151         min: 100
4152         max: 100000
4153       - name: nav_fw_land_final_approach_pitch2throttle_mod
4154         description: "Modifier for pitch to throttle ratio at final approach. In Percent."
4155         default_value: 100
4156         field: finalApproachPitchToThrottleMod
4157         min: 100
4158         max: 400
4159       - name: nav_fw_land_glide_alt
4160         description: "Initial altitude of the glide phase"
4161         default_value: 200
4162         field: glideAltitude
4163         min: 100
4164         max: 5000
4165       - name: nav_fw_land_flare_alt
4166         description: "Initial altitude of the flare phase"
4167         default_value: 150
4168         field: flareAltitude
4169         min: 0
4170         max: 10000
4171       - name: nav_fw_land_glide_pitch
4172         description: "Pitch value for glide phase. In degrees."
4173         default_value: 0
4174         field: glidePitch
4175         min: -15
4176         max: 45
4177       - name: nav_fw_land_flare_pitch
4178         description: "Pitch value for flare phase. In degrees"
4179         default_value: 8
4180         field: flarePitch
4181         min: -15
4182         max: 45
4183       - name: nav_fw_land_max_tailwind
4184         description: "Max. tailwind (in cm/s) if no landing direction with downwind is available"
4185         default_value: 140
4186         field: maxTailwind
4187         min: 0
4188         max: 3000