Merge branch 'master' into abo_stats_pages_auto_swap
[inav.git] / src / main / fc / settings.yaml
blob9778aa038c0f70b752dbf41d5f090cc6873cc788
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", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "FAKE"]
8     enum: accelerationSensor_e
9   - name: rangefinder_hardware
10     values: ["NONE", "HCSR04", "SRF10", "INAV_I2C", "VL53L0X", "MSP", "UNUSED", "BENEWAKE", "VL53L1X", "US42"]
11     enum: rangefinderType_e
12   - name: secondary_imu_hardware
13     values: ["NONE", "BNO055", "BNO055_SERIAL"]
14     enum: secondaryImuType_e
15   - name: mag_hardware
16     values: ["NONE", "AUTO", "HMC5883", "AK8975", "GPSMAG", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", FAKE"]
17     enum: magSensor_e
18   - name: opflow_hardware
19     values: ["NONE", "CXOF", "MSP", "FAKE"]
20     enum: opticalFlowSensor_e
21   - name: baro_hardware
22     values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "MSP", "FAKE"]
23     enum: baroSensor_e
24   - name: pitot_hardware
25     values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
26     enum: pitotSensor_e
27   - name: receiver_type
28     values: ["NONE", "PPM", "SERIAL", "MSP", "SPI", "UNUSED"]
29     enum: rxReceiverType_e
30   - name: serial_rx
31     values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "SUMH", "XB-B", "XB-B-RJ01", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
32   - name: rx_spi_protocol
33     values: ["ELERES"]
34     enum: rx_spi_protocol_e
35   - name: blackbox_device
36     values: ["SERIAL", "SPIFLASH", "SDCARD"]
37   - name: motor_pwm_protocol
38     values: ["STANDARD", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "SERIALSHOT"]
39   - name: servo_protocol
40     values: ["PWM", "SERVO_DRIVER", "SBUS", "SBUS_PWM"]
41   - name: failsafe_procedure
42     values: ["SET-THR", "DROP", "RTH", "NONE"]
43   - name: current_sensor
44     values: ["NONE", "ADC", "VIRTUAL", "ESC"]
45     enum: currentSensor_e
46   - name: voltage_sensor
47     values: ["NONE", "ADC", "ESC"]
48     enum: voltageSensor_e
49   - name: gps_provider
50     values: ["NMEA", "UBLOX", "UNUSED", "NAZA", "UBLOX7", "MTK", "MSP"]
51     enum: gpsProvider_e
52   - name: gps_sbas_mode
53     values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"]
54     enum: sbasMode_e
55   - name: gps_dyn_model
56     values: ["PEDESTRIAN", "AIR_1G", "AIR_4G"]
57     enum: gpsDynModel_e
58   - name: reset_type
59     values: ["NEVER", "FIRST_ARM", "EACH_ARM"]
60   - name: direction
61     values: ["RIGHT", "LEFT", "YAW"]
62   - name: nav_user_control_mode
63     values: ["ATTI", "CRUISE"]
64   - name: nav_rth_alt_mode
65     values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST", "AT_LEAST_LINEAR_DESCENT"]
66   - name: osd_unit
67     values: ["IMPERIAL", "METRIC", "UK"]
68     enum: osd_unit_e
69   - name: osd_stats_energy_unit
70     values: ["MAH", "WH"]
71     enum: osd_stats_energy_unit_e
72   - name: osd_stats_min_voltage_unit
73     values: ["BATTERY", "CELL"]
74     enum: osd_stats_min_voltage_unit_e
75   - name: osd_video_system
76     values: ["AUTO", "PAL", "NTSC"]
77     enum: videoSystem_e
78   - name: osd_telemetry
79     values: ["OFF", "ON","TEST"]
80     enum: osd_telemetry_e    
81   - name: osd_alignment
82     values: ["LEFT", "RIGHT"]
83     enum: osd_alignment_e
84   - name: frsky_unit
85     values: ["METRIC", "IMPERIAL"]
86     enum: frskyUnit_e
87   - name: ltm_rates
88     values: ["NORMAL", "MEDIUM", "SLOW"]
89   - name: i2c_speed
90     values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"]
91   - name: debug_modes
92     values: ["NONE", "GYRO", "AGL", "FLOW_RAW",
93       "FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
94       "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
95       "ERPM", "RPM_FILTER", "RPM_FREQ", "NAV_YAW", "DYNAMIC_FILTER", "DYNAMIC_FILTER_FREQUENCY",
96       "IRLOCK", "CD", "KALMAN_GAIN", "PID_MEASUREMENT", "SPM_CELLS", "SPM_VS600", "SPM_VARIO", "PCF8574", "DYN_GYRO_LPF", "FW_D", "IMU2", "ALTITUDE",
97       "SMITH_COMPENSATOR"]
98   - name: async_mode
99     values: ["NONE", "GYRO", "ALL"]
100   - name: aux_operator
101     values: ["OR", "AND"]
102     enum: modeActivationOperator_e
103   - name: osd_crosshairs_style
104     values: ["DEFAULT", "AIRCRAFT", "TYPE3", "TYPE4", "TYPE5", "TYPE6", "TYPE7"]
105     enum: osd_crosshairs_style_e
106   - name: osd_sidebar_scroll
107     values: ["NONE", "ALTITUDE", "GROUND_SPEED", "HOME_DISTANCE"]
108     enum: osd_sidebar_scroll_e
109   - name: nav_rth_allow_landing
110     values: ["NEVER", "ALWAYS", "FS_ONLY"]
111     enum: navRTHAllowLanding_e
112   - name: bat_capacity_unit
113     values: ["MAH", "MWH"]
114     enum: batCapacityUnit_e
115   - name: bat_voltage_source
116     values: ["RAW", "SAG_COMP"]
117     enum: batVoltageSource_e
118   - name: smartport_fuel_unit
119     values: ["PERCENT", "MAH", "MWH"]
120     enum: smartportFuelUnit_e
121   - name: platform_type
122     values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
123     enum: flyingPlatformType_e
124   - name: tz_automatic_dst
125     values: ["OFF", "EU", "USA"]
126     enum: tz_automatic_dst_e
127   - name: vtx_low_power_disarm
128     values: ["OFF", "ON", "UNTIL_FIRST_ARM"]
129     enum: vtxLowerPowerDisarm_e
130   - name: filter_type
131     values: ["PT1", "BIQUAD"]
132   - name: log_level
133     values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"]
134   - name: iterm_relax
135     values: ["OFF", "RP", "RPY"]
136     enum: itermRelax_e
137   - name: airmodeHandlingType
138     values: ["STICK_CENTER", "THROTTLE_THRESHOLD", "STICK_CENTER_ONCE"]
139   - name: nav_extra_arming_safety
140     values: ["OFF", "ON", "ALLOW_BYPASS"]
141     enum: navExtraArmingSafety_e
142   - name: rssi_source
143     values: ["NONE", "AUTO", "ADC", "CHANNEL", "PROTOCOL", "MSP"]
144     enum: rssiSource_e
145   - name: dynamicFilterRangeTable
146     values: ["HIGH", "MEDIUM", "LOW"]
147     enum: dynamicFilterRange_e
148   - name: pidTypeTable
149     values: ["NONE", "PID", "PIFF", "AUTO"]
150     enum: pidType_e
151   - name: osd_ahi_style
152     values: ["DEFAULT", "LINE"]
153     enum: osd_ahi_style_e
154   - name: tristate
155     enum: tristate_e
156     values: ["AUTO", "ON", "OFF"]
157   - name: osd_crsf_lq_format
158     enum: osd_crsf_lq_format_e
159     values: ["TYPE1", "TYPE2"]
160   - name: off_on
161     values: ["OFF", "ON"]
162   - name: djiOsdTempSource
163     values: ["ESC", "IMU", "BARO"]
164     enum: djiOsdTempSource_e
165   - name: djiOsdSpeedSource
166     values: ["GROUND", "3D", "AIR"]
167     enum: djiOsdSpeedSource_e
168   - name: nav_overrides_motor_stop
169     enum: navOverridesMotorStop_e
170     values: ["OFF_ALWAYS", "OFF", "AUTO_ONLY", "ALL_NAV"]
171   - name: osd_plus_code_short
172     values: ["0", "2", "4", "6"]
173   - name: safehome_usage_mode
174     values: ["OFF", "RTH", "RTH_FS"]
175     enum: safehomeUsageMode_e
176   - name: nav_rth_climb_first
177     enum: navRTHClimbFirst_e
178     values: ["OFF", "ON", "ON_FW_SPIRAL"]
180 constants:
181   RPYL_PID_MIN: 0
182   RPYL_PID_MAX: 200
184   MANUAL_RATE_MIN: 0
185   MANUAL_RATE_MAX: 100
187   ROLL_PITCH_RATE_MIN: 6
188   ROLL_PITCH_RATE_MAX: 180
190 groups:
191   - name: PG_GYRO_CONFIG
192     type: gyroConfig_t
193     headers: ["sensors/gyro.h"]
194     members:
195       - name: looptime
196         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."
197         default_value: 1000
198         max: 9000
199       - name: align_gyro
200         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."
201         default_value: "DEFAULT"
202         field: gyro_align
203         type: uint8_t
204         table: alignment
205       - name: gyro_hardware_lpf
206         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."
207         default_value: "256HZ"
208         field: gyro_lpf
209         table: gyro_lpf
210       - name: gyro_lpf_hz
211         description: "Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value."
212         default_value: 60
213         field: gyro_soft_lpf_hz
214         max: 200
215       - name: gyro_lpf_type
216         description: "Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds."
217         default_value: "BIQUAD"
218         field: gyro_soft_lpf_type
219         table: filter_type
220       - name: moron_threshold
221         description: "When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered."
222         default_value: 32
223         field: gyroMovementCalibrationThreshold
224         max: 128
225       - name: gyro_notch_hz
226         field: gyro_notch_hz
227         max: 500
228         default_value: 0
229       - name: gyro_notch_cutoff
230         field: gyro_notch_cutoff
231         min: 1
232         max: 500
233         default_value: 1
234       - name: gyro_stage2_lowpass_hz
235         description: "Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz)"
236         default_value: 0
237         field: gyro_stage2_lowpass_hz
238         min: 0
239         max: 500
240       - name: gyro_stage2_lowpass_type
241         description: "Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
242         default_value: BIQUAD
243         field: gyro_stage2_lowpass_type
244         table: filter_type
245       - name: gyro_use_dyn_lpf
246         description: "Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position."
247         default_value: OFF
248         field: useDynamicLpf
249         type: bool
250       - name: gyro_dyn_lpf_min_hz
251         description: "Minimum frequency of the gyro Dynamic LPF"
252         default_value: 200
253         field: gyroDynamicLpfMinHz
254         min: 40
255         max: 400
256       - name: gyro_dyn_lpf_max_hz
257         description: "Maximum frequency of the gyro Dynamic LPF"
258         default_value: 500
259         field: gyroDynamicLpfMaxHz
260         min: 40
261         max: 1000
262       - name: gyro_dyn_lpf_curve_expo
263         description: "Expo value for the throttle-to-frequency mapping for Dynamic LPF"
264         default_value: 5
265         field: gyroDynamicLpfCurveExpo
266         min: 1
267         max: 10
268       - name: dynamic_gyro_notch_enabled
269         description: "Enable/disable dynamic gyro notch also known as Matrix Filter"
270         default_value: OFF
271         field: dynamicGyroNotchEnabled
272         condition: USE_DYNAMIC_FILTERS
273         type: bool
274       - name: dynamic_gyro_notch_range
275         description: "Range for dynamic gyro notches. `MEDIUM` for 5\", `HIGH` for 3\" and `MEDIUM`/`LOW` for 7\" and bigger propellers"
276         default_value: "MEDIUM"
277         field: dynamicGyroNotchRange
278         condition: USE_DYNAMIC_FILTERS
279         table: dynamicFilterRangeTable
280       - name: dynamic_gyro_notch_q
281         description: "Q factor for dynamic notches"
282         default_value: 120
283         field: dynamicGyroNotchQ
284         condition: USE_DYNAMIC_FILTERS
285         min: 1
286         max: 1000
287       - name: dynamic_gyro_notch_min_hz
288         description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`"
289         default_value: 150
290         field: dynamicGyroNotchMinHz
291         condition: USE_DYNAMIC_FILTERS
292         min: 30
293         max: 1000
294       - name: gyro_to_use
295         condition: USE_DUAL_GYRO
296         min: 0
297         max: 1
298         default_value: 0
300   - name: PG_ADC_CHANNEL_CONFIG
301     type: adcChannelConfig_t
302     headers: ["fc/config.h"]
303     condition: USE_ADC
304     members:
305       - name: vbat_adc_channel
306         description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled"
307         default_value: :target
308         field: adcFunctionChannel[ADC_BATTERY]
309         min: ADC_CHN_NONE
310         max: ADC_CHN_MAX
311       - name: rssi_adc_channel
312         description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled"
313         default_value: :target
314         field: adcFunctionChannel[ADC_RSSI]
315         min: ADC_CHN_NONE
316         max: ADC_CHN_MAX
317       - name: current_adc_channel
318         description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled"
319         default_value: :target
320         field: adcFunctionChannel[ADC_CURRENT]
321         min: ADC_CHN_NONE
322         max: ADC_CHN_MAX
323       - name: airspeed_adc_channel
324         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"
325         default_value: :target
326         field: adcFunctionChannel[ADC_AIRSPEED]
327         min: ADC_CHN_NONE
328         max: ADC_CHN_MAX
330   - name: PG_ACCELEROMETER_CONFIG
331     type: accelerometerConfig_t
332     headers: ["sensors/acceleration.h"]
333     members:
334       - name: acc_notch_hz
335         min: 0
336         max: 255
337         default_value: 0
338       - name: acc_notch_cutoff
339         min: 1
340         max: 255
341         default_value: 1
342       - name: align_acc
343         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."
344         default_value: "DEFAULT"
345         field: acc_align
346         type: uint8_t
347         table: alignment
348       - name: acc_hardware
349         description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
350         default_value: "AUTO"
351         table: acc_hardware
352       - name: acc_lpf_hz
353         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."
354         default_value: 15
355         min: 0
356         max: 200
357       - name: acc_lpf_type
358         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."
359         default_value: "BIQUAD"
360         field: acc_soft_lpf_type
361         table: filter_type
362       - name: acczero_x
363         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
364         default_value: 0
365         field: accZero.raw[X]
366         min: INT16_MIN
367         max: INT16_MAX
368       - name: acczero_y
369         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
370         default_value: 0
371         field: accZero.raw[Y]
372         min: INT16_MIN
373         max: INT16_MAX
374       - name: acczero_z
375         description: "Calculated value after '6 position avanced calibration'. See Wiki page."
376         default_value: 0
377         field: accZero.raw[Z]
378         min: INT16_MIN
379         max: INT16_MAX
380       - name: accgain_x
381         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
382         default_value: 4096
383         field: accGain.raw[X]
384         min: 1
385         max: 8192
386       - name: accgain_y
387         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
388         default_value: 4096
389         field: accGain.raw[Y]
390         min: 1
391         max: 8192
392       - name: accgain_z
393         description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
394         default_value: 4096
395         field: accGain.raw[Z]
396         min: 1
397         max: 8192
399   - name: PG_RANGEFINDER_CONFIG
400     type: rangefinderConfig_t
401     headers: ["sensors/rangefinder.h"]
402     condition: USE_RANGEFINDER
403     members:
404       - name: rangefinder_hardware
405         table: rangefinder_hardware
406         description: "Selection of rangefinder hardware."
407         default_value: "NONE"
408       - name: rangefinder_median_filter
409         description: "3-point median filtering for rangefinder readouts"
410         default_value: OFF
411         field: use_median_filtering
412         type: bool
414   - name: PG_OPFLOW_CONFIG
415     type: opticalFlowConfig_t
416     headers: ["sensors/opflow.h"]
417     condition: USE_OPFLOW
418     members:
419       - name: opflow_hardware
420         description: "Selection of OPFLOW hardware."
421         default_value: NONE
422         table: opflow_hardware
423       - name: opflow_scale
424         min: 0
425         max: 10000
426         default_value: 10.5
427       - name: align_opflow
428         description: "Optical flow module alignment (default CW0_DEG_FLIP)"
429         default_value: CW0FLIP
430         field: opflow_align
431         type: uint8_t
432         table: alignment
434   - name: PG_SECONDARY_IMU
435     type: secondaryImuConfig_t
436     headers: ["flight/secondary_imu.h"]
437     condition: USE_SECONDARY_IMU
438     members:
439       - name: imu2_hardware
440         description: "Selection of a Secondary IMU hardware type. NONE disables this functionality"
441         default_value: "NONE"
442         field: hardwareType
443         table: secondary_imu_hardware
444       - name: imu2_use_for_osd_heading
445         description: "If set to ON, Secondary IMU data will be used for Analog OSD heading"
446         default_value: OFF
447         field: useForOsdHeading
448         type: bool
449       - name: imu2_use_for_osd_ahi
450         description: "If set to ON, Secondary IMU data will be used for Analog OSD Artificial Horizon"
451         field: useForOsdAHI
452         default_value: OFF
453         type: bool
454       - name: imu2_use_for_stabilized
455         description: "If set to ON, Secondary IMU data will be used for Angle, Horizon and all other modes that control attitude (PosHold, WP, RTH)"
456         field: useForStabilized
457         default_value: OFF
458         type: bool
459       - name: imu2_align_roll
460         description: "Roll alignment for Secondary IMU. 1/10 of a degree"
461         field: rollDeciDegrees
462         default_value: 0
463         min: -1800
464         max: 3600
465       - name: imu2_align_pitch
466         description: "Pitch alignment for Secondary IMU. 1/10 of a degree"
467         field: pitchDeciDegrees
468         default_value: 0
469         min: -1800
470         max: 3600
471       - name: imu2_align_yaw
472         description: "Yaw alignment for Secondary IMU. 1/10 of a degree"
473         field: yawDeciDegrees
474         default_value: 0
475         min: -1800
476         max: 3600
477       - name: imu2_gain_acc_x
478         description: "Secondary IMU ACC calibration data"
479         field: calibrationOffsetAcc[X]
480         default_value: 0
481         min: INT16_MIN
482         max: INT16_MAX
483       - name: imu2_gain_acc_y
484         field: calibrationOffsetAcc[Y]
485         description: "Secondary IMU ACC calibration data"
486         default_value: 0
487         min: INT16_MIN
488         max: INT16_MAX
489       - name: imu2_gain_acc_z
490         field: calibrationOffsetAcc[Z]
491         description: "Secondary IMU ACC calibration data"
492         default_value: 0
493         min: INT16_MIN
494         max: INT16_MAX
495       - name: imu2_gain_mag_x
496         field: calibrationOffsetMag[X]
497         description: "Secondary IMU MAG calibration data"
498         default_value: 0
499         min: INT16_MIN
500         max: INT16_MAX
501       - name: imu2_gain_mag_y
502         field: calibrationOffsetMag[Y]
503         description: "Secondary IMU MAG calibration data"
504         default_value: 0
505         min: INT16_MIN
506         max: INT16_MAX
507       - name: imu2_gain_mag_z
508         field: calibrationOffsetMag[Z]
509         description: "Secondary IMU MAG calibration data"
510         default_value: 0
511         min: INT16_MIN
512         max: INT16_MAX
513       - name: imu2_radius_acc
514         field: calibrationRadiusAcc
515         description: "Secondary IMU MAG calibration data"
516         default_value: 0
517         min: INT16_MIN
518         max: INT16_MAX
519       - name: imu2_radius_mag
520         field: calibrationRadiusMag
521         description: "Secondary IMU MAG calibration data"
522         default_value: 0
523         min: INT16_MIN
524         max: INT16_MAX
526   - name: PG_COMPASS_CONFIG
527     type: compassConfig_t
528     headers: ["sensors/compass.h"]
529     condition: USE_MAG
530     members:
531       - name: align_mag
532         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."
533         default_value: "DEFAULT"
534         field: mag_align
535         type: uint8_t
536         table: alignment
537       - name: mag_hardware
538         description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
539         default_value: "AUTO"
540         table: mag_hardware
541       - name: mag_declination
542         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."
543         default_value: 0
544         min: -18000
545         max: 18000
546       - name: magzero_x
547         description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed."
548         default_value: :zero
549         field: magZero.raw[X]
550         min: INT16_MIN
551         max: INT16_MAX
552       - name: magzero_y
553         description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed."
554         default_value: :zero
555         field: magZero.raw[Y]
556         min: INT16_MIN
557         max: INT16_MAX
558       - name: magzero_z
559         description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed."
560         default_value: :zero
561         field: magZero.raw[Z]
562         min: INT16_MIN
563         max: INT16_MAX
564       - name: maggain_x
565         description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed"
566         default_value: 1024
567         field: magGain[X]
568         min: INT16_MIN
569         max: INT16_MAX
570       - name: maggain_y
571         description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed"
572         default_value: 1024
573         field: magGain[Y]
574         min: INT16_MIN
575         max: INT16_MAX
576       - name: maggain_z
577         description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed"
578         default_value: 1024
579         field: magGain[Z]
580         min: INT16_MIN
581         max: INT16_MAX
582       - name: mag_calibration_time
583         description: "Adjust how long time the Calibration of mag will last."
584         default_value: 30
585         field: magCalibrationTimeLimit
586         min: 20
587         max: 120
588       - name: mag_to_use
589         description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target"
590         condition: USE_DUAL_MAG
591         min: 0
592         max: 1
593         default_value: 0
594       - name: align_mag_roll
595         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."
596         default_value: 0
597         field: rollDeciDegrees
598         min: -1800
599         max: 3600
600       - name: align_mag_pitch
601         description: "Same as align_mag_roll, but for the pitch axis."
602         default_value: 0
603         field: pitchDeciDegrees
604         min: -1800
605         max: 3600
606       - name: align_mag_yaw
607         description: "Same as align_mag_roll, but for the yaw axis."
608         default_value: 0
609         field: yawDeciDegrees
610         min: -1800
611         max: 3600
613   - name: PG_BAROMETER_CONFIG
614     type: barometerConfig_t
615     headers: ["sensors/barometer.h"]
616     condition: USE_BARO
617     members:
618       - name: baro_hardware
619         description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
620         default_value: "AUTO"
621         table: baro_hardware
622       - name: baro_median_filter
623         description: "3-point median filtering for barometer readouts. No reason to change this setting"
624         default_value: ON
625         field: use_median_filtering
626         type: bool
627       - name: baro_cal_tolerance
628         description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]."
629         default_value: 150
630         field: baro_calibration_tolerance
631         min: 0
632         max: 1000
634   - name: PG_PITOTMETER_CONFIG
635     type: pitotmeterConfig_t
636     headers: ["sensors/pitotmeter.h"]
637     condition: USE_PITOT
638     members:
639       - name: pitot_hardware
640         description: "Selection of pitot hardware."
641         default_value: "NONE"
642         table: pitot_hardware
643       - name: pitot_lpf_milli_hz
644         min: 0
645         max: 10000
646         default_value: 350
647       - name: pitot_scale
648         min: 0
649         max: 100
650         default_value: 1.0
652   - name: PG_RX_CONFIG
653     type: rxConfig_t
654     headers: ["rx/rx.h", "rx/spektrum.h"]
655     members:
656       - name: receiver_type
657         description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`"
658         default_value: :target
659         field: receiverType
660         table: receiver_type
661       - name: min_check
662         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."
663         default_value: 1100
664         field: mincheck
665         min: PWM_RANGE_MIN
666         max: PWM_RANGE_MAX
667       - name: max_check
668         description: "These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value."
669         default_value: 1900
670         field: maxcheck
671         min: PWM_RANGE_MIN
672         max: PWM_RANGE_MAX
673       - name: rssi_source
674         description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`"
675         default_value: "AUTO"
676         field: rssi_source
677         table: rssi_source
678       - name: rssi_channel
679         description: "RX channel containing the RSSI signal"
680         default_value: 0
681         min: 0
682         max: MAX_SUPPORTED_RC_CHANNEL_COUNT
683       - name: rssi_min
684         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)."
685         default_value: 0
686         field: rssiMin
687         min: RSSI_VISIBLE_VALUE_MIN
688         max: RSSI_VISIBLE_VALUE_MAX
689       - name: rssi_max
690         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."
691         default_value: 100
692         field: rssiMax
693         min: RSSI_VISIBLE_VALUE_MIN
694         max: RSSI_VISIBLE_VALUE_MAX
695       - name: sbus_sync_interval
696         field: sbusSyncInterval
697         min: 500
698         max: 10000
699         default_value: 3000
700       - name: rc_filter_frequency
701         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"
702         default_value: 50
703         field: rcFilterFrequency
704         min: 0
705         max: 100
706       - name: serialrx_provider
707         description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section."
708         default_value: :target
709         condition: USE_SERIAL_RX
710         table: serial_rx
711       - name: serialrx_inverted
712         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)."
713         default_value: OFF
714         condition: USE_SERIAL_RX
715         type: bool
716       - name: rx_spi_protocol
717         condition: USE_RX_SPI
718         table: rx_spi_protocol
719         default_value: :target
720       - name: rx_spi_id
721         condition: USE_RX_SPI
722         min: 0
723         max: 0
724         default_value: :zero
725       - name: rx_spi_rf_channel_count
726         condition: USE_RX_SPI
727         min: 0
728         max: 8
729         default_value: :zero
730       - name: spektrum_sat_bind
731         description: "0 = disabled. Used to bind the spektrum satellite to RX"
732         condition: USE_SPEKTRUM_BIND
733         min: SPEKTRUM_SAT_BIND_DISABLED
734         max: SPEKTRUM_SAT_BIND_MAX
735         default_value: :SPEKTRUM_SAT_BIND_DISABLED
736       - name: srxl2_unit_id
737         condition: USE_SERIALRX_SRXL2
738         min: 0
739         max: 15
740         default_value: 1
741       - name: srxl2_baud_fast
742         condition: USE_SERIALRX_SRXL2
743         type: bool
744         default_value: ON
745       - name: rx_min_usec
746         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."
747         default_value: 885
748         min: PWM_PULSE_MIN
749         max: PWM_PULSE_MAX
750       - name: rx_max_usec
751         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."
752         default_value: 2115
753         min: PWM_PULSE_MIN
754         max: PWM_PULSE_MAX
755       - name: serialrx_halfduplex
756         description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire."
757         default_value: "AUTO"
758         field: halfDuplex
759         table: tristate
760       - name: msp_override_channels
761         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."
762         default_value: 0
763         field: mspOverrideChannels
764         condition: USE_MSP_RC_OVERRIDE
765         min: 0
766         max: 65535
768   - name: PG_BLACKBOX_CONFIG
769     type: blackboxConfig_t
770     headers: ["blackbox/blackbox.h"]
771     condition: USE_BLACKBOX
772     members:
773       - name: blackbox_rate_num
774         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"
775         default_value: 1
776         field: rate_num
777         min: 1
778         max: 65535
779       - name: blackbox_rate_denom
780         description: "Blackbox logging rate denominator. See blackbox_rate_num."
781         default_value: 1
782         field: rate_denom
783         min: 1
784         max: 65535
785       - name: blackbox_device
786         description: "Selection of where to write blackbox data"
787         default_value: :target
788         field: device
789         table: blackbox_device
790       - name: sdcard_detect_inverted
791         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."
792         default_value: :target
793         field: invertedCardDetection
794         condition: USE_SDCARD
795         type: bool
797   - name: PG_MOTOR_CONFIG
798     type: motorConfig_t
799     headers: ["flight/mixer.h"]
800     members:
801       - name: max_throttle
802         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."
803         default_value: 1850
804         field: maxthrottle
805         min: PWM_RANGE_MIN
806         max: PWM_RANGE_MAX
807       - name: min_command
808         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."
809         default_value: 1000
810         field: mincommand
811         min: 0
812         max: PWM_RANGE_MAX
813       - name: motor_pwm_rate
814         description: "Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000."
815         default_value: 400
816         field: motorPwmRate
817         min: 50
818         max: 32000
819       - name: motor_accel_time
820         description: "Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000]"
821         default_value: 0
822         field: motorAccelTimeMs
823         min: 0
824         max: 1000
825       - name: motor_decel_time
826         description: "Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000]"
827         default_value: 0
828         field: motorDecelTimeMs
829         min: 0
830         max: 1000
831       - name: motor_pwm_protocol
832         description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
833         default_value: "ONESHOT125"
834         field: motorPwmProtocol
835         table: motor_pwm_protocol
836       - name: throttle_scale
837         description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
838         default_value: 1.0
839         field: throttleScale
840         min: 0
841         max: 1
842       - name: throttle_idle
843         description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
844         default_value: 15
845         field: throttleIdle
846         min: 0
847         max: 30
848       - name: motor_poles
849         field: motorPoleCount
850         description: "The number of motor poles. Required to compute motor RPM"
851         min: 4
852         max: 255
853         default_value: 14
854       - name: flip_over_after_crash_power_factor
855         field: flipOverAfterPowerFactor
856         default_value: 65
857         description: "flip over after crash power factor"
858         condition: "USE_DSHOT"
859         min: 0
860         max: 100
862   - name: PG_FAILSAFE_CONFIG
863     type: failsafeConfig_t
864     headers: ["flight/failsafe.h"]
865     members:
866       - name: failsafe_delay
867         description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)."
868         default_value: 5
869         min: 0
870         max: 200
871       - name: failsafe_recovery_delay
872         description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)."
873         default_value: 5
874         min: 0
875         max: 200
876       - name: failsafe_off_delay
877         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)."
878         default_value: 200
879         min: 0
880         max: 200
881       - name: failsafe_throttle
882         description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
883         default_value: 1000
884         min: PWM_RANGE_MIN
885         max: PWM_RANGE_MAX
886       - name: failsafe_throttle_low_delay
887         description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout"
888         default_value: 0
889         min: 0
890         max: 300
891       - name: failsafe_procedure
892         description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
893         default_value: "SET-THR"
894         table: failsafe_procedure
895       - name: failsafe_stick_threshold
896         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."
897         default_value: 50
898         field: failsafe_stick_motion_threshold
899         min: 0
900         max: 500
901       - name: failsafe_fw_roll_angle
902         description: "Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll"
903         default_value: -200
904         min: -800
905         max: 800
906       - name: failsafe_fw_pitch_angle
907         description: "Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb"
908         default_value: 100
909         min: -800
910         max: 800
911       - name: failsafe_fw_yaw_rate
912         description: "Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn"
913         default_value: -45
914         min: -1000
915         max: 1000
916       - name: failsafe_min_distance
917         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."
918         default_value: 0
919         min: 0
920         max: 65000
921       - name: failsafe_min_distance_procedure
922         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)."
923         default_value: "DROP"
924         table: failsafe_procedure
925       - name: failsafe_mission
926         description: "If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode"
927         default_value: ON
928         type: bool
930   - name: PG_LIGHTS_CONFIG
931     type: lightsConfig_t
932     headers: ["io/lights.h"]
933     condition: USE_LIGHTS
934     members:
935       - name: failsafe_lights
936         description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
937         default_value: ON
938         field: failsafe.enabled
939         type: bool
940       - name: failsafe_lights_flash_period
941         description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
942         default_value: 1000
943         field: failsafe.flash_period
944         min: 40
945         max: 65535
946       - name: failsafe_lights_flash_on_time
947         description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
948         default_value: 100
949         field: failsafe.flash_on_time
950         min: 20
951         max: 65535
953   - name: PG_BOARD_ALIGNMENT
954     type: boardAlignment_t
955     headers: ["sensors/boardalignment.h"]
956     members:
957       - name: align_board_roll
958         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
959         default_value: :zero
960         field: rollDeciDegrees
961         min: -1800
962         max: 3600
963       - name: align_board_pitch
964         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
965         default_value: :zero
966         field: pitchDeciDegrees
967         min: -1800
968         max: 3600
969       - name: align_board_yaw
970         description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
971         default_value: :zero
972         field: yawDeciDegrees
973         min: -1800
974         max: 3600
976   - name: PG_BATTERY_METERS_CONFIG
977     type: batteryMetersConfig_t
978     headers: ["sensors/battery.h"]
979     members:
980       - name: vbat_meter_type
981         description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
982         condition: USE_ADC
983         default_value: ADC
984         field: voltage.type
985         table: voltage_sensor
986         type: uint8_t
987       - name: vbat_scale
988         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."
989         default_value: :target
990         field: voltage.scale
991         condition: USE_ADC
992         min: VBAT_SCALE_MIN
993         max: VBAT_SCALE_MAX
994       - name: current_meter_scale
995         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."
996         default_value: :target
997         field: current.scale
998         min: -10000
999         max: 10000
1000       - name: current_meter_offset
1001         description: "This sets the output offset voltage of the current sensor in millivolts."
1002         default_value: :target
1003         field: current.offset
1004         min: -32768
1005         max: 32767
1006       - name: current_meter_type
1007         description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position."
1008         default_value: "ADC"
1009         field: current.type
1010         table: current_sensor
1011         type: uint8_t
1012       - name: bat_voltage_src
1013         description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`"
1014         default_value: "RAW"
1015         field: voltageSource
1016         table: bat_voltage_source
1017         type: uint8_t
1018       - name: cruise_power
1019         description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
1020         default_value: 0
1021         field: cruise_power
1022         min: 0
1023         max: 4294967295
1024       - name: idle_power
1025         description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
1026         default_value: 0
1027         field: idle_power
1028         min: 0
1029         max: 65535
1030       - name: rth_energy_margin
1031         description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
1032         default_value: 5
1033         min: 0
1034         max: 100
1035       - name: thr_comp_weight
1036         description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
1037         default_value: 1
1038         field: throttle_compensation_weight
1039         min: 0
1040         max: 2
1042   - name: PG_BATTERY_PROFILES
1043     type: batteryProfile_t
1044     headers: ["sensors/battery.h"]
1045     value_type: BATTERY_CONFIG_VALUE
1046     members:
1047       - name: bat_cells
1048         description: "Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected."
1049         default_value: 0
1050         field: cells
1051         condition: USE_ADC
1052         min: 0
1053         max: 12
1054       - name: vbat_cell_detect_voltage
1055         description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units."
1056         default_value: 425
1057         field: voltage.cellDetect
1058         condition: USE_ADC
1059         min: 100
1060         max: 500
1061       - name: vbat_max_cell_voltage
1062         description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
1063         default_value: 420
1064         field: voltage.cellMax
1065         condition: USE_ADC
1066         min: 100
1067         max: 500
1068       - name: vbat_min_cell_voltage
1069         description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
1070         default_value: 330
1071         field: voltage.cellMin
1072         condition: USE_ADC
1073         min: 100
1074         max: 500
1075       - name: vbat_warning_cell_voltage
1076         description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
1077         default_value: 350
1078         field: voltage.cellWarning
1079         condition: USE_ADC
1080         min: 100
1081         max: 500
1082       - name: battery_capacity
1083         description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
1084         default_value: 0
1085         field: capacity.value
1086         min: 0
1087         max: 4294967295
1088       - name: battery_capacity_warning
1089         description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
1090         default_value: 0
1091         field: capacity.warning
1092         min: 0
1093         max: 4294967295
1094       - name: battery_capacity_critical
1095         description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
1096         default_value: 0
1097         field: capacity.critical
1098         min: 0
1099         max: 4294967295
1100       - name: battery_capacity_unit
1101         description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)."
1102         default_value: "MAH"
1103         field: capacity.unit
1104         table: bat_capacity_unit
1105         type: uint8_t
1107   - name: PG_MIXER_CONFIG
1108     type: mixerConfig_t
1109     members:
1110       - name: motor_direction_inverted
1111         description: "Use if you need to inverse yaw motor direction."
1112         default_value: OFF
1113         field: motorDirectionInverted
1114         type: bool
1115       - name: platform_type
1116         description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
1117         default_value: "MULTIROTOR"
1118         field: platformType
1119         type: uint8_t
1120         table: platform_type
1121       - name: has_flaps
1122         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"
1123         default_value: OFF
1124         field: hasFlaps
1125         type: bool
1126       - name: model_preview_type
1127         description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
1128         default_value: -1
1129         field: appliedMixerPreset
1130         min: -1
1131         max: INT16_MAX
1132       - name: fw_min_throttle_down_pitch
1133         description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
1134         default_value: 0
1135         field: fwMinThrottleDownPitchAngle
1136         min: 0
1137         max: 450
1139   - name: PG_REVERSIBLE_MOTORS_CONFIG
1140     type: reversibleMotorsConfig_t
1141     members:
1142       - name: 3d_deadband_low
1143         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)"
1144         default_value: 1406
1145         field: deadband_low
1146         min: PWM_RANGE_MIN
1147         max: PWM_RANGE_MAX
1148       - name: 3d_deadband_high
1149         description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
1150         default_value: 1514
1151         field: deadband_high
1152         min: PWM_RANGE_MIN
1153         max: PWM_RANGE_MAX
1154       - name: 3d_neutral
1155         description: "Neutral (stop) throttle value for 3D mode"
1156         default_value: 1460
1157         field: neutral
1158         min: PWM_RANGE_MIN
1159         max: PWM_RANGE_MAX
1161   - name: PG_SERVO_CONFIG
1162     type: servoConfig_t
1163     headers: ["flight/servos.h"]
1164     members:
1165       - name: servo_protocol
1166         description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port)"
1167         default_value: "PWM"
1168         field: servo_protocol
1169         table: servo_protocol
1170       - name: servo_center_pulse
1171         description: "Servo midpoint"
1172         default_value: 1500
1173         field: servoCenterPulse
1174         min: PWM_RANGE_MIN
1175         max: PWM_RANGE_MAX
1176       - name: servo_pwm_rate
1177         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."
1178         default_value: 50
1179         field: servoPwmRate
1180         min: 50
1181         max: 498
1182       - name: servo_lpf_hz
1183         description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
1184         default_value: 20
1185         field: servo_lowpass_freq
1186         min: 0
1187         max: 400
1188       - name: flaperon_throw_offset
1189         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."
1190         default_value: 200
1191         min: FLAPERON_THROW_MIN
1192         max: FLAPERON_THROW_MAX
1193       - name: tri_unarmed_servo
1194         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."
1195         default_value: ON
1196         type: bool
1198   - name: PG_CONTROL_RATE_PROFILES
1199     type: controlRateConfig_t
1200     headers: ["fc/controlrate_profile.h"]
1201     value_type: CONTROL_RATE_VALUE
1202     members:
1203       - name: thr_mid
1204         description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
1205         default_value: 50
1206         field: throttle.rcMid8
1207         min: 0
1208         max: 100
1209       - name: thr_expo
1210         description: "Throttle exposition value"
1211         default_value: 0
1212         field: throttle.rcExpo8
1213         min: 0
1214         max: 100
1215       - name: tpa_rate
1216         description: "Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate."
1217         default_value: 0
1218         field: throttle.dynPID
1219         min: 0
1220         max: 100
1221       - name: tpa_breakpoint
1222         description: "See tpa_rate."
1223         default_value: 1500
1224         field: throttle.pa_breakpoint
1225         min: PWM_RANGE_MIN
1226         max: PWM_RANGE_MAX
1227       - name: fw_tpa_time_constant
1228         description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups"
1229         default_value: 0
1230         field: throttle.fixedWingTauMs
1231         min: 0
1232         max: 5000
1233       - name: rc_expo
1234         description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
1235         default_value: 70
1236         field: stabilized.rcExpo8
1237         min: 0
1238         max: 100
1239       - name: rc_yaw_expo
1240         description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
1241         default_value: 20
1242         field: stabilized.rcYawExpo8
1243         min: 0
1244         max: 100
1245       # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
1246       # Rate 180 (1800dps) is max. value gyro can measure reliably
1247       - name: roll_rate
1248         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."
1249         default_value: 20
1250         field: stabilized.rates[FD_ROLL]
1251         min: ROLL_PITCH_RATE_MIN
1252         max: ROLL_PITCH_RATE_MAX
1253       - name: pitch_rate
1254         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."
1255         default_value: 20
1256         field: stabilized.rates[FD_PITCH]
1257         min: ROLL_PITCH_RATE_MIN
1258         max: ROLL_PITCH_RATE_MAX
1259       - name: yaw_rate
1260         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."
1261         default_value: 20
1262         field: stabilized.rates[FD_YAW]
1263         min: 2
1264         max: 180
1265       - name: manual_rc_expo
1266         description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
1267         default_value: 70
1268         field: manual.rcExpo8
1269         min: 0
1270         max: 100
1271       - name: manual_rc_yaw_expo
1272         description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
1273         default_value: 20
1274         field: manual.rcYawExpo8
1275         min: 0
1276         max: 100
1277       - name: manual_roll_rate
1278         description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
1279         default_value: 100
1280         field: manual.rates[FD_ROLL]
1281         min: MANUAL_RATE_MIN
1282         max: MANUAL_RATE_MAX
1283       - name: manual_pitch_rate
1284         description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
1285         default_value: 100
1286         field: manual.rates[FD_PITCH]
1287         min: MANUAL_RATE_MIN
1288         max: MANUAL_RATE_MAX
1289       - name: manual_yaw_rate
1290         description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
1291         default_value: 100
1292         field: manual.rates[FD_YAW]
1293         min: MANUAL_RATE_MIN
1294         max: MANUAL_RATE_MAX
1295       - name: fpv_mix_degrees
1296         field: misc.fpvCamAngleDegrees
1297         min: 0
1298         max: 50
1299         default_value: 0
1301   - name: PG_SERIAL_CONFIG
1302     type: serialConfig_t
1303     headers: ["io/serial.h"]
1304     members:
1305       - name: reboot_character
1306         description: "Special character used to trigger reboot"
1307         default_value: 82
1308         min: 48
1309         max: 126
1311   - name: PG_IMU_CONFIG
1312     type: imuConfig_t
1313     headers: ["flight/imu.h"]
1314     members:
1315       - name: imu_dcm_kp
1316         description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
1317         default_value: 2500
1318         field: dcm_kp_acc
1319         max: UINT16_MAX
1320       - name: imu_dcm_ki
1321         description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
1322         default_value: 50
1323         field: dcm_ki_acc
1324         max: UINT16_MAX
1325       - name: imu_dcm_kp_mag
1326         description: "Inertial Measurement Unit KP Gain for compass measurements"
1327         default_value: 10000
1328         field: dcm_kp_mag
1329         max: UINT16_MAX
1330       - name: imu_dcm_ki_mag
1331         description: "Inertial Measurement Unit KI Gain for compass measurements"
1332         default_value: 0
1333         field: dcm_ki_mag
1334         max: UINT16_MAX
1335       - name: small_angle
1336         description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
1337         default_value: 25
1338         min: 0
1339         max: 180
1340       - name: imu_acc_ignore_rate
1341         description: "Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes"
1342         default_value: 0
1343         field: acc_ignore_rate
1344         min: 0
1345         max: 20
1346       - name: imu_acc_ignore_slope
1347         description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
1348         default_value: 0
1349         field: acc_ignore_slope
1350         min: 0
1351         max: 5
1353   - name: PG_ARMING_CONFIG
1354     type: armingConfig_t
1355     members:
1356       - name: fixed_wing_auto_arm
1357         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."
1358         default_value: OFF
1359         type: bool
1360       - name: disarm_kill_switch
1361         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."
1362         default_value: ON
1363         type: bool
1364       - name: switch_disarm_delay
1365         description: "Delay before disarming when requested by switch (ms) [0-1000]"
1366         default_value: 250
1367         field: switchDisarmDelayMs
1368         min: 0
1369         max: 1000
1370       - name: prearm_timeout
1371         description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
1372         default_value: 10000
1373         field: prearmTimeoutMs
1374         min: 0
1375         max: 10000
1377   - name: PG_GENERAL_SETTINGS
1378     headers: ["config/general_settings.h"]
1379     type: generalSettings_t
1380     members:
1381       - name: applied_defaults
1382         description: "Internal (configurator) hint. Should not be changed manually"
1383         default_value: 0
1384         field: appliedDefaults
1385         type: uint8_t
1386         min: 0
1387         max: 3
1389   - name: PG_RPM_FILTER_CONFIG
1390     headers: ["flight/rpm_filter.h"]
1391     condition: USE_RPM_FILTER
1392     type: rpmFilterConfig_t
1393     members:
1394       - name: rpm_gyro_filter_enabled
1395         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"
1396         default_value: OFF
1397         field: gyro_filter_enabled
1398         type: bool
1399       - name: rpm_gyro_harmonics
1400         description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
1401         default_value: 1
1402         field: gyro_harmonics
1403         type: uint8_t
1404         min: 1
1405         max: 3
1406       - name: rpm_gyro_min_hz
1407         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`"
1408         default_value: 100
1409         field: gyro_min_hz
1410         type: uint8_t
1411         min: 30
1412         max: 200
1413       - name: rpm_gyro_q
1414         description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
1415         default_value: 500
1416         field: gyro_q
1417         type: uint16_t
1418         min: 1
1419         max: 3000
1420   - name: PG_GPS_CONFIG
1421     type: gpsConfig_t
1422     condition: USE_GPS
1423     members:
1424       - name: gps_provider
1425         description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)."
1426         default_value: "UBLOX"
1427         field: provider
1428         table: gps_provider
1429         type: uint8_t
1430       - name: gps_sbas_mode
1431         description: "Which SBAS mode to be used"
1432         default_value: "NONE"
1433         field: sbasMode
1434         table: gps_sbas_mode
1435         type: uint8_t
1436       - name: gps_dyn_model
1437         description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying."
1438         default_value: "AIR_1G"
1439         field: dynModel
1440         table: gps_dyn_model
1441         type: uint8_t
1442       - name: gps_auto_config
1443         description: "Enable automatic configuration of UBlox GPS receivers."
1444         default_value: ON
1445         field: autoConfig
1446         type: bool
1447       - name: gps_auto_baud
1448         description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports"
1449         default_value: ON
1450         field: autoBaud
1451         type: bool
1452       - name: gps_ublox_use_galileo
1453         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]."
1454         default_value: OFF
1455         field: ubloxUseGalileo
1456         type: bool
1457       - name: gps_min_sats
1458         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."
1459         default_value: 6
1460         field: gpsMinSats
1461         min: 5
1462         max: 10
1464   - name: PG_RC_CONTROLS_CONFIG
1465     type: rcControlsConfig_t
1466     headers: ["fc/rc_controls.h"]
1467     members:
1468       - name: deadband
1469         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."
1470         default_value: 5
1471         min: 0
1472         max: 32
1473       - name: yaw_deadband
1474         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."
1475         default_value: 5
1476         min: 0
1477         max: 100
1478       - name: pos_hold_deadband
1479         description: "Stick deadband in [r/c points], applied after r/c deadband and expo"
1480         default_value: 10
1481         min: 2
1482         max: 250
1483       - name: alt_hold_deadband
1484         description: "Defines the deadband of throttle during alt_hold [r/c points]"
1485         default_value: 50
1486         min: 10
1487         max: 250
1488       - name: 3d_deadband_throttle
1489         description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
1490         default_value: 50
1491         field: mid_throttle_deadband
1492         min: 0
1493         max: 200
1494       - name: airmode_type
1495         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."
1496         default_value: "STICK_CENTER"
1497         field: airmodeHandlingType
1498         table: airmodeHandlingType
1499       - name: airmode_throttle_threshold
1500         description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
1501         default_value: 1300
1502         field: airmodeThrottleThreshold
1503         min: 1000
1504         max: 2000
1506   - name: PG_PID_PROFILE
1507     type: pidProfile_t
1508     headers: ["flight/pid.h"]
1509     value_type: PROFILE_VALUE
1510     members:
1511       - name: mc_p_pitch
1512         description: "Multicopter rate stabilisation P-gain for PITCH"
1513         default_value: 40
1514         field: bank_mc.pid[PID_PITCH].P
1515         min: RPYL_PID_MIN
1516         max: RPYL_PID_MAX
1517       - name: mc_i_pitch
1518         description: "Multicopter rate stabilisation I-gain for PITCH"
1519         default_value: 30
1520         field: bank_mc.pid[PID_PITCH].I
1521         min: RPYL_PID_MIN
1522         max: RPYL_PID_MAX
1523       - name: mc_d_pitch
1524         description: "Multicopter rate stabilisation D-gain for PITCH"
1525         default_value: 23
1526         field: bank_mc.pid[PID_PITCH].D
1527         min: RPYL_PID_MIN
1528         max: RPYL_PID_MAX
1529       - name: mc_cd_pitch
1530         description: "Multicopter Control Derivative gain for PITCH"
1531         default_value: 60
1532         field: bank_mc.pid[PID_PITCH].FF
1533         min: RPYL_PID_MIN
1534         max: RPYL_PID_MAX
1535       - name: mc_p_roll
1536         description: "Multicopter rate stabilisation P-gain for ROLL"
1537         default_value: 40
1538         field: bank_mc.pid[PID_ROLL].P
1539         min: RPYL_PID_MIN
1540         max: RPYL_PID_MAX
1541       - name: mc_i_roll
1542         description: "Multicopter rate stabilisation I-gain for ROLL"
1543         default_value: 30
1544         field: bank_mc.pid[PID_ROLL].I
1545         min: RPYL_PID_MIN
1546         max: RPYL_PID_MAX
1547       - name: mc_d_roll
1548         description: "Multicopter rate stabilisation D-gain for ROLL"
1549         default_value: 23
1550         field: bank_mc.pid[PID_ROLL].D
1551         min: RPYL_PID_MIN
1552         max: RPYL_PID_MAX
1553       - name: mc_cd_roll
1554         description: "Multicopter Control Derivative gain for ROLL"
1555         default_value: 60
1556         field: bank_mc.pid[PID_ROLL].FF
1557         min: RPYL_PID_MIN
1558         max: RPYL_PID_MAX
1559       - name: mc_p_yaw
1560         description: "Multicopter rate stabilisation P-gain for YAW"
1561         default_value: 85
1562         field: bank_mc.pid[PID_YAW].P
1563         min: RPYL_PID_MIN
1564         max: RPYL_PID_MAX
1565       - name: mc_i_yaw
1566         description: "Multicopter rate stabilisation I-gain for YAW"
1567         default_value: 45
1568         field: bank_mc.pid[PID_YAW].I
1569         min: RPYL_PID_MIN
1570         max: RPYL_PID_MAX
1571       - name: mc_d_yaw
1572         description: "Multicopter rate stabilisation D-gain for YAW"
1573         default_value: 0
1574         field: bank_mc.pid[PID_YAW].D
1575         min: RPYL_PID_MIN
1576         max: RPYL_PID_MAX
1577       - name: mc_cd_yaw
1578         description: "Multicopter Control Derivative gain for YAW"
1579         default_value: 60
1580         field: bank_mc.pid[PID_YAW].FF
1581         min: RPYL_PID_MIN
1582         max: RPYL_PID_MAX
1583       - name: mc_p_level
1584         description: "Multicopter attitude stabilisation P-gain"
1585         default_value: 20
1586         field: bank_mc.pid[PID_LEVEL].P
1587         min: RPYL_PID_MIN
1588         max: RPYL_PID_MAX
1589       - name: mc_i_level
1590         description: "Multicopter attitude stabilisation low-pass filter cutoff"
1591         default_value: 15
1592         field: bank_mc.pid[PID_LEVEL].I
1593         min: RPYL_PID_MIN
1594         max: RPYL_PID_MAX
1595       - name: mc_d_level
1596         description: "Multicopter attitude stabilisation HORIZON transition point"
1597         default_value: 75
1598         field: bank_mc.pid[PID_LEVEL].D
1599         min: RPYL_PID_MIN
1600         max: RPYL_PID_MAX
1601       - name: fw_p_pitch
1602         description: "Fixed-wing rate stabilisation P-gain for PITCH"
1603         default_value: 5
1604         field: bank_fw.pid[PID_PITCH].P
1605         min: RPYL_PID_MIN
1606         max: RPYL_PID_MAX
1607       - name: fw_i_pitch
1608         description: "Fixed-wing rate stabilisation I-gain for PITCH"
1609         default_value: 7
1610         field: bank_fw.pid[PID_PITCH].I
1611         min: RPYL_PID_MIN
1612         max: RPYL_PID_MAX
1613       - name: fw_d_pitch
1614         description: "Fixed wing rate stabilisation D-gain for PITCH"
1615         default_value: 0
1616         field: bank_fw.pid[PID_PITCH].D
1617         min: RPYL_PID_MIN
1618         max: RPYL_PID_MAX
1619       - name: fw_ff_pitch
1620         description: "Fixed-wing rate stabilisation FF-gain for PITCH"
1621         default_value: 50
1622         field: bank_fw.pid[PID_PITCH].FF
1623         min: RPYL_PID_MIN
1624         max: RPYL_PID_MAX
1625       - name: fw_p_roll
1626         description: "Fixed-wing rate stabilisation P-gain for ROLL"
1627         default_value: 5
1628         field: bank_fw.pid[PID_ROLL].P
1629         min: RPYL_PID_MIN
1630         max: RPYL_PID_MAX
1631       - name: fw_i_roll
1632         description: "Fixed-wing rate stabilisation I-gain for ROLL"
1633         default_value: 7
1634         field: bank_fw.pid[PID_ROLL].I
1635         min: RPYL_PID_MIN
1636         max: RPYL_PID_MAX
1637       - name: fw_d_roll
1638         description: "Fixed wing rate stabilisation D-gain for ROLL"
1639         default_value: 0
1640         field: bank_fw.pid[PID_ROLL].D
1641         min: RPYL_PID_MIN
1642         max: RPYL_PID_MAX
1643       - name: fw_ff_roll
1644         description: "Fixed-wing rate stabilisation FF-gain for ROLL"
1645         default_value: 50
1646         field: bank_fw.pid[PID_ROLL].FF
1647         min: RPYL_PID_MIN
1648         max: RPYL_PID_MAX
1649       - name: fw_p_yaw
1650         description: "Fixed-wing rate stabilisation P-gain for YAW"
1651         default_value: 6
1652         field: bank_fw.pid[PID_YAW].P
1653         min: RPYL_PID_MIN
1654         max: RPYL_PID_MAX
1655       - name: fw_i_yaw
1656         description: "Fixed-wing rate stabilisation I-gain for YAW"
1657         default_value: 10
1658         field: bank_fw.pid[PID_YAW].I
1659         min: RPYL_PID_MIN
1660         max: RPYL_PID_MAX
1661       - name: fw_d_yaw
1662         description: "Fixed wing rate stabilisation D-gain for YAW"
1663         default_value: 0
1664         field: bank_fw.pid[PID_YAW].D
1665         min: RPYL_PID_MIN
1666         max: RPYL_PID_MAX
1667       - name: fw_ff_yaw
1668         description: "Fixed-wing rate stabilisation FF-gain for YAW"
1669         default_value: 60
1670         field: bank_fw.pid[PID_YAW].FF
1671         min: RPYL_PID_MIN
1672         max: RPYL_PID_MAX
1673       - name: fw_p_level
1674         description: "Fixed-wing attitude stabilisation P-gain"
1675         default_value: 20
1676         field: bank_fw.pid[PID_LEVEL].P
1677         min: RPYL_PID_MIN
1678         max: RPYL_PID_MAX
1679       - name: fw_i_level
1680         description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
1681         default_value: 5
1682         field: bank_fw.pid[PID_LEVEL].I
1683         min: RPYL_PID_MIN
1684         max: RPYL_PID_MAX
1685       - name: fw_d_level
1686         description: "Fixed-wing attitude stabilisation HORIZON transition point"
1687         default_value: 75
1688         field: bank_fw.pid[PID_LEVEL].D
1689         min: RPYL_PID_MIN
1690         max: RPYL_PID_MAX
1691       - name: max_angle_inclination_rll
1692         description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
1693         default_value: 300
1694         field: max_angle_inclination[FD_ROLL]
1695         min: 100
1696         max: 900
1697       - name: max_angle_inclination_pit
1698         description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
1699         default_value: 300
1700         field: max_angle_inclination[FD_PITCH]
1701         min: 100
1702         max: 900
1703       - name: dterm_lpf_hz
1704         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"
1705         default_value: 40
1706         min: 0
1707         max: 500
1708       - name: dterm_lpf_type
1709         description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
1710         default_value: "BIQUAD"
1711         field: dterm_lpf_type
1712         table: filter_type
1713       - name: dterm_lpf2_hz
1714         description: "Cutoff frequency for stage 2 D-term low pass filter"
1715         default_value: 0
1716         min: 0
1717         max: 500
1718       - name: dterm_lpf2_type
1719         description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
1720         default_value: "BIQUAD"
1721         field: dterm_lpf2_type
1722         table: filter_type
1723       - name: yaw_lpf_hz
1724         description: "Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
1725         default_value: 0
1726         min: 0
1727         max: 200
1728       - name: fw_iterm_throw_limit
1729         description: "Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely."
1730         default_value: 165
1731         field: fixedWingItermThrowLimit
1732         min: FW_ITERM_THROW_LIMIT_MIN
1733         max: FW_ITERM_THROW_LIMIT_MAX
1734       - name: fw_loiter_direction
1735         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."
1736         default_value: "RIGHT"
1737         field: loiter_direction
1738         condition: USE_NAV
1739         table: direction
1740       - name: fw_reference_airspeed
1741         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."
1742         default_value: 1500
1743         field: fixedWingReferenceAirspeed
1744         min: 300
1745         max: 6000
1746       - name: fw_turn_assist_yaw_gain
1747         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"
1748         default_value: 1
1749         field: fixedWingCoordinatedYawGain
1750         min: 0
1751         max: 2
1752       - name: fw_turn_assist_pitch_gain
1753         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"
1754         default_value: 1
1755         field: fixedWingCoordinatedPitchGain
1756         min: 0
1757         max: 2
1758       - name: fw_iterm_limit_stick_position
1759         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"
1760         default_value: 0.5
1761         field: fixedWingItermLimitOnStickPosition
1762         min: 0
1763         max: 1
1764       - name: fw_yaw_iterm_freeze_bank_angle
1765         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."
1766         default_value: 0
1767         field: fixedWingYawItermBankFreeze
1768         min: 0
1769         max: 90
1770       - name: pidsum_limit
1771         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"
1772         default_value: 500
1773         field: pidSumLimit
1774         min: PID_SUM_LIMIT_MIN
1775         max: PID_SUM_LIMIT_MAX
1776       - name: pidsum_limit_yaw
1777         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"
1778         default_value: 350
1779         field: pidSumLimitYaw
1780         min: PID_SUM_LIMIT_MIN
1781         max: PID_SUM_LIMIT_MAX
1782       - name: iterm_windup
1783         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)"
1784         default_value: 50
1785         field: itermWindupPointPercent
1786         min: 0
1787         max: 90
1788       - name: rate_accel_limit_roll_pitch
1789         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."
1790         default_value: 0
1791         field: axisAccelerationLimitRollPitch
1792         max: 500000
1793       - name: rate_accel_limit_yaw
1794         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."
1795         default_value: 10000
1796         field: axisAccelerationLimitYaw
1797         max: 500000
1798       - name: heading_hold_rate_limit
1799         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."
1800         min: HEADING_HOLD_RATE_LIMIT_MIN
1801         max: HEADING_HOLD_RATE_LIMIT_MAX
1802         default_value: 90
1804       - name: nav_mc_pos_z_p
1805         description: "P gain of altitude PID controller (Multirotor)"
1806         field: bank_mc.pid[PID_POS_Z].P
1807         condition: USE_NAV
1808         min: 0
1809         max: 255
1810         default_value: 50
1811       - name: nav_mc_vel_z_p
1812         description: "P gain of velocity PID controller"
1813         field: bank_mc.pid[PID_VEL_Z].P
1814         condition: USE_NAV
1815         min: 0
1816         max: 255
1817         default_value: 100
1818       - name: nav_mc_vel_z_i
1819         description: "I gain of velocity PID controller"
1820         field: bank_mc.pid[PID_VEL_Z].I
1821         condition: USE_NAV
1822         min: 0
1823         max: 255
1824         default_value: 50
1825       - name: nav_mc_vel_z_d
1826         description: "D gain of velocity PID controller"
1827         default_value: 10
1828         field: bank_mc.pid[PID_VEL_Z].D
1829         condition: USE_NAV
1830         min: 0
1831         max: 255
1832         default_value: 10
1833       - name: nav_mc_pos_xy_p
1834         description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
1835         field: bank_mc.pid[PID_POS_XY].P
1836         condition: USE_NAV
1837         min: 0
1838         max: 255
1839         default_value: 65
1840       - name: nav_mc_vel_xy_p
1841         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"
1842         field: bank_mc.pid[PID_VEL_XY].P
1843         condition: USE_NAV
1844         min: 0
1845         max: 255
1846         default_value: 40
1847       - name: nav_mc_vel_xy_i
1848         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"
1849         field: bank_mc.pid[PID_VEL_XY].I
1850         condition: USE_NAV
1851         min: 0
1852         max: 255
1853         default_value: 15
1854       - name: nav_mc_vel_xy_d
1855         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."
1856         field: bank_mc.pid[PID_VEL_XY].D
1857         condition: USE_NAV
1858         min: 0
1859         max: 255
1860         default_value: 100
1861       - name: nav_mc_vel_xy_ff
1862         field: bank_mc.pid[PID_VEL_XY].FF
1863         condition: USE_NAV
1864         min: 0
1865         max: 255
1866         default_value: 40
1867       - name: nav_mc_heading_p
1868         description: "P gain of Heading Hold controller (Multirotor)"
1869         default_value: 60
1870         field: bank_mc.pid[PID_HEADING].P
1871         condition: USE_NAV
1872         min: 0
1873         max: 255
1874       - name: nav_mc_vel_xy_dterm_lpf_hz
1875         field: navVelXyDTermLpfHz
1876         min: 0
1877         max: 100
1878         default_value: 2
1879       - name: nav_mc_vel_xy_dterm_attenuation
1880         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."
1881         field: navVelXyDtermAttenuation
1882         min: 0
1883         max: 100
1884         default_value: 90
1885       - name: nav_mc_vel_xy_dterm_attenuation_start
1886         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
1887         default_value: 10
1888         field: navVelXyDtermAttenuationStart
1889         min: 0
1890         max: 100
1891       - name: nav_mc_vel_xy_dterm_attenuation_end
1892         description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
1893         default_value: 60
1894         field: navVelXyDtermAttenuationEnd
1895         min: 0
1896         max: 100
1897       - name: nav_fw_pos_z_p
1898         description: "P gain of altitude PID controller (Fixedwing)"
1899         default_value: 40
1900         field: bank_fw.pid[PID_POS_Z].P
1901         condition: USE_NAV
1902         min: 0
1903         max: 255
1904       - name: nav_fw_pos_z_i
1905         description: "I gain of altitude PID controller (Fixedwing)"
1906         default_value: 5
1907         field: bank_fw.pid[PID_POS_Z].I
1908         condition: USE_NAV
1909         min: 0
1910         max: 255
1911       - name: nav_fw_pos_z_d
1912         description: "D gain of altitude PID controller (Fixedwing)"
1913         default_value: 10
1914         field: bank_fw.pid[PID_POS_Z].D
1915         condition: USE_NAV
1916         min: 0
1917         max: 255
1918       - name: nav_fw_pos_xy_p
1919         description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
1920         default_value: 75
1921         field: bank_fw.pid[PID_POS_XY].P
1922         condition: USE_NAV
1923         min: 0
1924         max: 255
1925       - name: nav_fw_pos_xy_i
1926         description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
1927         default_value: 5
1928         field: bank_fw.pid[PID_POS_XY].I
1929         condition: USE_NAV
1930         min: 0
1931         max: 255
1932       - name: nav_fw_pos_xy_d
1933         description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
1934         default_value: 8
1935         field: bank_fw.pid[PID_POS_XY].D
1936         condition: USE_NAV
1937         min: 0
1938         max: 255
1939       - name: nav_fw_heading_p
1940         description: "P gain of Heading Hold controller (Fixedwing)"
1941         default_value: 60
1942         field: bank_fw.pid[PID_HEADING].P
1943         condition: USE_NAV
1944         min: 0
1945         max: 255
1946       - name: nav_fw_pos_hdg_p
1947         description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
1948         default_value: 30
1949         field: bank_fw.pid[PID_POS_HEADING].P
1950         condition: USE_NAV
1951         min: 0
1952         max: 255
1953       - name: nav_fw_pos_hdg_i
1954         description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
1955         default_value: 2
1956         field: bank_fw.pid[PID_POS_HEADING].I
1957         condition: USE_NAV
1958         min: 0
1959         max: 255
1960       - name: nav_fw_pos_hdg_d
1961         description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
1962         default_value: 0
1963         field: bank_fw.pid[PID_POS_HEADING].D
1964         condition: USE_NAV
1965         min: 0
1966         max: 255
1967       - name: nav_fw_pos_hdg_pidsum_limit
1968         description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
1969         default_value: 350
1970         field: navFwPosHdgPidsumLimit
1971         min: PID_SUM_LIMIT_MIN
1972         max: PID_SUM_LIMIT_MAX
1973       - name: mc_iterm_relax
1974         field: iterm_relax
1975         table: iterm_relax
1976         default_value: RP
1977       - name: mc_iterm_relax_cutoff
1978         field: iterm_relax_cutoff
1979         min: 1
1980         max: 100
1981         default_value: 15
1982       - name: d_boost_factor
1983         field: dBoostFactor
1984         condition: USE_D_BOOST
1985         min: 1
1986         max: 3
1987         default_value: 1.25
1988       - name: d_boost_max_at_acceleration
1989         field: dBoostMaxAtAlleceleration
1990         condition: USE_D_BOOST
1991         min: 1000
1992         max: 16000
1993         default_value: 7500
1994       - name: d_boost_gyro_delta_lpf_hz
1995         field: dBoostGyroDeltaLpfHz
1996         condition: USE_D_BOOST
1997         min: 10
1998         max: 250
1999         default_value: 80
2000       - name: antigravity_gain
2001         description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
2002         default_value: 1
2003         field: antigravityGain
2004         condition: USE_ANTIGRAVITY
2005         min: 1
2006         max: 20
2007       - name: antigravity_accelerator
2008         description: ""
2009         default_value: 1
2010         field: antigravityAccelerator
2011         condition: USE_ANTIGRAVITY
2012         min: 1
2013         max: 20
2014       - name: antigravity_cutoff_lpf_hz
2015         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"
2016         default_value: 15
2017         field: antigravityCutoff
2018         condition: USE_ANTIGRAVITY
2019         min: 1
2020         max: 30
2021       - name: pid_type
2022         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`"
2023         field: pidControllerType
2024         table: pidTypeTable
2025         default_value: AUTO
2026       - name: mc_cd_lpf_hz
2027         description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky"
2028         default_value: 30
2029         field: controlDerivativeLpfHz
2030         min: 0
2031         max: 200
2032       - name: setpoint_kalman_enabled
2033         description: "Enable Kalman filter on the PID controller setpoint"
2034         default_value: OFF
2035         condition: USE_GYRO_KALMAN
2036         field: kalmanEnabled
2037         type: bool
2038       - name: setpoint_kalman_q
2039         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"
2040         default_value: 100
2041         field: kalman_q
2042         condition: USE_GYRO_KALMAN
2043         min: 1
2044         max: 16000
2045       - name: setpoint_kalman_w
2046         description: "Window size for the setpoint Kalman filter. Wider the window, more samples are used to compute variance. In general, wider window results in smoother filter response"
2047         default_value: 4
2048         field: kalman_w
2049         condition: USE_GYRO_KALMAN
2050         min: 1
2051         max: 40
2052       - name: setpoint_kalman_sharpness
2053         description: "Dynamic factor for the setpoint Kalman filter. In general, the higher the value, the more dynamic Kalman filter gets"
2054         default_value: 100
2055         field: kalman_sharpness
2056         condition: USE_GYRO_KALMAN
2057         min: 1
2058         max: 16000
2059       - name: fw_level_pitch_trim
2060         description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
2061         default_value: 0
2062         field: fixedWingLevelTrim
2063         min: -10
2064         max: 10
2065       - name: smith_predictor_strength
2066         description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2067         default_value: 0.5
2068         field: smithPredictorStrength
2069         condition: USE_SMITH_PREDICTOR
2070         min: 0
2071         max: 1
2072       - name: smith_predictor_delay
2073         description: "Expected delay of the gyro signal. In milliseconds"
2074         default_value: 0
2075         field: smithPredictorDelay
2076         condition: USE_SMITH_PREDICTOR
2077         min: 0
2078         max: 8
2079       - name: smith_predictor_lpf_hz
2080         description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2081         default_value: 50
2082         field: smithPredictorFilterHz
2083         condition: USE_SMITH_PREDICTOR
2084         min: 1
2085         max: 500
2087   - name: PG_PID_AUTOTUNE_CONFIG
2088     type: pidAutotuneConfig_t
2089     condition: USE_AUTOTUNE_FIXED_WING
2090     members:
2091       - name: fw_autotune_overshoot_time
2092         description: "Time [ms] to detect sustained overshoot"
2093         default_value: 100
2094         field: fw_overshoot_time
2095         min: 50
2096         max: 500
2097       - name: fw_autotune_undershoot_time
2098         description: "Time [ms] to detect sustained undershoot"
2099         default_value: 200
2100         field: fw_undershoot_time
2101         min: 50
2102         max: 500
2103       - name: fw_autotune_threshold
2104         description: "Threshold [%] of max rate to consider overshoot/undershoot detection"
2105         default_value: 50
2106         field: fw_max_rate_threshold
2107         min: 0
2108         max: 100
2109       - name: fw_autotune_ff_to_p_gain
2110         description: "FF to P gain (strength relationship) [%]"
2111         default_value: 10
2112         field: fw_ff_to_p_gain
2113         min: 0
2114         max: 100
2115       - name: fw_autotune_ff_to_i_tc
2116         description: "FF to I time (defines time for I to reach the same level of response as FF) [ms]"
2117         default_value: 600
2118         field: fw_ff_to_i_time_constant
2119         min: 100
2120         max: 5000
2122   - name: PG_POSITION_ESTIMATION_CONFIG
2123     type: positionEstimationConfig_t
2124     condition: USE_NAV
2125     members:
2126       - name: inav_auto_mag_decl
2127         description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
2128         default_value: ON
2129         field: automatic_mag_declination
2130         type: bool
2131       - name: inav_gravity_cal_tolerance
2132         description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
2133         default_value: 5
2134         field: gravity_calibration_tolerance
2135         min: 0
2136         max: 255
2137       - name: inav_use_gps_velned
2138         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."
2139         default_value: ON
2140         field: use_gps_velned
2141         type: bool
2142       - name: inav_use_gps_no_baro
2143         field: use_gps_no_baro
2144         type: bool
2145         default_value: OFF
2146       - name: inav_allow_dead_reckoning
2147         description: "Defines if inav will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
2148         default_value: OFF
2149         field: allow_dead_reckoning
2150         type: bool
2151       - name: inav_reset_altitude
2152         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)"
2153         default_value: "FIRST_ARM"
2154         field: reset_altitude_type
2155         table: reset_type
2156       - name: inav_reset_home
2157         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"
2158         default_value: "FIRST_ARM"
2159         field: reset_home_type
2160         table: reset_type
2161       - name: inav_max_surface_altitude
2162         description: "Max allowed altitude for surface following mode. [cm]"
2163         default_value: 200
2164         field: max_surface_altitude
2165         min: 0
2166         max: 1000
2167       - name: inav_w_z_surface_p
2168         field: w_z_surface_p
2169         min: 0
2170         max: 100
2171         default_value: 3.5
2172       - name: inav_w_z_surface_v
2173         field: w_z_surface_v
2174         min: 0
2175         max: 100
2176         default_value: 6.1
2177       - name: inav_w_xy_flow_p
2178         field: w_xy_flow_p
2179         min: 0
2180         max: 100
2181         default_value: 1.0
2182       - name: inav_w_xy_flow_v
2183         field: w_xy_flow_v
2184         min: 0
2185         max: 100
2186         default_value: 2.0
2187       - name: inav_w_z_baro_p
2188         description: "Weight of barometer measurements in estimated altitude and climb rate"
2189         field: w_z_baro_p
2190         min: 0
2191         max: 10
2192         default_value: 0.35
2193       - name: inav_w_z_gps_p
2194         description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes"
2195         field: w_z_gps_p
2196         min: 0
2197         max: 10
2198         default_value: 0.2
2199       - name: inav_w_z_gps_v
2200         description: "Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero"
2201         field: w_z_gps_v
2202         min: 0
2203         max: 10
2204         default_value: 0.1
2205       - name: inav_w_xy_gps_p
2206         description: "Weight of GPS coordinates in estimated UAV position and speed."
2207         default_value: 1.0
2208         field: w_xy_gps_p
2209         min: 0
2210         max: 10
2211       - name: inav_w_xy_gps_v
2212         description: "Weight of GPS velocity data in estimated UAV speed"
2213         default_value: 2.0
2214         field: w_xy_gps_v
2215         min: 0
2216         max: 10
2217       - name: inav_w_z_res_v
2218         description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
2219         default_value: 0.5
2220         field: w_z_res_v
2221         min: 0
2222         max: 10
2223       - name: inav_w_xy_res_v
2224         description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
2225         default_value: 0.5
2226         field: w_xy_res_v
2227         min: 0
2228         max: 10
2229       - name: inav_w_xyz_acc_p
2230         field: w_xyz_acc_p
2231         min: 0
2232         max: 1
2233         default_value: 1.0
2234       - name: inav_w_acc_bias
2235         description: "Weight for accelerometer drift estimation"
2236         default_value: 0.01
2237         field: w_acc_bias
2238         min: 0
2239         max: 1
2240       - name: inav_max_eph_epv
2241         description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
2242         default_value: 1000
2243         field: max_eph_epv
2244         min: 0
2245         max: 9999
2246       - name: inav_baro_epv
2247         description: "Uncertainty value for barometric sensor [cm]"
2248         default_value: 100
2249         field: baro_epv
2250         min: 0
2251         max: 9999
2253   - name: PG_NAV_CONFIG
2254     type: navConfig_t
2255     headers: ["navigation/navigation.h"]
2256     condition: USE_NAV
2257     members:
2258       - name: nav_disarm_on_landing
2259         description: "If set to ON, iNav disarms the FC after landing"
2260         default_value: OFF
2261         field: general.flags.disarm_on_landing
2262         type: bool
2263       - name: nav_use_midthr_for_althold
2264         description: "If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude"
2265         default_value: OFF
2266         field: general.flags.use_thr_mid_for_althold
2267         type: bool
2268       - name: nav_extra_arming_safety
2269         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"
2270         default_value: "ON"
2271         field: general.flags.extra_arming_safety
2272         table: nav_extra_arming_safety
2273       - name: nav_user_control_mode
2274         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."
2275         default_value: "ATTI"
2276         field: general.flags.user_control_mode
2277         table: nav_user_control_mode
2278       - name: nav_position_timeout
2279         description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
2280         default_value: 5
2281         field: general.pos_failure_timeout
2282         min: 0
2283         max: 10
2284       - name: nav_wp_radius
2285         description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
2286         default_value: 100
2287         field: general.waypoint_radius
2288         min: 10
2289         max: 10000
2290       - name: nav_wp_safe_distance
2291         description: "First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check."
2292         default_value: 10000
2293         field: general.waypoint_safe_distance
2294         max: 65000
2295       - name: nav_auto_speed
2296         description: "Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only]"
2297         default_value: 300
2298         field: general.max_auto_speed
2299         min: 10
2300         max: 2000
2301       - name: nav_auto_climb_rate
2302         description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2303         default_value: 500
2304         field: general.max_auto_climb_rate
2305         min: 10
2306         max: 2000
2307       - name: nav_manual_speed
2308         description: "Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
2309         default_value: 500
2310         field: general.max_manual_speed
2311         min: 10
2312         max: 2000
2313       - name: nav_manual_climb_rate
2314         description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2315         default_value: 200
2316         field: general.max_manual_climb_rate
2317         min: 10
2318         max: 2000
2319       - name: nav_land_minalt_vspd
2320         description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
2321         default_value: 50
2322         field: general.land_minalt_vspd
2323         min: 50
2324         max: 500
2325       - name: nav_land_maxalt_vspd
2326         description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"
2327         default_value: 200
2328         field: general.land_maxalt_vspd
2329         min: 100
2330         max: 2000
2331       - name: nav_land_slowdown_minalt
2332         description: "Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]"
2333         default_value: 500
2334         field: general.land_slowdown_minalt
2335         min: 50
2336         max: 1000
2337       - name: nav_land_slowdown_maxalt
2338         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]"
2339         default_value: 2000
2340         field: general.land_slowdown_maxalt
2341         min: 500
2342         max: 4000
2343       - name: nav_emerg_landing_speed
2344         description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
2345         default_value: 500
2346         field: general.emerg_descent_rate
2347         min: 100
2348         max: 2000
2349       - name: nav_min_rth_distance
2350         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."
2351         default_value: 500
2352         field: general.min_rth_distance
2353         min: 0
2354         max: 5000
2355       - name: nav_overrides_motor_stop
2356         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"
2357         default_value: "ALL_NAV"
2358         field: general.flags.nav_overrides_motor_stop
2359         table: nav_overrides_motor_stop
2360       - name: nav_rth_climb_first
2361         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)"
2362         default_value: "ON"
2363         field: general.flags.rth_climb_first
2364         table: nav_rth_climb_first
2365       - name: nav_rth_climb_ignore_emerg
2366         description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
2367         default_value: OFF
2368         field: general.flags.rth_climb_ignore_emerg
2369         type: bool
2370       - name: nav_rth_tail_first
2371         description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
2372         default_value: OFF
2373         field: general.flags.rth_tail_first
2374         type: bool
2375       - name: nav_rth_allow_landing
2376         description: "If set to ON drone will land as a last phase of RTH."
2377         default_value: "ALWAYS"
2378         field: general.flags.rth_allow_landing
2379         table: nav_rth_allow_landing
2380       - name: nav_rth_alt_mode
2381         description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details"
2382         default_value: "AT_LEAST"
2383         field: general.flags.rth_alt_control_mode
2384         table: nav_rth_alt_mode
2385       - name: nav_rth_alt_control_override
2386         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)"
2387         default_value: OFF
2388         field: general.flags.rth_alt_control_override
2389         type: bool
2390       - name: nav_rth_abort_threshold
2391         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. [cm]"
2392         default_value: 50000
2393         field: general.rth_abort_threshold
2394         max: 65000
2395       - name: nav_max_terrain_follow_alt
2396         field: general.max_terrain_follow_altitude
2397         default_value: "100"
2398         description: "Max allowed above the ground altitude for terrain following mode"
2399         max: 1000
2400         default_value: 100
2401       - name: nav_rth_altitude
2402         description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
2403         default_value: 1000
2404         field: general.rth_altitude
2405         max: 65000
2406       - name: nav_rth_home_altitude
2407         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]"
2408         default_value: 0
2409         field: general.rth_home_altitude
2410         max: 65000
2411       - name: safehome_max_distance
2412         description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
2413         default_value: 20000
2414         field: general.safehome_max_distance
2415         min: 0
2416         max: 65000
2417       - name: safehome_usage_mode
2418         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."
2419         default_value: "RTH"
2420         field: general.flags.safehome_usage_mode
2421         table: safehome_usage_mode
2422       - name: nav_mc_bank_angle
2423         description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
2424         default_value: 30
2425         field: mc.max_bank_angle
2426         min: 15
2427         max: 45
2428       - name: nav_mc_hover_thr
2429         description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
2430         default_value: 1500
2431         field: mc.hover_throttle
2432         min: 1000
2433         max: 2000
2434       - name: nav_mc_auto_disarm_delay
2435         description: "Delay before multi-rotor disarms when `nav_disarm_on_landing` is set (m/s)"
2436         default_value: 2000
2437         field: mc.auto_disarm_delay
2438         min: 100
2439         max: 10000
2440       - name: nav_mc_braking_speed_threshold
2441         description: "min speed in cm/s above which braking can happen"
2442         default_value: 100
2443         field: mc.braking_speed_threshold
2444         condition: USE_MR_BRAKING_MODE
2445         min: 0
2446         max: 1000
2447       - name: nav_mc_braking_disengage_speed
2448         description: "braking is disabled when speed goes below this value"
2449         default_value: 75
2450         field: mc.braking_disengage_speed
2451         condition: USE_MR_BRAKING_MODE
2452         min: 0
2453         max: 1000
2454       - name: nav_mc_braking_timeout
2455         description: "timeout in ms for braking"
2456         default_value: 2000
2457         field: mc.braking_timeout
2458         condition: USE_MR_BRAKING_MODE
2459         min: 100
2460         max: 5000
2461       - name: nav_mc_braking_boost_factor
2462         description: "acceleration factor for BOOST phase"
2463         default_value: 100
2464         field: mc.braking_boost_factor
2465         condition: USE_MR_BRAKING_MODE
2466         min: 0
2467         max: 200
2468       - name: nav_mc_braking_boost_timeout
2469         description: "how long in ms BOOST phase can happen"
2470         default_value: 750
2471         field: mc.braking_boost_timeout
2472         condition: USE_MR_BRAKING_MODE
2473         min: 0
2474         max: 5000
2475       - name: nav_mc_braking_boost_speed_threshold
2476         description: "BOOST can be enabled when speed is above this value"
2477         default_value: 150
2478         field: mc.braking_boost_speed_threshold
2479         condition: USE_MR_BRAKING_MODE
2480         min: 100
2481         max: 1000
2482       - name: nav_mc_braking_boost_disengage_speed
2483         description: "BOOST will be disabled when speed goes below this value"
2484         default_value: 100
2485         field: mc.braking_boost_disengage_speed
2486         condition: USE_MR_BRAKING_MODE
2487         min: 0
2488         max: 1000
2489       - name: nav_mc_braking_bank_angle
2490         description: "max angle that MR is allowed to bank in BOOST mode"
2491         default_value: 40
2492         field: mc.braking_bank_angle
2493         condition: USE_MR_BRAKING_MODE
2494         min: 15
2495         max: 60
2496       - name: nav_mc_pos_deceleration_time
2497         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"
2498         default_value: 120
2499         field: mc.posDecelerationTime
2500         condition: USE_NAV
2501         min: 0
2502         max: 255
2503       - name: nav_mc_pos_expo
2504         description: "Expo for PosHold control"
2505         default_value: 10
2506         field: mc.posResponseExpo
2507         condition: USE_NAV
2508         min: 0
2509         max: 255
2510       - name: nav_mc_wp_slowdown
2511         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."
2512         default_value: ON
2513         field: mc.slowDownForTurning
2514         type: bool
2515       - name: nav_fw_cruise_thr
2516         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 )"
2517         default_value: 1400
2518         field: fw.cruise_throttle
2519         min: 1000
2520         max: 2000
2521       - name: nav_fw_min_thr
2522         description: "Minimum throttle for flying wing in GPS assisted modes"
2523         default_value: 1200
2524         field: fw.min_throttle
2525         min: 1000
2526         max: 2000
2527       - name: nav_fw_max_thr
2528         description: "Maximum throttle for flying wing in GPS assisted modes"
2529         default_value: 1700
2530         field: fw.max_throttle
2531         min: 1000
2532         max: 2000
2533       - name: nav_fw_bank_angle
2534         description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
2535         default_value: 35
2536         field: fw.max_bank_angle
2537         min: 5
2538         max: 80
2539       - name: nav_fw_climb_angle
2540         description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2541         default_value: 20
2542         field: fw.max_climb_angle
2543         min: 5
2544         max: 80
2545       - name: nav_fw_dive_angle
2546         description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2547         default_value: 15
2548         field: fw.max_dive_angle
2549         min: 5
2550         max: 80
2551       - name: nav_fw_pitch2thr
2552         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)"
2553         default_value: 10
2554         field: fw.pitch_to_throttle
2555         min: 0
2556         max: 100
2557       - name: nav_fw_pitch2thr_smoothing
2558         description:  "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
2559         default_value: 6
2560         field: fw.pitch_to_throttle_smooth
2561         min: 0
2562         max: 9
2563       - name: nav_fw_pitch2thr_threshold
2564         description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
2565         default_value: 50
2566         field: fw.pitch_to_throttle_thresh
2567         min: 0
2568         max: 900
2569       - name: nav_fw_loiter_radius
2570         description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
2571         default_value: 7500
2572         field: fw.loiter_radius
2573         min: 0
2574         max: 30000
2575       - name: nav_fw_cruise_speed
2576         description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
2577         default_value: 0
2578         field: fw.cruise_speed
2579         min: 0
2580         max: 65535
2581       - name: nav_fw_control_smoothness
2582         description: "How smoothly the autopilot controls the airplane to correct the navigation error"
2583         default_value: 0
2584         field: fw.control_smoothness
2585         min: 0
2586         max: 9
2588       - name: nav_fw_land_dive_angle
2589         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"
2590         default_value: 2
2591         field: fw.land_dive_angle
2592         condition: NAV_FIXED_WING_LANDING
2593         min: -20
2594         max: 20
2596       - name: nav_fw_launch_velocity
2597         description: "Forward velocity threshold for swing-launch detection [cm/s]"
2598         default_value: 300
2599         field: fw.launch_velocity_thresh
2600         min: 100
2601         max: 10000
2602       - name: nav_fw_launch_accel
2603         description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s"
2604         default_value: 1863
2605         field: fw.launch_accel_thresh
2606         min: 1000
2607         max: 20000
2608       - name: nav_fw_launch_max_angle
2609         description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
2610         default_value: 45
2611         field: fw.launch_max_angle
2612         min: 5
2613         max: 180
2614       - name: nav_fw_launch_detect_time
2615         description: "Time for which thresholds have to breached to consider launch happened [ms]"
2616         default_value: 40
2617         field: fw.launch_time_thresh
2618         min: 10
2619         max: 1000
2620       - name: nav_fw_launch_thr
2621         description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
2622         default_value: 1700
2623         field: fw.launch_throttle
2624         min: 1000
2625         max: 2000
2626       - name: nav_fw_launch_idle_thr
2627         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)"
2628         default_value: 1000
2629         field: fw.launch_idle_throttle
2630         min: 1000
2631         max: 2000
2632       - name: nav_fw_launch_motor_delay
2633         description: "Delay between detected launch and launch sequence start and throttling up (ms)"
2634         default_value: 500
2635         field: fw.launch_motor_timer
2636         min: 0
2637         max: 5000
2638       - name: nav_fw_launch_spinup_time
2639         description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
2640         default_value: 100
2641         field: fw.launch_motor_spinup_time
2642         min: 0
2643         max: 1000
2644       - name: nav_fw_launch_end_time
2645         description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
2646         default_value: 3000
2647         field: fw.launch_end_time
2648         min: 0
2649         max: 5000
2650       - name: nav_fw_launch_min_time
2651         description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
2652         default_value: 0
2653         field: fw.launch_min_time
2654         min: 0
2655         max: 60000
2656       - name: nav_fw_launch_timeout
2657         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)"
2658         default_value: 5000
2659         field: fw.launch_timeout
2660         max: 60000
2661       - name: nav_fw_launch_max_altitude
2662         description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
2663         default_value: 0
2664         field: fw.launch_max_altitude
2665         min: 0
2666         max: 60000
2667       - name: nav_fw_launch_climb_angle
2668         description: "Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
2669         default_value: 18
2670         field: fw.launch_climb_angle
2671         min: 5
2672         max: 45
2673       - name: nav_fw_cruise_yaw_rate
2674         description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]"
2675         default_value: 20
2676         field: fw.cruise_yaw_rate
2677         min: 0
2678         max: 60
2679       - name: nav_fw_allow_manual_thr_increase
2680         description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
2681         default_value: OFF
2682         field: fw.allow_manual_thr_increase
2683         type: bool
2684       - name: nav_use_fw_yaw_control
2685         description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
2686         default_value: OFF
2687         field: fw.useFwNavYawControl
2688         type: bool
2689       - name: nav_fw_yaw_deadband
2690         description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
2691         default_value: 0
2692         field: fw.yawControlDeadband
2693         min: 0
2694         max: 90
2696   - name: PG_TELEMETRY_CONFIG
2697     type: telemetryConfig_t
2698     headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/frsky_d.h", "telemetry/sim.h"]
2699     condition: USE_TELEMETRY
2700     members:
2701       - name: telemetry_switch
2702         description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
2703         default_value: OFF
2704         type: bool
2705       - name: telemetry_inverted
2706         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."
2707         default_value: OFF
2708         type: bool
2709       - name: frsky_default_latitude
2710         description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired."
2711         default_value: 0
2712         field: gpsNoFixLatitude
2713         min: -90
2714         max: 90
2715       - name: frsky_default_longitude
2716         description: "D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired."
2717         default_value: 0
2718         field: gpsNoFixLongitude
2719         min: -180
2720         max: 180
2721       - name: frsky_coordinates_format
2722         description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA"
2723         default_value: 0
2724         field: frsky_coordinate_format
2725         min: 0
2726         max: FRSKY_FORMAT_NMEA
2727         type: uint8_t # TODO: This seems to use an enum, we should use table:
2728       - name: frsky_unit
2729         description: "Not used? [METRIC/IMPERIAL]"
2730         default_value: "METRIC"
2731         table: frsky_unit
2732         type: uint8_t
2733       - name: frsky_vfas_precision
2734         description: "D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method"
2735         default_value: 0
2736         min: FRSKY_VFAS_PRECISION_LOW
2737         max: FRSKY_VFAS_PRECISION_HIGH
2738       - name: frsky_pitch_roll
2739         description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
2740         default_value: OFF
2741         type: bool
2742       - name: report_cell_voltage
2743         description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON"
2744         default_value: OFF
2745         type: bool
2746       - name: hott_alarm_sound_interval
2747         description: "Battery alarm delay in seconds for Hott telemetry"
2748         default_value: 5
2749         field: hottAlarmSoundInterval
2750         min: 0
2751         max: 120
2752       - name: telemetry_halfduplex
2753         description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
2754         default_value: ON
2755         field: halfDuplex
2756         type: bool
2757       - name: smartport_fuel_unit
2758         description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]"
2759         default_value: "MAH"
2760         field: smartportFuelUnit
2761         condition: USE_TELEMETRY_SMARTPORT
2762         type: uint8_t
2763         table: smartport_fuel_unit
2764       - name: ibus_telemetry_type
2765         description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
2766         default_value: 0
2767         field: ibusTelemetryType
2768         min: 0
2769         max: 255
2770       - name: ltm_update_rate
2771         description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details."
2772         default_value: "NORMAL"
2773         field: ltmUpdateRate
2774         condition: USE_TELEMETRY_LTM
2775         table: ltm_rates
2776       - name: sim_ground_station_number
2777         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."
2778         default_value: ""
2779         field: simGroundStationNumber
2780         condition: USE_TELEMETRY_SIM
2781       - name: sim_pin
2782         description: "PIN code for the SIM module"
2783         default_value: "0000"
2784         field: simPin
2785         condition: USE_TELEMETRY_SIM
2786       - name: sim_transmit_interval
2787         description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
2788         default_value: 60
2789         field: simTransmitInterval
2790         condition: USE_TELEMETRY_SIM
2791         type: uint16_t
2792         min: SIM_MIN_TRANSMIT_INTERVAL
2793         max: 65535
2794       - name: sim_transmit_flags
2795         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`"
2796         default_value: :SIM_TX_FLAG_FAILSAFE
2797         field: simTransmitFlags
2798         condition: USE_TELEMETRY_SIM
2799         max: 63
2800       - name: acc_event_threshold_high
2801         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."
2802         default_value: 0
2803         field: accEventThresholdHigh
2804         condition: USE_TELEMETRY_SIM
2805         type: uint16_t
2806         min: 0
2807         max: 65535
2808       - name: acc_event_threshold_low
2809         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."
2810         default_value: 0
2811         field: accEventThresholdLow
2812         condition: USE_TELEMETRY_SIM
2813         type: uint16_t
2814         min: 0
2815         max: 900
2816       - name: acc_event_threshold_neg_x
2817         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."
2818         default_value: 0
2819         field: accEventThresholdNegX
2820         condition: USE_TELEMETRY_SIM
2821         type: uint16_t
2822         min: 0
2823         max: 65535
2824       - name: sim_low_altitude
2825         description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
2826         default_value: -32767
2827         field: simLowAltitude
2828         condition: USE_TELEMETRY_SIM
2829         type: int16_t
2830         min: INT16_MIN
2831         max: INT16_MAX
2832       - name: mavlink_ext_status_rate
2833         field: mavlink.extended_status_rate
2834         type: uint8_t
2835         min: 0
2836         max: 255
2837         default_value: 2
2838       - name: mavlink_rc_chan_rate
2839         field: mavlink.rc_channels_rate
2840         type: uint8_t
2841         min: 0
2842         max: 255
2843         default_value: 5
2844       - name: mavlink_pos_rate
2845         field: mavlink.position_rate
2846         type: uint8_t
2847         min: 0
2848         max: 255
2849         default_value: 2
2850       - name: mavlink_extra1_rate
2851         field: mavlink.extra1_rate
2852         type: uint8_t
2853         min: 0
2854         max: 255
2855         default_value: 10
2856       - name: mavlink_extra2_rate
2857         field: mavlink.extra2_rate
2858         type: uint8_t
2859         min: 0
2860         max: 255
2861         default_value: 2
2862       - name: mavlink_extra3_rate
2863         field: mavlink.extra3_rate
2864         type: uint8_t
2865         min: 0
2866         max: 255
2867         default_value: 1
2868       - name: mavlink_version
2869         field: mavlink.version
2870         description: "Version of MAVLink to use"
2871         type: uint8_t
2872         min: 1
2873         max: 2
2874         default_value: 2
2875   - name: PG_ELERES_CONFIG
2876     type: eleresConfig_t
2877     headers: ["rx/eleres.h"]
2878     condition: USE_RX_ELERES
2879     members:
2880       - name: eleres_freq
2881         field: eleresFreq
2882         min: 415
2883         max: 450
2884         default_value: 435
2885       - name: eleres_telemetry_en
2886         field: eleresTelemetryEn
2887         type: bool
2888         default_value: OFF
2889       - name: eleres_telemetry_power
2890         field: eleresTelemetryPower
2891         min: 0
2892         max: 7
2893         default_value: 7
2894       - name: eleres_loc_en
2895         field: eleresLocEn
2896         type: bool
2897         default_value: OFF
2898       - name: eleres_loc_power
2899         field: eleresLocPower
2900         min: 0
2901         max: 7
2902         default_value: 7
2903       - name: eleres_loc_delay
2904         field: eleresLocDelay
2905         min: 30
2906         max: 1800
2907         default_value: 240
2908       - name: eleres_signature
2909         field: eleresSignature
2910         max: UINT32_MAX
2911         default_value: :zero
2913   - name: PG_LED_STRIP_CONFIG
2914     type: ledStripConfig_t
2915     headers: ["common/color.h", "io/ledstrip.h"]
2916     condition: USE_LED_STRIP
2917     members:
2918       - name: ledstrip_visual_beeper
2919         description: ""
2920         default_value: OFF
2921         type: bool
2923   - name: PG_OSD_CONFIG
2924     type: osdConfig_t
2925     headers: ["io/osd.h", "drivers/osd.h"]
2926     condition: USE_OSD
2927     members:
2928       - name: osd_telemetry
2929         description: "To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`"
2930         table: osd_telemetry
2931         field: telemetry
2932         type: uint8_t
2933         default_value: "OFF"
2934       - name: osd_video_system
2935         description: "Video system used. Possible values are `AUTO`, `PAL` and `NTSC`"
2936         default_value: "AUTO"
2937         table: osd_video_system
2938         field: video_system
2939         type: uint8_t
2940       - name: osd_row_shiftdown
2941         description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
2942         default_value: 0
2943         field: row_shiftdown
2944         min: 0
2945         max: 1
2946       - name: osd_units
2947         description: "IMPERIAL, METRIC, UK"
2948         default_value: "METRIC"
2949         field: units
2950         table: osd_unit
2951         type: uint8_t
2952       - name: osd_stats_energy_unit
2953         description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)"
2954         default_value: "MAH"
2955         field: stats_energy_unit
2956         table: osd_stats_energy_unit
2957         type: uint8_t
2958       - name: osd_stats_min_voltage_unit
2959         description: "Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats."
2960         default_value: "BATTERY"
2961         field: stats_min_voltage_unit
2962         table: osd_stats_min_voltage_unit
2963         type: uint8_t
2964       - name: osd_stats_page_auto_swap_time
2965         description: "Auto swap display time interval between disarm stats pages (seconds)."
2966         default_value: 3
2967         field: stats_page_auto_swap_time
2968         min: 1
2969         max: 10
2970       - name: osd_rssi_alarm
2971         description: "Value below which to make the OSD RSSI indicator blink"
2972         default_value: 20
2973         field: rssi_alarm
2974         min: 0
2975         max: 100
2976       - name: osd_time_alarm
2977         description: "Value above which to make the OSD flight time indicator blink (minutes)"
2978         default_value: 10
2979         field: time_alarm
2980         min: 0
2981         max: 600
2982       - name: osd_alt_alarm
2983         description: "Value above which to make the OSD relative altitude indicator blink (meters)"
2984         default_value: 100
2985         field: alt_alarm
2986         min: 0
2987         max: 10000
2988       - name: osd_dist_alarm
2989         description: "Value above which to make the OSD distance from home indicator blink (meters)"
2990         default_value: 1000
2991         field: dist_alarm
2992         min: 0
2993         max: 50000
2994       - name: osd_neg_alt_alarm
2995         description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
2996         default_value: 5
2997         field: neg_alt_alarm
2998         min: 0
2999         max: 10000
3000       - name: osd_current_alarm
3001         description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
3002         default_value: 0
3003         field: current_alarm
3004         min: 0
3005         max: 255
3006       - name: osd_gforce_alarm
3007         description: "Value above which the OSD g force indicator will blink (g)"
3008         default_value: 5
3009         field: gforce_alarm
3010         min: 0
3011         max: 20
3012       - name: osd_gforce_axis_alarm_min
3013         description: "Value under which the OSD axis g force indicators will blink (g)"
3014         default_value: -5
3015         field: gforce_axis_alarm_min
3016         min: -20
3017         max: 20
3018       - name: osd_gforce_axis_alarm_max
3019         description: "Value above which the OSD axis g force indicators will blink (g)"
3020         default_value: 5
3021         field: gforce_axis_alarm_max
3022         min: -20
3023         max: 20
3024       - name: osd_imu_temp_alarm_min
3025         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3026         default_value: -200
3027         field: imu_temp_alarm_min
3028         min: -550
3029         max: 1250
3030       - name: osd_imu_temp_alarm_max
3031         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3032         default_value: 600
3033         field: imu_temp_alarm_max
3034         min: -550
3035         max: 1250
3036       - name: osd_esc_temp_alarm_max
3037         description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3038         default_value: 900
3039         field: esc_temp_alarm_max
3040         min: -550
3041         max: 1500
3042       - name: osd_esc_temp_alarm_min
3043         description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3044         default_value: -200
3045         field: esc_temp_alarm_min
3046         min: -550
3047         max: 1500
3048       - name: osd_baro_temp_alarm_min
3049         description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3050         default_value: -200
3051         field: baro_temp_alarm_min
3052         condition: USE_BARO
3053         min: -550
3054         max: 1250
3055       - name: osd_baro_temp_alarm_max
3056         description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3057         default_value: 600
3058         field: baro_temp_alarm_max
3059         condition: USE_BARO
3060         min: -550
3061         max: 1250
3062       - name: osd_snr_alarm
3063         condition: USE_SERIALRX_CRSF
3064         description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
3065         default_value: 4
3066         field: snr_alarm
3067         min: -20
3068         max: 10
3069       - name: osd_link_quality_alarm
3070         condition: USE_SERIALRX_CRSF
3071         description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
3072         default_value: 70
3073         field: link_quality_alarm
3074         min: 0
3075         max: 100
3076       - name: osd_temp_label_align
3077         description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
3078         default_value: "LEFT"
3079         field: temp_label_align
3080         condition: USE_TEMPERATURE_SENSOR
3081         table: osd_alignment
3082         type: uint8_t
3084       - name: osd_ahi_reverse_roll
3085         field: ahi_reverse_roll
3086         type: bool
3087         default_value: OFF
3088       - name: osd_ahi_max_pitch
3089         description: "Max pitch, in degrees, for OSD artificial horizon"
3090         default_value: 20
3091         field: ahi_max_pitch
3092         min: 10
3093         max: 90
3094         default_value: 20
3095       - name: osd_crosshairs_style
3096         description: "To set the visual type for the crosshair"
3097         default_value: "DEFAULT"
3098         field: crosshairs_style
3099         table: osd_crosshairs_style
3100         type: uint8_t
3101       - name: osd_crsf_lq_format
3102         description: "To select LQ format"
3103         default_value: "TYPE1"
3104         field: crsf_lq_format
3105         table: osd_crsf_lq_format
3106         type: uint8_t
3107       - name: osd_horizon_offset
3108         description: "To vertically adjust the whole OSD and AHI and scrolling bars"
3109         default_value: 0
3110         field: horizon_offset
3111         min: -2
3112         max: 2
3113       - name: osd_camera_uptilt
3114         description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal"
3115         default_value: 0
3116         field: camera_uptilt
3117         min: -40
3118         max: 80
3119       - name: osd_camera_fov_h
3120         description: "Horizontal field of view for the camera in degres"
3121         default_value: 135
3122         field: camera_fov_h
3123         min: 60
3124         max: 150
3125       - name: osd_camera_fov_v
3126         description: "Vertical field of view for the camera in degres"
3127         default_value: 85
3128         field: camera_fov_v
3129         min: 30
3130         max: 120
3131       - name: osd_hud_margin_h
3132         description: "Left and right margins for the hud area"
3133         default_value: 3
3134         field: hud_margin_h
3135         min: 0
3136         max: 4
3137       - name: osd_hud_margin_v
3138         description: "Top and bottom margins for the hud area"
3139         default_value: 3
3140         field: hud_margin_v
3141         min: 1
3142         max: 3
3143       - name: osd_hud_homing
3144         description: "To display little arrows around the crossair showing where the home point is in the hud"
3145         default_value: OFF
3146         field: hud_homing
3147         type: bool
3148       - name: osd_hud_homepoint
3149         description: "To 3D-display the home point location in the hud"
3150         default_value: OFF
3151         field: hud_homepoint
3152         type: bool
3153       - name: osd_hud_radar_disp
3154         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"
3155         default_value: 0
3156         field: hud_radar_disp
3157         min: 0
3158         max: 4
3159       - name: osd_hud_radar_range_min
3160         description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
3161         default_value: 3
3162         field: hud_radar_range_min
3163         min: 1
3164         max: 30
3165       - name: osd_hud_radar_range_max
3166         description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
3167         default_value: 4000
3168         field: hud_radar_range_max
3169         min: 100
3170         max: 9990
3171       - name: osd_hud_radar_nearest
3172         description: "To display an extra bar of informations at the bottom of the hud area for the closest radar aircraft found, if closest than the set value, in meters. Shows relative altitude (meters or feet, with an up or down arrow to indicate if above or below), speed (in m/s or f/s), and absolute heading (in Â°, 0 is north, 90 is east, 180 is south, 270 is west). Set to 0 (zero) to disable."
3173         default_value: 0
3174         field: hud_radar_nearest
3175         min: 0
3176         max: 4000
3177       - name: osd_hud_wp_disp
3178         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)"
3179         default_value: 0
3180         field: hud_wp_disp
3182         min: 0
3183         max: 3
3184       - name: osd_left_sidebar_scroll
3185         field: left_sidebar_scroll
3186         table: osd_sidebar_scroll
3187         type: uint8_t
3188         default_value: NONE
3189       - name: osd_right_sidebar_scroll
3190         field: right_sidebar_scroll
3191         table: osd_sidebar_scroll
3192         type: uint8_t
3193         default_value: NONE
3194       - name: osd_sidebar_scroll_arrows
3195         field: sidebar_scroll_arrows
3196         type: bool
3197         default_value: OFF
3198       - name: osd_main_voltage_decimals
3199         description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
3200         default_value: 1
3201         field: main_voltage_decimals
3202         min: 1
3203         max: 2
3204       - name: osd_coordinate_digits
3205         field: coordinate_digits
3206         min: 8
3207         max: 11
3208         default_value: 9
3210       - name: osd_estimations_wind_compensation
3211         description: "Use wind estimation for remaining flight time/distance estimation"
3212         default_value: ON
3213         condition: USE_WIND_ESTIMATOR
3214         field: estimations_wind_compensation
3215         type: bool
3217       - name: osd_failsafe_switch_layout
3218         description: "If enabled the OSD automatically switches to the first layout during failsafe"
3219         default_value: OFF
3220         type: bool
3222       - name: osd_plus_code_digits
3223         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."
3224         field: plus_code_digits
3225         default_value: 11
3226         min: 10
3227         max: 13
3228       - name: osd_plus_code_short
3229         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."
3230         field: plus_code_short
3231         default_value: "0"
3232         table: osd_plus_code_short
3234       - name: osd_ahi_style
3235         description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
3236         field: ahi_style
3237         default_value: "DEFAULT"
3238         table: osd_ahi_style
3239         type: uint8_t
3241       - name: osd_force_grid
3242         field: force_grid
3243         type: bool
3244         default_value: OFF
3245         description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
3247       - name: osd_ahi_bordered
3248         field: ahi_bordered
3249         type: bool
3250         description: Shows a border/corners around the AHI region (pixel OSD only)
3251         default_value: OFF
3253       - name: osd_ahi_width
3254         field: ahi_width
3255         max: 255
3256         description: AHI width in pixels (pixel OSD only)
3257         default_value: 132
3259       - name: osd_ahi_height
3260         field: ahi_height
3261         max: 255
3262         description: AHI height in pixels (pixel OSD only)
3263         default_value: 162
3265       - name: osd_ahi_vertical_offset
3266         field: ahi_vertical_offset
3267         min: -128
3268         max: 127
3269         description: AHI vertical offset from center (pixel OSD only)
3270         default_value: -18
3272       - name: osd_sidebar_horizontal_offset
3273         field: sidebar_horizontal_offset
3274         min: -128
3275         max: 127
3276         default_value: 0
3277         description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
3279       - name: osd_left_sidebar_scroll_step
3280         field: left_sidebar_scroll_step
3281         max: 255
3282         default_value: 0
3283         description: How many units each sidebar step represents. 0 means the default value for the scroll type.
3285       - name: osd_right_sidebar_scroll_step
3286         field: right_sidebar_scroll_step
3287         max: 255
3288         default_value: 0
3289         description: Same as left_sidebar_scroll_step, but for the right sidebar
3291       - name: osd_home_position_arm_screen
3292         type: bool
3293         default_value: ON
3294         description: Should home position coordinates be displayed on the arming screen.
3296       - name: osd_pan_servo_index
3297         description: Index of the pan servo to adjust osd home heading direction based on camera pan. Note that this feature does not work with continiously rotating servos.
3298         field: pan_servo_index
3299         min: 0
3300         max: 10
3301         default_value: 0
3303       - name: osd_pan_servo_pwm2centideg
3304         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.
3305         field: pan_servo_pwm2centideg
3306         default_value: 0
3307         min: -36
3308         max: 36
3311   - name: PG_SYSTEM_CONFIG
3312     type: systemConfig_t
3313     headers: ["fc/config.h"]
3314     members:
3315       - name: i2c_speed
3316         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)"
3317         default_value: "400KHZ"
3318         condition: USE_I2C
3319         table: i2c_speed
3320       - name: cpu_underclock
3321         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"
3322         default_value: OFF
3323         field: cpuUnderclock
3324         condition: USE_UNDERCLOCK
3325         type: bool
3326       - name: debug_mode
3327         description: "Defines debug values exposed in debug variables (developer / debugging setting)"
3328         default_value: "NONE"
3329         table: debug_modes
3330       - name: throttle_tilt_comp_str
3331         description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
3332         default_value: 0
3333         field: throttle_tilt_compensation_strength
3334         min: 0
3335         max: 100
3336       - name: name
3337         description: "Craft name"
3338         default_value: ""
3340   - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
3341     type: modeActivationOperatorConfig_t
3342     headers: ["fc/rc_modes.h"]
3343     members:
3344       - name: mode_range_logic_operator
3345         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."
3346         default_value: "OR"
3347         field: modeActivationOperator
3348         table: aux_operator
3349         type: uint8_t
3351   - name: PG_STATS_CONFIG
3352     type: statsConfig_t
3353     headers: ["fc/stats.h"]
3354     condition: USE_STATS
3355     members:
3356       - name: stats
3357         description: "General switch of the statistics recording feature (a.k.a. odometer)"
3358         default_value: OFF
3359         field: stats_enabled
3360         type: bool
3361       - name: stats_total_time
3362         description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
3363         default_value: 0
3364         max: INT32_MAX
3365       - name: stats_total_dist
3366         description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
3367         default_value: 0
3368         max: INT32_MAX
3369       - name: stats_total_energy
3370         max: INT32_MAX
3371         condition: USE_ADC
3372         default_value: 0
3374   - name: PG_TIME_CONFIG
3375     type: timeConfig_t
3376     headers: ["common/time.h"]
3377     members:
3378       - name: tz_offset
3379         description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
3380         default_value: 0
3381         min: -1440
3382         max: 1440
3383       - name: tz_automatic_dst
3384         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`."
3385         default_value: "OFF"
3386         type: uint8_t
3387         table: tz_automatic_dst
3389   - name: PG_DISPLAY_CONFIG
3390     type: displayConfig_t
3391     headers: ["drivers/display.h"]
3392     members:
3393       - name: display_force_sw_blink
3394         description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
3395         default_value: OFF
3396         field: force_sw_blink
3397         type: bool
3399   - name: PG_VTX_CONFIG
3400     type: vtxConfig_t
3401     headers: ["io/vtx_control.h"]
3402     condition: USE_VTX_CONTROL
3403     members:
3404       - name: vtx_halfduplex
3405         description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
3406         default_value: ON
3407         field: halfDuplex
3408         type: bool
3409       - name: vtx_smartaudio_early_akk_workaround
3410         description: "Enable workaround for early AKK SAudio-enabled VTX bug."
3411         default_value: ON
3412         field: smartAudioEarlyAkkWorkaroundEnable
3413         type: bool
3415   - name: PG_VTX_SETTINGS_CONFIG
3416     type: vtxSettingsConfig_t
3417     headers: ["drivers/vtx_common.h", "io/vtx.h"]
3418     condition: USE_VTX_SMARTAUDIO || USE_VTX_TRAMP
3419     members:
3420       - name: vtx_band
3421         description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
3422         default_value: 4
3423         field: band
3424         min: VTX_SETTINGS_NO_BAND
3425         max: VTX_SETTINGS_MAX_BAND
3426       - name: vtx_channel
3427         description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
3428         default_value: 1
3429         field: channel
3430         min: VTX_SETTINGS_MIN_CHANNEL
3431         max: VTX_SETTINGS_MAX_CHANNEL
3432       - name: vtx_power
3433         description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
3434         default_value: 1
3435         field: power
3436         min: VTX_SETTINGS_MIN_POWER
3437         max: VTX_SETTINGS_MAX_POWER
3438       - name: vtx_low_power_disarm
3439         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."
3440         default_value: "OFF"
3441         field: lowPowerDisarm
3442         table: vtx_low_power_disarm
3443         type: uint8_t
3444       - name: vtx_pit_mode_chan
3445         field: pitModeChan
3446         min: VTX_SETTINGS_MIN_CHANNEL
3447         max: VTX_SETTINGS_MAX_CHANNEL
3448         default_value: 1
3449       - name: vtx_max_power_override
3450         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"
3451         default_value: 0
3452         field: maxPowerOverride
3453         min: 0
3454         max: 10000
3456   - name: PG_PINIOBOX_CONFIG
3457     type: pinioBoxConfig_t
3458     headers: ["io/piniobox.h"]
3459     condition: USE_PINIOBOX
3460     members:
3461       - name: pinio_box1
3462         field: permanentId[0]
3463         description: "Mode assignment for PINIO#1"
3464         default_value: "target specific"
3465         min: 0
3466         max: 255
3467         default_value: :BOX_PERMANENT_ID_NONE
3468         type: uint8_t
3469       - name: pinio_box2
3470         field: permanentId[1]
3471         default_value: "target specific"
3472         description: "Mode assignment for PINIO#1"
3473         min: 0
3474         max: 255
3475         default_value: :BOX_PERMANENT_ID_NONE
3476         type: uint8_t
3477       - name: pinio_box3
3478         field: permanentId[2]
3479         default_value: "target specific"
3480         description: "Mode assignment for PINIO#1"
3481         min: 0
3482         max: 255
3483         default_value: :BOX_PERMANENT_ID_NONE
3484         type: uint8_t
3485       - name: pinio_box4
3486         field: permanentId[3]
3487         default_value: "target specific"
3488         description: "Mode assignment for PINIO#1"
3489         min: 0
3490         max: 255
3491         default_value: :BOX_PERMANENT_ID_NONE
3492         type: uint8_t
3494   - name: PG_LOG_CONFIG
3495     type: logConfig_t
3496     headers: ["common/log.h"]
3497     condition: USE_LOG
3498     members:
3499         - name: log_level
3500           field: level
3501           table: log_level
3502           description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
3503           default_value: "ERROR"
3504         - name: log_topics
3505           field: topics
3506           min: 0
3507           max: UINT32_MAX
3508           description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
3509           default_value: 0
3511   - name: PG_ESC_SENSOR_CONFIG
3512     type: escSensorConfig_t
3513     headers: ["sensors/esc_sensor.h"]
3514     condition: USE_ESC_SENSOR
3515     members:
3516         - name: esc_sensor_listen_only
3517           default_value: OFF
3518           description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
3519           field: listenOnly
3520           type: bool
3521           default_value: OFF
3523   - name: PG_SMARTPORT_MASTER_CONFIG
3524     type: smartportMasterConfig_t
3525     headers: ["io/smartport_master.h"]
3526     condition: USE_SMARTPORT_MASTER
3527     members:
3528       - name: smartport_master_halfduplex
3529         field: halfDuplex
3530         type: bool
3531         default_value: ON
3532       - name: smartport_master_inverted
3533         field: inverted
3534         type: bool
3535         default_value: OFF
3537   - name: PG_DJI_OSD_CONFIG
3538     type: djiOsdConfig_t
3539     headers: ["io/osd_dji_hd.h"]
3540     condition: USE_DJI_HD_OSD
3541     members:
3542         - name: dji_workarounds
3543           description: "Enables workarounds for different versions of MSP protocol used"
3544           field: proto_workarounds
3545           min: 0
3546           max: UINT8_MAX
3547           default_value: 1
3548         - name: dji_use_name_for_messages
3549           description: "Re-purpose the craft name field for messages. Replace craft name with :WTSED for Warnings|Throttle|Speed|Efficiency|Trip distance"
3550           default_value: ON
3551           field: use_name_for_messages
3552           type: bool
3553         - name: dji_esc_temp_source
3554           description: "Re-purpose the ESC temperature field for IMU/BARO temperature"
3555           default_value: "ESC"
3556           field: esc_temperature_source
3557           table: djiOsdTempSource
3558           type: uint8_t
3559         - name: dji_speed_source
3560           description: "Sets the speed type displayed by the DJI OSD: GROUND, 3D, AIR"
3561           default_value: "GROUND"
3562           field: speedSource
3563           table: djiOsdSpeedSource
3564           type: uint8_t
3566   - name: PG_BEEPER_CONFIG
3567     type: beeperConfig_t
3568     headers: [ "fc/config.h" ]
3569     members:
3570       - name: dshot_beeper_enabled
3571         description: "Whether using DShot motors as beepers is enabled"
3572         default_value: ON
3573         field: dshot_beeper_enabled
3574         type: bool
3575       - name: dshot_beeper_tone
3576         description: "Sets the DShot beeper tone"
3577         min: 1
3578         max: 5
3579         default_value: 1
3580         field: dshot_beeper_tone
3581         type: uint8_t