3 values: ["DEFAULT", "CW0", "CW90", "CW180", "CW270", "CW0FLIP", "CW90FLIP", "CW180FLIP", "CW270FLIP"]
5 values: ["256HZ", "188HZ", "98HZ", "42HZ", "20HZ", "10HZ"]
7 values: ["NONE", "AUTO", "MPU6000", "MPU6500", "MPU9250", "BMI160", "ICM20689", "BMI088", "ICM42605", "BMI270", "FAKE"]
8 enum: accelerationSensor_e
9 - name: rangefinder_hardware
10 values: ["NONE", "SRF10", "VL53L0X", "MSP", "BENEWAKE", "VL53L1X", "US42", "TOF10120_I2C"]
11 enum: rangefinderType_e
13 values: ["NONE", "AUTO", "HMC5883", "AK8975", "MAG3110", "AK8963", "IST8310", "QMC5883", "MPU9250", "IST8308", "LIS3MDL", "MSP", "RM3100", "VCM5883", "MLX90393", "FAKE"]
15 - name: opflow_hardware
16 values: ["NONE", "CXOF", "MSP", "FAKE"]
17 enum: opticalFlowSensor_e
19 values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "DPS310", "B2SMPB", "MSP", "FAKE"]
21 - name: pitot_hardware
22 values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE", "MSP"]
25 values: ["NONE", "SERIAL", "MSP"]
26 enum: rxReceiverType_e
28 values: ["SPEK1024", "SPEK2048", "SBUS", "SUMD", "IBUS", "JETIEXBUS", "CRSF", "FPORT", "SBUS_FAST", "FPORT2", "SRXL2", "GHST", "MAVLINK"]
29 - name: blackbox_device
30 values: ["SERIAL", "SPIFLASH", "SDCARD"]
31 - name: motor_pwm_protocol
32 values: ["STANDARD", "ONESHOT125", "MULTISHOT", "BRUSHED", "DSHOT150", "DSHOT300", "DSHOT600"]
33 - name: servo_protocol
34 values: ["PWM", "SBUS", "SBUS_PWM"]
35 - name: failsafe_procedure
36 values: ["LAND", "DROP", "RTH", "NONE"]
37 - name: current_sensor
38 values: ["NONE", "ADC", "VIRTUAL", "ESC"]
40 - name: voltage_sensor
41 values: ["NONE", "ADC", "ESC"]
43 - name: imu_inertia_comp_method
44 values: ["VELNED", "TURNRATE","ADAPTIVE"]
45 enum: imu_inertia_comp_method_e
47 values: ["NMEA", "UBLOX", "UBLOX7", "MSP"]
50 values: ["AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"]
53 values: ["PEDESTRIAN", "AIR_1G", "AIR_4G"]
56 values: ["NEVER", "FIRST_ARM", "EACH_ARM"]
58 values: ["RIGHT", "LEFT", "YAW"]
59 - name: nav_user_control_mode
60 values: ["ATTI", "CRUISE"]
61 - name: nav_rth_alt_mode
62 values: ["CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST", "AT_LEAST_LINEAR_DESCENT"]
63 - name: nav_rth_climb_first_stage_modes
64 values: ["AT_LEAST", "EXTRA"]
66 values: ["IMPERIAL", "METRIC", "METRIC_MPH", "UK", "GA"]
68 - name: osd_stats_energy_unit
70 enum: osd_stats_energy_unit_e
71 - name: osd_stats_min_voltage_unit
72 values: ["BATTERY", "CELL"]
73 enum: osd_stats_min_voltage_unit_e
74 - name: osd_video_system
75 values: ["AUTO", "PAL", "NTSC", "HDZERO", "DJIWTF", "AVATAR", "BF43COMPAT"]
78 values: ["OFF", "ON","TEST"]
81 values: ["LEFT", "RIGHT"]
84 values: ["METRIC", "IMPERIAL"]
87 values: ["NORMAL", "MEDIUM", "SLOW"]
89 values: ["400KHZ", "800KHZ", "100KHZ", "200KHZ"]
91 values: ["NONE", "AGL", "FLOW_RAW", "FLOW", "ALWAYS", "SAG_COMP_VOLTAGE",
92 "VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC",
93 "NAV_YAW", "PCF8574", "DYN_GYRO_LPF", "AUTOLEVEL", "ALTITUDE",
94 "AUTOTRIM", "AUTOTUNE", "RATE_DYNAMICS", "LANDING", "POS_EST"]
97 enum: modeActivationOperator_e
98 - name: osd_crosshairs_style
99 values: ["DEFAULT", "AIRCRAFT", "TYPE3", "TYPE4", "TYPE5", "TYPE6", "TYPE7", "TYPE8"]
100 enum: osd_crosshairs_style_e
101 - name: osd_sidebar_scroll
102 values: ["NONE", "ALTITUDE", "SPEED", "HOME_DISTANCE"]
103 enum: osd_sidebar_scroll_e
104 - name: nav_rth_allow_landing
105 values: ["NEVER", "ALWAYS", "FS_ONLY"]
106 enum: navRTHAllowLanding_e
107 - name: bat_capacity_unit
108 values: ["MAH", "MWH"]
109 enum: batCapacityUnit_e
110 - name: bat_voltage_source
111 values: ["RAW", "SAG_COMP"]
112 enum: batVoltageSource_e
113 - name: smartport_fuel_unit
114 values: ["PERCENT", "MAH", "MWH"]
115 enum: smartportFuelUnit_e
116 - name: platform_type
117 values: ["MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT"]
119 values: ["AUTO", "MOTORS", "SERVOS"]
121 - name: tz_automatic_dst
122 values: ["OFF", "EU", "USA"]
123 enum: tz_automatic_dst_e
124 - name: vtx_low_power_disarm
125 values: ["OFF", "ON", "UNTIL_FIRST_ARM"]
126 enum: vtxLowerPowerDisarm_e
127 - name: vtx_frequency_groups
128 values: ["FREQUENCYGROUP_5G8", "FREQUENCYGROUP_2G4", "FREQUENCYGROUP_1G3"]
129 enum: vtxFrequencyGroups_e
131 values: ["PT1", "BIQUAD"]
132 - name: filter_type_full
133 values: ["PT1", "BIQUAD", "PT2", "PT3"]
135 values: ["ERROR", "WARNING", "INFO", "VERBOSE", "DEBUG"]
137 values: ["OFF", "RP", "RPY"]
139 - name: airmodeHandlingType
140 values: ["STICK_CENTER", "THROTTLE_THRESHOLD", "STICK_CENTER_ONCE"]
141 - name: nav_extra_arming_safety
142 values: ["ON", "ALLOW_BYPASS"]
143 enum: navExtraArmingSafety_e
145 values: ["NONE", "AUTO", "ADC", "CHANNEL", "PROTOCOL", "MSP"]
148 values: ["NONE", "PID", "PIFF", "AUTO"]
150 - name: osd_ahi_style
151 values: ["DEFAULT", "LINE"]
152 enum: osd_ahi_style_e
155 values: ["AUTO", "ON", "OFF"]
156 - name: osd_crsf_lq_format
157 enum: osd_crsf_lq_format_e
158 values: ["TYPE1", "TYPE2", "TYPE3"]
160 values: ["OFF", "ON"]
161 - name: djiOsdTempSource
162 values: ["ESC", "IMU", "BARO"]
163 enum: djiOsdTempSource_e
164 - name: osdSpeedSource
165 values: ["GROUND", "3D", "AIR"]
166 enum: osdSpeedSource_e
167 - name: nav_overrides_motor_stop
168 enum: navOverridesMotorStop_e
169 values: ["OFF_ALWAYS", "OFF", "AUTO_ONLY", "ALL_NAV"]
170 - name: osd_plus_code_short
171 values: ["0", "2", "4", "6"]
172 - name: autotune_rate_adjustment
173 enum: autotune_rate_adjustment_e
174 values: ["FIXED", "LIMIT", "AUTO"]
175 - name: safehome_usage_mode
176 values: ["OFF", "RTH", "RTH_FS"]
177 enum: safehomeUsageMode_e
178 - name: nav_rth_climb_first
179 enum: navRTHClimbFirst_e
180 values: ["OFF", "ON", "ON_FW_SPIRAL"]
181 - name: nav_wp_mission_restart
182 enum: navMissionRestart_e
183 values: ["START", "RESUME", "SWITCH"]
184 - name: djiRssiSource
185 values: ["RSSI", "CRSF_LQ"]
186 enum: djiRssiSource_e
187 - name: rth_trackback_mode
188 values: ["OFF", "ON", "FS"]
189 enum: rthTrackbackMode_e
190 - name: dynamic_gyro_notch_mode
191 values: ["2D", "3D_R", "3D_P", "3D_Y", "3D_RP", "3D_RY", "3D_PY", "3D"]
192 enum: dynamicGyroNotchMode_e
193 - name: nav_fw_wp_turn_smoothing
194 values: ["OFF", "ON", "ON-CUT"]
195 enum: wpFwTurnSmoothing_e
204 ROLL_PITCH_RATE_MIN: 4
205 ROLL_PITCH_RATE_MAX: 180
207 MAX_CONTROL_RATE_PROFILE_COUNT: 3
208 MAX_BATTERY_PROFILE_COUNT: 3
212 - name: PG_GYRO_CONFIG
214 headers: ["sensors/gyro.h"]
217 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."
220 - name: gyro_hardware_lpf
221 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."
222 default_value: "256HZ"
225 - name: gyro_anti_aliasing_lpf_hz
226 description: "Gyro processing anti-aliasing filter cutoff frequency. In normal operation this filter setting should never be changed. In Hz"
228 field: gyro_anti_aliasing_lpf_hz
230 - name: gyro_anti_aliasing_lpf_type
231 description: "Specifies the type of the software LPF of the gyro signals."
233 field: gyro_anti_aliasing_lpf_type
235 - name: moron_threshold
236 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."
238 field: gyroMovementCalibrationThreshold
240 - name: gyro_main_lpf_hz
241 description: "Software based gyro main lowpass filter. Value is cutoff frequency (Hz)"
243 field: gyro_main_lpf_hz
246 - name: gyro_main_lpf_type
247 description: "Defines the type of the main gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation."
248 default_value: BIQUAD
249 field: gyro_main_lpf_type
251 - name: gyro_use_dyn_lpf
252 description: "Use Dynamic LPF instead of static gyro stage1 LPF. Dynamic Gyro LPF updates gyro LPF based on the throttle position."
256 - name: gyro_dyn_lpf_min_hz
257 description: "Minimum frequency of the gyro Dynamic LPF"
259 field: gyroDynamicLpfMinHz
262 - name: gyro_dyn_lpf_max_hz
263 description: "Maximum frequency of the gyro Dynamic LPF"
265 field: gyroDynamicLpfMaxHz
268 - name: gyro_dyn_lpf_curve_expo
269 description: "Expo value for the throttle-to-frequency mapping for Dynamic LPF"
271 field: gyroDynamicLpfCurveExpo
274 - name: dynamic_gyro_notch_enabled
275 description: "Enable/disable dynamic gyro notch also known as Matrix Filter"
277 field: dynamicGyroNotchEnabled
278 condition: USE_DYNAMIC_FILTERS
280 - name: dynamic_gyro_notch_q
281 description: "Q factor for dynamic notches"
283 field: dynamicGyroNotchQ
284 condition: USE_DYNAMIC_FILTERS
287 - name: dynamic_gyro_notch_min_hz
288 description: "Minimum frequency for dynamic notches. Default value of `150` works best with 5\" multirotors. Should be lowered with increased size of propellers. Values around `100` work fine on 7\" drones. 10\" can go down to `60` - `70`"
290 field: dynamicGyroNotchMinHz
291 condition: USE_DYNAMIC_FILTERS
294 - name: dynamic_gyro_notch_mode
295 description: "Gyro dynamic notch type"
297 table: dynamic_gyro_notch_mode
298 field: dynamicGyroNotchMode
299 condition: USE_DYNAMIC_FILTERS
300 - name: dynamic_gyro_notch_3d_q
301 description: "Q factor for 3D dynamic notches"
303 field: dynamicGyroNotch3dQ
304 condition: USE_DYNAMIC_FILTERS
308 condition: USE_DUAL_GYRO
312 - name: setpoint_kalman_enabled
313 description: "Enable Kalman filter on the gyro data"
315 condition: USE_GYRO_KALMAN
318 - name: setpoint_kalman_q
319 description: "Quality factor of the setpoint Kalman filter. Higher values means less filtering and lower phase delay. On 3-7 inch multirotors can be usually increased to 200-300 or even higher of clean builds"
322 condition: USE_GYRO_KALMAN
325 - name: init_gyro_cal
326 description: "If defined to 'OFF', it will ignore the gyroscope calibration done at each startup. Instead, the gyroscope last calibration from when you calibrated will be used. It also means you don't have to keep the UAV stationary during a startup."
328 field: init_gyro_cal_enabled
331 description: "Calculated gyro zero calibration of axis X"
333 field: gyro_zero_cal[X]
337 description: "Calculated gyro zero calibration of axis Y"
339 field: gyro_zero_cal[Y]
343 description: "Calculated gyro zero calibration of axis Z"
345 field: gyro_zero_cal[Z]
348 - name: ins_gravity_cmss
349 description: "Calculated 1G of Acc axis Z to use in INS"
351 field: gravity_cmss_cal
355 - name: PG_ADC_CHANNEL_CONFIG
356 type: adcChannelConfig_t
357 headers: ["fc/config.h"]
360 - name: vbat_adc_channel
361 description: "ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled"
362 default_value: :target
363 field: adcFunctionChannel[ADC_BATTERY]
366 - name: rssi_adc_channel
367 description: "ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled"
368 default_value: :target
369 field: adcFunctionChannel[ADC_RSSI]
372 - name: current_adc_channel
373 description: "ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled"
374 default_value: :target
375 field: adcFunctionChannel[ADC_CURRENT]
378 - name: airspeed_adc_channel
379 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"
380 default_value: :target
381 field: adcFunctionChannel[ADC_AIRSPEED]
385 - name: PG_ACCELEROMETER_CONFIG
386 type: accelerometerConfig_t
387 headers: ["sensors/acceleration.h"]
393 - name: acc_notch_cutoff
398 description: "Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
399 default_value: "AUTO"
402 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."
407 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."
408 default_value: "BIQUAD"
409 field: acc_soft_lpf_type
412 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
414 field: accZero.raw[X]
418 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
420 field: accZero.raw[Y]
424 description: "Calculated value after '6 position avanced calibration'. See Wiki page."
426 field: accZero.raw[Z]
430 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
432 field: accGain.raw[X]
436 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
438 field: accGain.raw[Y]
442 description: "Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page."
444 field: accGain.raw[Z]
448 - name: PG_RANGEFINDER_CONFIG
449 type: rangefinderConfig_t
450 headers: ["sensors/rangefinder.h"]
451 condition: USE_RANGEFINDER
453 - name: rangefinder_hardware
454 table: rangefinder_hardware
455 description: "Selection of rangefinder hardware."
456 default_value: "NONE"
457 - name: rangefinder_median_filter
458 description: "3-point median filtering for rangefinder readouts"
460 field: use_median_filtering
463 - name: PG_OPFLOW_CONFIG
464 type: opticalFlowConfig_t
465 headers: ["sensors/opflow.h"]
466 condition: USE_OPFLOW
468 - name: opflow_hardware
469 description: "Selection of OPFLOW hardware."
471 table: opflow_hardware
477 description: "Optical flow module alignment (default CW0_DEG_FLIP)"
478 default_value: CW0FLIP
483 - name: PG_COMPASS_CONFIG
484 type: compassConfig_t
485 headers: ["sensors/compass.h"]
489 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."
490 default_value: "DEFAULT"
495 description: "Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
496 default_value: "AUTO"
498 - name: mag_declination
499 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."
504 description: "Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed."
506 field: magZero.raw[X]
510 description: "Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed."
512 field: magZero.raw[Y]
516 description: "Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed."
518 field: magZero.raw[Z]
522 description: "Magnetometer calibration X gain. If 1024, no calibration or calibration failed"
528 description: "Magnetometer calibration Y gain. If 1024, no calibration or calibration failed"
534 description: "Magnetometer calibration Z gain. If 1024, no calibration or calibration failed"
539 - name: mag_calibration_time
540 description: "Adjust how long time the Calibration of mag will last."
542 field: magCalibrationTimeLimit
546 description: "Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target"
547 condition: USE_DUAL_MAG
551 - name: align_mag_roll
552 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."
554 field: rollDeciDegrees
557 - name: align_mag_pitch
558 description: "Same as align_mag_roll, but for the pitch axis."
560 field: pitchDeciDegrees
563 - name: align_mag_yaw
564 description: "Same as align_mag_roll, but for the yaw axis."
566 field: yawDeciDegrees
570 - name: PG_BAROMETER_CONFIG
571 type: barometerConfig_t
572 headers: ["sensors/barometer.h"]
575 - name: baro_hardware
576 description: "Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info"
577 default_value: "AUTO"
579 - name: baro_cal_tolerance
580 description: "Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]."
582 field: baro_calibration_tolerance
586 - name: PG_PITOTMETER_CONFIG
587 type: pitotmeterConfig_t
588 headers: ["sensors/pitotmeter.h"]
591 - name: pitot_hardware
592 description: "Selection of pitot hardware."
593 default_value: "NONE"
594 table: pitot_hardware
595 - name: pitot_lpf_milli_hz
606 headers: ["rx/rx.h", "rx/spektrum.h"]
608 - name: receiver_type
609 description: "Selection of receiver (RX) type. Additional configuration of a `serialrx_provider` and a UART will be needed for `SERIAL`"
610 default_value: :target
614 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."
620 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."
626 description: "Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP`"
627 default_value: "AUTO"
631 description: "RX channel containing the RSSI signal"
634 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
636 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)."
639 min: RSSI_VISIBLE_VALUE_MIN
640 max: RSSI_VISIBLE_VALUE_MAX
642 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."
645 min: RSSI_VISIBLE_VALUE_MIN
646 max: RSSI_VISIBLE_VALUE_MAX
647 - name: sbus_sync_interval
648 field: sbusSyncInterval
652 - name: rc_filter_lpf_hz
653 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"
655 field: rcFilterFrequency
658 - name: rc_filter_auto
659 description: "When enabled, INAV will set RC filtering based on refresh rate and smoothing factor."
663 - name: rc_filter_smoothing_factor
664 description: "The RC filter smoothing factor. The higher the value, the more smoothing but also the more delay in response. Value 1 sets the filter at half the refresh rate. Value 100 sets the filter to aprox. 10% of the RC refresh rate"
665 field: autoSmoothFactor
669 - name: serialrx_provider
670 description: "When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section."
671 default_value: :target
672 condition: USE_SERIAL_RX
674 - name: serialrx_inverted
675 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)."
677 condition: USE_SERIAL_RX
679 - name: spektrum_sat_bind
680 description: "0 = disabled. Used to bind the spektrum satellite to RX"
681 condition: USE_SPEKTRUM_BIND
682 min: SPEKTRUM_SAT_BIND_DISABLED
683 max: SPEKTRUM_SAT_BIND_MAX
684 default_value: :SPEKTRUM_SAT_BIND_DISABLED
685 - name: srxl2_unit_id
686 condition: USE_SERIALRX_SRXL2
690 - name: srxl2_baud_fast
691 condition: USE_SERIALRX_SRXL2
695 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."
700 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."
704 - name: serialrx_halfduplex
705 description: "Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire."
706 default_value: "AUTO"
709 - name: msp_override_channels
710 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."
712 field: mspOverrideChannels
713 condition: USE_MSP_RC_OVERRIDE
717 - name: PG_BLACKBOX_CONFIG
718 type: blackboxConfig_t
719 headers: ["blackbox/blackbox.h"]
720 condition: USE_BLACKBOX
722 - name: blackbox_rate_num
723 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"
728 - name: blackbox_rate_denom
729 description: "Blackbox logging rate denominator. See blackbox_rate_num."
734 - name: blackbox_device
735 description: "Selection of where to write blackbox data"
736 default_value: :target
738 table: blackbox_device
739 - name: sdcard_detect_inverted
740 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."
741 default_value: :target
742 field: invertedCardDetection
743 condition: USE_SDCARD
746 - name: PG_MOTOR_CONFIG
748 headers: ["flight/mixer.h"]
751 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."
757 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."
762 - name: motor_pwm_rate
763 description: "Output frequency (in Hz) for motor pins. Applies only to brushed motors. "
768 - name: motor_pwm_protocol
769 description: "Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED"
770 default_value: "ONESHOT125"
771 field: motorPwmProtocol
772 table: motor_pwm_protocol
774 field: motorPoleCount
775 description: "The number of motor poles. Required to compute motor RPM"
780 - name: PG_FAILSAFE_CONFIG
781 type: failsafeConfig_t
782 headers: ["flight/failsafe.h"]
784 - name: failsafe_delay
785 description: "Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay)."
789 - name: failsafe_recovery_delay
790 description: "Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay)."
794 - name: failsafe_off_delay
795 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)."
799 - name: failsafe_throttle_low_delay
800 description: "If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout"
804 - name: failsafe_procedure
805 description: "What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
806 default_value: "LAND"
807 table: failsafe_procedure
808 - name: failsafe_stick_threshold
809 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."
811 field: failsafe_stick_motion_threshold
814 - name: failsafe_fw_roll_angle
815 description: "Amount of banking when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll"
819 - name: failsafe_fw_pitch_angle
820 description: "Amount of dive/climb when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb"
824 - name: failsafe_fw_yaw_rate
825 description: "Requested yaw rate to execute when `LAND` (or old `SET-THR`) failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn"
829 - name: failsafe_min_distance
830 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."
834 - name: failsafe_min_distance_procedure
835 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)."
836 default_value: "DROP"
837 table: failsafe_procedure
838 - name: failsafe_mission_delay
839 description: "Applies if failsafe occurs when a WP mission is in progress. Sets the time delay in seconds between failsafe occurring and the selected failsafe procedure activating. If set to -1 the failsafe procedure won't activate at all and the mission will continue until the end."
844 - name: PG_LIGHTS_CONFIG
846 headers: ["io/lights.h"]
847 condition: USE_LIGHTS
849 - name: failsafe_lights
850 description: "Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]."
852 field: failsafe.enabled
854 - name: failsafe_lights_flash_period
855 description: "Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]."
857 field: failsafe.flash_period
860 - name: failsafe_lights_flash_on_time
861 description: "Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]."
863 field: failsafe.flash_on_time
867 - name: PG_BOARD_ALIGNMENT
868 type: boardAlignment_t
869 headers: ["sensors/boardalignment.h"]
871 - name: align_board_roll
872 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
874 field: rollDeciDegrees
877 - name: align_board_pitch
878 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
880 field: pitchDeciDegrees
883 - name: align_board_yaw
884 description: "Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc"
886 field: yawDeciDegrees
890 - name: PG_BATTERY_METERS_CONFIG
891 type: batteryMetersConfig_t
892 headers: ["sensors/battery_config_structs.h"]
894 - name: vbat_meter_type
895 description: "Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running"
899 table: voltage_sensor
902 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."
903 default_value: :target
908 - name: current_meter_scale
909 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."
910 default_value: :target
914 - name: current_meter_offset
915 description: "This sets the output offset voltage of the current sensor in millivolts."
916 default_value: :target
917 field: current.offset
920 - name: current_meter_type
921 description: "ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position."
924 table: current_sensor
926 - name: bat_voltage_src
927 description: "Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP`"
930 table: bat_voltage_source
933 description: "Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit"
939 description: "Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit"
944 - name: rth_energy_margin
945 description: "Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation"
949 - name: thr_comp_weight
950 description: "Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage)"
952 field: throttle_compensation_weight
956 - name: PG_BATTERY_PROFILES
957 type: batteryProfile_t
958 headers: ["sensors/battery_config_structs.h"]
959 value_type: BATTERY_CONFIG_VALUE
962 description: "Number of cells of the battery (0 = auto-detect), see battery documentation. 7S, 9S and 11S batteries cannot be auto-detected."
968 - name: vbat_cell_detect_voltage
969 description: "Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units."
971 field: voltage.cellDetect
975 - name: vbat_max_cell_voltage
976 description: "Maximum voltage per cell in 0.01V units, default is 4.20V"
978 field: voltage.cellMax
982 - name: vbat_min_cell_voltage
983 description: "Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V)"
985 field: voltage.cellMin
989 - name: vbat_warning_cell_voltage
990 description: "Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V)"
992 field: voltage.cellWarning
996 - name: battery_capacity
997 description: "Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity."
999 field: capacity.value
1002 - name: battery_capacity_warning
1003 description: "If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink."
1005 field: capacity.warning
1008 - name: battery_capacity_critical
1009 description: "If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps."
1011 field: capacity.critical
1014 - name: battery_capacity_unit
1015 description: "Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour)."
1016 default_value: "MAH"
1017 field: capacity.unit
1018 table: bat_capacity_unit
1020 - name: controlrate_profile
1021 description: "Control rate profile to switch to when the battery profile is selected, 0 to disable and keep the currently selected control rate profile"
1023 field: controlRateProfile
1025 max: MAX_CONTROL_RATE_PROFILE_COUNT
1027 - name: throttle_scale
1028 description: "Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50%"
1030 field: motor.throttleScale
1033 - name: throttle_idle
1034 description: "The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle."
1036 field: motor.throttleIdle
1039 - name: turtle_mode_power_factor
1040 field: motor.turtleModePowerFactor
1042 description: "Turtle mode power factor"
1043 condition: USE_DSHOT
1046 - name: failsafe_throttle
1047 description: "Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle)."
1051 - name: nav_mc_hover_thr
1052 description: "Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering."
1054 field: nav.mc.hover_throttle
1057 - name: nav_fw_cruise_thr
1058 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 )"
1060 field: nav.fw.cruise_throttle
1063 - name: nav_fw_min_thr
1064 description: "Minimum throttle for flying wing in GPS assisted modes"
1066 field: nav.fw.min_throttle
1069 - name: nav_fw_max_thr
1070 description: "Maximum throttle for flying wing in GPS assisted modes"
1072 field: nav.fw.max_throttle
1075 - name: nav_fw_pitch2thr
1076 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)"
1078 field: nav.fw.pitch_to_throttle
1081 - name: nav_fw_launch_thr
1082 description: "Launch throttle - throttle to be set during launch sequence (pwm units)"
1084 field: nav.fw.launch_throttle
1087 - name: nav_fw_launch_idle_thr
1088 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)"
1090 field: nav.fw.launch_idle_throttle
1093 - name: limit_cont_current
1094 description: "Continous current limit (dA), set to 0 to disable"
1095 condition: USE_POWER_LIMITS
1097 field: powerLimits.continuousCurrent
1099 - name: limit_burst_current
1100 description: "Burst current limit (dA): the current which is allowed during `limit_burst_current_time` after which `limit_cont_current` will be enforced, set to 0 to disable"
1101 condition: USE_POWER_LIMITS
1103 field: powerLimits.burstCurrent
1105 - name: limit_burst_current_time
1106 description: "Allowed current burst time (ds) during which `limit_burst_current` is allowed and after which `limit_cont_current` will be enforced"
1107 condition: USE_POWER_LIMITS
1109 field: powerLimits.burstCurrentTime
1111 - name: limit_burst_current_falldown_time
1112 description: "Time slice at the end of the burst time during which the current limit will be ramped down from `limit_burst_current` back down to `limit_cont_current`"
1113 condition: USE_POWER_LIMITS
1115 field: powerLimits.burstCurrentFalldownTime
1117 - name: limit_cont_power
1118 description: "Continous power limit (dW), set to 0 to disable"
1119 condition: USE_POWER_LIMITS && USE_ADC
1121 field: powerLimits.continuousPower
1123 - name: limit_burst_power
1124 description: "Burst power limit (dW): the current which is allowed during `limit_burst_power_time` after which `limit_cont_power` will be enforced, set to 0 to disable"
1125 condition: USE_POWER_LIMITS && USE_ADC
1127 field: powerLimits.burstPower
1129 - name: limit_burst_power_time
1130 description: "Allowed power burst time (ds) during which `limit_burst_power` is allowed and after which `limit_cont_power` will be enforced"
1131 condition: USE_POWER_LIMITS && USE_ADC
1133 field: powerLimits.burstPowerTime
1135 - name: limit_burst_power_falldown_time
1136 description: "Time slice at the end of the burst time during which the power limit will be ramped down from `limit_burst_power` back down to `limit_cont_power`"
1137 condition: USE_POWER_LIMITS && USE_ADC
1139 field: powerLimits.burstPowerFalldownTime
1142 - name: PG_MIXER_CONFIG
1145 - name: motor_direction_inverted
1146 description: "Use if you need to inverse yaw motor direction."
1148 field: motorDirectionInverted
1150 - name: platform_type
1151 description: "Defines UAV platform type. Allowed values: \"MULTIROTOR\", \"AIRPLANE\", \"HELICOPTER\", \"TRICOPTER\", \"ROVER\", \"BOAT\". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented"
1152 default_value: "MULTIROTOR"
1155 table: platform_type
1157 description: "Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot"
1161 - name: model_preview_type
1162 description: "ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons."
1164 field: appliedMixerPreset
1168 description: "Output function assignment mode. AUTO assigns outputs according to the default mapping, SERVOS assigns all outputs to servos, MOTORS assigns all outputs to motors"
1169 default_value: "AUTO"
1173 - name: PG_REVERSIBLE_MOTORS_CONFIG
1174 type: reversibleMotorsConfig_t
1176 - name: 3d_deadband_low
1177 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)"
1182 - name: 3d_deadband_high
1183 description: "High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead)"
1185 field: deadband_high
1189 description: "Neutral (stop) throttle value for 3D mode"
1195 - name: PG_SERVO_CONFIG
1197 headers: ["flight/servos.h"]
1199 - name: servo_protocol
1200 description: "An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SBUS` (S.Bus protocol output via a configured serial port)"
1201 default_value: "PWM"
1202 field: servo_protocol
1203 table: servo_protocol
1204 - name: servo_center_pulse
1205 description: "Servo midpoint"
1207 field: servoCenterPulse
1210 - name: servo_pwm_rate
1211 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."
1216 - name: servo_lpf_hz
1217 description: "Selects the servo PWM output cutoff frequency. Value is in [Hz]"
1219 field: servo_lowpass_freq
1222 - name: flaperon_throw_offset
1223 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."
1225 min: FLAPERON_THROW_MIN
1226 max: FLAPERON_THROW_MAX
1227 - name: tri_unarmed_servo
1228 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."
1231 - name: servo_autotrim_rotation_limit
1232 description: "Servo midpoints are only updated when total aircraft rotation is less than this threshold [deg/s]. Only applies when using `feature FW_AUTOTRIM`."
1237 - name: PG_CONTROL_RATE_PROFILES
1238 type: controlRateConfig_t
1239 headers: ["fc/controlrate_profile_config_struct.h"]
1240 value_type: CONTROL_RATE_VALUE
1243 description: "Throttle value when the stick is set to mid-position. Used in the throttle curve calculation."
1245 field: throttle.rcMid8
1249 description: "Throttle exposition value"
1251 field: throttle.rcExpo8
1255 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."
1257 field: throttle.dynPID
1260 - name: tpa_breakpoint
1261 description: "See tpa_rate."
1263 field: throttle.pa_breakpoint
1266 - name: fw_tpa_time_constant
1267 description: "TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. See **PID Attenuation and scaling** Wiki for full details."
1269 field: throttle.fixedWingTauMs
1273 description: "Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`)"
1275 field: stabilized.rcExpo8
1279 description: "Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`)"
1281 field: stabilized.rcYawExpo8
1284 # New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
1285 # Rate 180 (1800dps) is max. value gyro can measure reliably
1287 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."
1289 field: stabilized.rates[FD_ROLL]
1290 min: ROLL_PITCH_RATE_MIN
1291 max: ROLL_PITCH_RATE_MAX
1293 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."
1295 field: stabilized.rates[FD_PITCH]
1296 min: ROLL_PITCH_RATE_MIN
1297 max: ROLL_PITCH_RATE_MAX
1299 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."
1301 field: stabilized.rates[FD_YAW]
1304 - name: manual_rc_expo
1305 description: "Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100]"
1307 field: manual.rcExpo8
1310 - name: manual_rc_yaw_expo
1311 description: "Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100]"
1313 field: manual.rcYawExpo8
1316 - name: manual_roll_rate
1317 description: "Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]%"
1319 field: manual.rates[FD_ROLL]
1320 min: MANUAL_RATE_MIN
1321 max: MANUAL_RATE_MAX
1322 - name: manual_pitch_rate
1323 description: "Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]%"
1325 field: manual.rates[FD_PITCH]
1326 min: MANUAL_RATE_MIN
1327 max: MANUAL_RATE_MAX
1328 - name: manual_yaw_rate
1329 description: "Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]%"
1331 field: manual.rates[FD_YAW]
1332 min: MANUAL_RATE_MIN
1333 max: MANUAL_RATE_MAX
1334 - name: fpv_mix_degrees
1335 field: misc.fpvCamAngleDegrees
1339 - name: rate_dynamics_center_sensitivity
1340 field: rateDynamics.sensitivityCenter
1344 description: "The center stick sensitivity for Rate Dynamics"
1345 condition: USE_RATE_DYNAMICS
1346 - name: rate_dynamics_end_sensitivity
1347 field: rateDynamics.sensitivityEnd
1351 description: "The end stick sensitivity for Rate Dynamics"
1352 condition: USE_RATE_DYNAMICS
1353 - name: rate_dynamics_center_correction
1354 field: rateDynamics.correctionCenter
1358 description: "The center stick correction for Rate Dynamics"
1359 condition: USE_RATE_DYNAMICS
1360 - name: rate_dynamics_end_correction
1361 field: rateDynamics.correctionEnd
1365 description: "The end stick correction for Rate Dynamics"
1366 condition: USE_RATE_DYNAMICS
1367 - name: rate_dynamics_center_weight
1368 field: rateDynamics.weightCenter
1372 description: "The center stick weight for Rate Dynamics"
1373 condition: USE_RATE_DYNAMICS
1374 - name: rate_dynamics_end_weight
1375 field: rateDynamics.weightEnd
1379 description: "The end stick weight for Rate Dynamics"
1380 condition: USE_RATE_DYNAMICS
1382 - name: PG_SERIAL_CONFIG
1383 type: serialConfig_t
1384 headers: ["io/serial.h"]
1386 - name: reboot_character
1387 description: "Special character used to trigger reboot"
1392 - name: PG_IMU_CONFIG
1394 headers: ["flight/imu.h"]
1397 description: "Inertial Measurement Unit KP Gain for accelerometer measurements"
1402 description: "Inertial Measurement Unit KI Gain for accelerometer measurements"
1406 - name: imu_dcm_kp_mag
1407 description: "Inertial Measurement Unit KP Gain for compass measurements"
1411 - name: imu_dcm_ki_mag
1412 description: "Inertial Measurement Unit KI Gain for compass measurements"
1417 description: "If the aircraft tilt angle exceed this value the copter will refuse to arm."
1421 - name: imu_acc_ignore_rate
1422 description: "Total gyro rotation rate threshold [deg/s] before scaling to consider accelerometer trustworthy"
1424 field: acc_ignore_rate
1427 - name: imu_acc_ignore_slope
1428 description: "Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight)"
1430 field: acc_ignore_slope
1433 - name: imu_gps_yaw_windcomp
1434 description: "Wind compensation in heading estimation from gps groundcourse(fixed wing only)"
1436 field: gps_yaw_windcomp
1438 - name: imu_inertia_comp_method
1439 description: "Inertia force compensation method when gps is avaliable, VELNED use the accleration from gps, TURNRATE calculates accleration by turnrate multiplied by speed, ADAPTIVE choose best result from two in each ahrs loop"
1440 default_value: VELNED
1441 field: inertia_comp_method
1442 table: imu_inertia_comp_method
1444 - name: PG_ARMING_CONFIG
1445 type: armingConfig_t
1447 - name: fixed_wing_auto_arm
1448 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."
1451 - name: disarm_kill_switch
1452 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."
1455 - name: switch_disarm_delay
1456 description: "Delay before disarming when requested by switch (ms) [0-1000]"
1458 field: switchDisarmDelayMs
1461 - name: prearm_timeout
1462 description: "Duration (ms) for which Prearm being activated is valid. after this, Prearm needs to be reset. 0 means Prearm does not timeout."
1463 default_value: 10000
1464 field: prearmTimeoutMs
1468 - name: PG_GENERAL_SETTINGS
1469 headers: ["config/general_settings.h"]
1470 type: generalSettings_t
1472 - name: applied_defaults
1473 description: "Internal (configurator) hint. Should not be changed manually"
1475 field: appliedDefaults
1480 - name: PG_RPM_FILTER_CONFIG
1481 headers: ["flight/rpm_filter.h"]
1482 condition: USE_RPM_FILTER
1483 type: rpmFilterConfig_t
1485 - name: rpm_gyro_filter_enabled
1486 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"
1488 field: gyro_filter_enabled
1490 - name: rpm_gyro_harmonics
1491 description: "Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine"
1493 field: gyro_harmonics
1497 - name: rpm_gyro_min_hz
1498 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`"
1505 description: "Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting"
1511 - name: PG_GPS_CONFIG
1515 - name: gps_provider
1516 description: "Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N)."
1517 default_value: "UBLOX"
1521 - name: gps_sbas_mode
1522 description: "Which SBAS mode to be used"
1523 default_value: "NONE"
1525 table: gps_sbas_mode
1527 - name: gps_dyn_model
1528 description: "GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying."
1529 default_value: "AIR_1G"
1531 table: gps_dyn_model
1533 - name: gps_auto_config
1534 description: "Enable automatic configuration of UBlox GPS receivers."
1538 - name: gps_auto_baud
1539 description: "Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS"
1543 - name: gps_ublox_use_galileo
1544 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]."
1546 field: ubloxUseGalileo
1548 - name: gps_min_sats
1549 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."
1555 - name: PG_RC_CONTROLS_CONFIG
1556 type: rcControlsConfig_t
1557 headers: ["fc/rc_controls.h"]
1560 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."
1564 - name: yaw_deadband
1565 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."
1569 - name: pos_hold_deadband
1570 description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used for adjustments in navigation modes."
1574 - name: control_deadband
1575 description: "Stick deadband in [r/c points], applied after r/c deadband and expo. Used to check if sticks are centered."
1579 - name: alt_hold_deadband
1580 description: "Defines the deadband of throttle during alt_hold [r/c points]"
1584 - name: 3d_deadband_throttle
1585 description: "Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter."
1587 field: mid_throttle_deadband
1590 - name: airmode_type
1591 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."
1592 default_value: "STICK_CENTER"
1593 field: airmodeHandlingType
1594 table: airmodeHandlingType
1595 - name: airmode_throttle_threshold
1596 description: "Defines airmode THROTTLE activation threshold when `airmode_type` **THROTTLE_THRESHOLD** is used"
1598 field: airmodeThrottleThreshold
1602 - name: PG_PID_PROFILE
1604 headers: ["flight/pid.h"]
1605 value_type: PROFILE_VALUE
1608 description: "Multicopter rate stabilisation P-gain for PITCH"
1610 field: bank_mc.pid[PID_PITCH].P
1614 description: "Multicopter rate stabilisation I-gain for PITCH"
1616 field: bank_mc.pid[PID_PITCH].I
1620 description: "Multicopter rate stabilisation D-gain for PITCH"
1622 field: bank_mc.pid[PID_PITCH].D
1626 description: "Multicopter Control Derivative gain for PITCH"
1628 field: bank_mc.pid[PID_PITCH].FF
1632 description: "Multicopter rate stabilisation P-gain for ROLL"
1634 field: bank_mc.pid[PID_ROLL].P
1638 description: "Multicopter rate stabilisation I-gain for ROLL"
1640 field: bank_mc.pid[PID_ROLL].I
1644 description: "Multicopter rate stabilisation D-gain for ROLL"
1646 field: bank_mc.pid[PID_ROLL].D
1650 description: "Multicopter Control Derivative gain for ROLL"
1652 field: bank_mc.pid[PID_ROLL].FF
1656 description: "Multicopter rate stabilisation P-gain for YAW"
1658 field: bank_mc.pid[PID_YAW].P
1662 description: "Multicopter rate stabilisation I-gain for YAW"
1664 field: bank_mc.pid[PID_YAW].I
1668 description: "Multicopter rate stabilisation D-gain for YAW"
1670 field: bank_mc.pid[PID_YAW].D
1674 description: "Multicopter Control Derivative gain for YAW"
1676 field: bank_mc.pid[PID_YAW].FF
1680 description: "Multicopter attitude stabilisation P-gain"
1682 field: bank_mc.pid[PID_LEVEL].P
1686 description: "Multicopter attitude stabilisation low-pass filter cutoff"
1688 field: bank_mc.pid[PID_LEVEL].I
1692 description: "Multicopter attitude stabilisation HORIZON transition point"
1694 field: bank_mc.pid[PID_LEVEL].D
1698 description: "Fixed-wing rate stabilisation P-gain for PITCH"
1700 field: bank_fw.pid[PID_PITCH].P
1704 description: "Fixed-wing rate stabilisation I-gain for PITCH"
1706 field: bank_fw.pid[PID_PITCH].I
1710 description: "Fixed wing rate stabilisation D-gain for PITCH"
1712 field: bank_fw.pid[PID_PITCH].D
1716 description: "Fixed-wing rate stabilisation FF-gain for PITCH"
1718 field: bank_fw.pid[PID_PITCH].FF
1722 description: "Fixed-wing rate stabilisation P-gain for ROLL"
1724 field: bank_fw.pid[PID_ROLL].P
1728 description: "Fixed-wing rate stabilisation I-gain for ROLL"
1730 field: bank_fw.pid[PID_ROLL].I
1734 description: "Fixed wing rate stabilisation D-gain for ROLL"
1736 field: bank_fw.pid[PID_ROLL].D
1740 description: "Fixed-wing rate stabilisation FF-gain for ROLL"
1742 field: bank_fw.pid[PID_ROLL].FF
1746 description: "Fixed-wing rate stabilisation P-gain for YAW"
1748 field: bank_fw.pid[PID_YAW].P
1752 description: "Fixed-wing rate stabilisation I-gain for YAW"
1754 field: bank_fw.pid[PID_YAW].I
1758 description: "Fixed wing rate stabilisation D-gain for YAW"
1760 field: bank_fw.pid[PID_YAW].D
1764 description: "Fixed-wing rate stabilisation FF-gain for YAW"
1766 field: bank_fw.pid[PID_YAW].FF
1770 description: "Fixed-wing attitude stabilisation P-gain"
1772 field: bank_fw.pid[PID_LEVEL].P
1776 description: "Fixed-wing attitude stabilisation low-pass filter cutoff"
1778 field: bank_fw.pid[PID_LEVEL].I
1782 description: "Fixed-wing attitude stabilisation HORIZON transition point"
1784 field: bank_fw.pid[PID_LEVEL].D
1787 - name: max_angle_inclination_rll
1788 description: "Maximum inclination in level (angle) mode (ROLL axis). 100=10°"
1790 field: max_angle_inclination[FD_ROLL]
1793 - name: max_angle_inclination_pit
1794 description: "Maximum inclination in level (angle) mode (PITCH axis). 100=10°"
1796 field: max_angle_inclination[FD_PITCH]
1799 - name: dterm_lpf_hz
1800 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"
1804 - name: dterm_lpf_type
1805 description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
1806 default_value: "PT2"
1807 field: dterm_lpf_type
1808 table: filter_type_full
1809 - name: dterm_lpf2_hz
1810 description: "Cutoff frequency for stage 2 D-term low pass filter"
1814 - name: dterm_lpf2_type
1815 description: "Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`, `PT2`, `PT3`."
1816 default_value: "PT1"
1817 field: dterm_lpf2_type
1818 table: filter_type_full
1820 description: "Yaw P term low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below)"
1824 - name: fw_iterm_throw_limit
1825 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."
1827 field: fixedWingItermThrowLimit
1828 min: FW_ITERM_THROW_LIMIT_MIN
1829 max: FW_ITERM_THROW_LIMIT_MAX
1830 - name: fw_reference_airspeed
1831 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."
1833 field: fixedWingReferenceAirspeed
1836 - name: fw_turn_assist_yaw_gain
1837 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"
1839 field: fixedWingCoordinatedYawGain
1842 - name: fw_turn_assist_pitch_gain
1843 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"
1845 field: fixedWingCoordinatedPitchGain
1848 - name: fw_iterm_limit_stick_position
1849 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"
1851 field: fixedWingItermLimitOnStickPosition
1854 - name: fw_yaw_iterm_freeze_bank_angle
1855 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."
1857 field: fixedWingYawItermBankFreeze
1860 - name: pidsum_limit
1861 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"
1864 min: PID_SUM_LIMIT_MIN
1865 max: PID_SUM_LIMIT_MAX
1866 - name: pidsum_limit_yaw
1867 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"
1869 field: pidSumLimitYaw
1870 min: PID_SUM_LIMIT_MIN
1871 max: PID_SUM_LIMIT_MAX
1872 - name: iterm_windup
1873 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)"
1875 field: itermWindupPointPercent
1878 - name: rate_accel_limit_roll_pitch
1879 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."
1881 field: axisAccelerationLimitRollPitch
1883 - name: rate_accel_limit_yaw
1884 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."
1885 default_value: 10000
1886 field: axisAccelerationLimitYaw
1888 - name: heading_hold_rate_limit
1889 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."
1890 min: HEADING_HOLD_RATE_LIMIT_MIN
1891 max: HEADING_HOLD_RATE_LIMIT_MAX
1893 - name: nav_mc_pos_z_p
1894 description: "P gain of altitude PID controller (Multirotor)"
1895 field: bank_mc.pid[PID_POS_Z].P
1899 - name: nav_mc_vel_z_p
1900 description: "P gain of velocity PID controller"
1901 field: bank_mc.pid[PID_VEL_Z].P
1905 - name: nav_mc_vel_z_i
1906 description: "I gain of velocity PID controller"
1907 field: bank_mc.pid[PID_VEL_Z].I
1911 - name: nav_mc_vel_z_d
1912 description: "D gain of velocity PID controller"
1913 field: bank_mc.pid[PID_VEL_Z].D
1917 - name: nav_mc_pos_xy_p
1918 description: "Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity"
1919 field: bank_mc.pid[PID_POS_XY].P
1923 - name: nav_mc_vel_xy_p
1924 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"
1925 field: bank_mc.pid[PID_VEL_XY].P
1929 - name: nav_mc_vel_xy_i
1930 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"
1931 field: bank_mc.pid[PID_VEL_XY].I
1935 - name: nav_mc_vel_xy_d
1936 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."
1937 field: bank_mc.pid[PID_VEL_XY].D
1941 - name: nav_mc_vel_xy_ff
1942 field: bank_mc.pid[PID_VEL_XY].FF
1946 - name: nav_mc_heading_p
1947 description: "P gain of Heading Hold controller (Multirotor)"
1949 field: bank_mc.pid[PID_HEADING].P
1952 - name: nav_mc_vel_xy_dterm_lpf_hz
1953 field: navVelXyDTermLpfHz
1957 - name: nav_mc_vel_xy_dterm_attenuation
1958 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."
1959 field: navVelXyDtermAttenuation
1963 - name: nav_mc_vel_xy_dterm_attenuation_start
1964 description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation begins"
1966 field: navVelXyDtermAttenuationStart
1969 - name: nav_mc_vel_xy_dterm_attenuation_end
1970 description: "A point (in percent of both target and current horizontal velocity) where nav_mc_vel_xy_dterm_attenuation reaches maximum"
1972 field: navVelXyDtermAttenuationEnd
1975 - name: nav_fw_pos_z_p
1976 description: "P gain of altitude PID controller (Fixedwing)"
1978 field: bank_fw.pid[PID_POS_Z].P
1981 - name: nav_fw_pos_z_i
1982 description: "I gain of altitude PID controller (Fixedwing)"
1984 field: bank_fw.pid[PID_POS_Z].I
1987 - name: nav_fw_pos_z_d
1988 description: "D gain of altitude PID controller (Fixedwing)"
1990 field: bank_fw.pid[PID_POS_Z].D
1993 - name: nav_fw_pos_xy_p
1994 description: "P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH"
1996 field: bank_fw.pid[PID_POS_XY].P
1999 - name: nav_fw_pos_xy_i
2000 description: "I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2002 field: bank_fw.pid[PID_POS_XY].I
2005 - name: nav_fw_pos_xy_d
2006 description: "D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero"
2008 field: bank_fw.pid[PID_POS_XY].D
2011 - name: nav_fw_heading_p
2012 description: "P gain of Heading Hold controller (Fixedwing)"
2014 field: bank_fw.pid[PID_HEADING].P
2017 - name: nav_fw_pos_hdg_p
2018 description: "P gain of heading PID controller. (Fixedwing, rovers, boats)"
2020 field: bank_fw.pid[PID_POS_HEADING].P
2023 - name: nav_fw_pos_hdg_i
2024 description: "I gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2026 field: bank_fw.pid[PID_POS_HEADING].I
2029 - name: nav_fw_pos_hdg_d
2030 description: "D gain of heading trajectory PID controller. (Fixedwing, rovers, boats)"
2032 field: bank_fw.pid[PID_POS_HEADING].D
2035 - name: nav_fw_pos_hdg_pidsum_limit
2036 description: "Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats)"
2038 field: navFwPosHdgPidsumLimit
2039 min: PID_SUM_LIMIT_MIN
2040 max: PID_SUM_LIMIT_MAX
2041 - name: mc_iterm_relax
2045 - name: mc_iterm_relax_cutoff
2046 field: iterm_relax_cutoff
2052 condition: USE_D_BOOST
2058 condition: USE_D_BOOST
2062 - name: d_boost_max_at_acceleration
2063 field: dBoostMaxAtAlleceleration
2064 condition: USE_D_BOOST
2068 - name: d_boost_gyro_delta_lpf_hz
2069 field: dBoostGyroDeltaLpfHz
2070 condition: USE_D_BOOST
2074 - name: antigravity_gain
2075 description: "Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements"
2077 field: antigravityGain
2078 condition: USE_ANTIGRAVITY
2081 - name: antigravity_accelerator
2084 field: antigravityAccelerator
2085 condition: USE_ANTIGRAVITY
2088 - name: antigravity_cutoff_lpf_hz
2089 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"
2091 field: antigravityCutoff
2092 condition: USE_ANTIGRAVITY
2096 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`"
2097 field: pidControllerType
2100 - name: mc_cd_lpf_hz
2101 description: "Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky"
2103 field: controlDerivativeLpfHz
2106 - name: fw_level_pitch_trim
2107 description: "Pitch trim for self-leveling flight modes. In degrees. +5 means airplane nose should be raised 5 deg from level"
2109 field: fixedWingLevelTrim
2112 - name: smith_predictor_strength
2113 description: "The strength factor of a Smith Predictor of PID measurement. In percents"
2115 field: smithPredictorStrength
2116 condition: USE_SMITH_PREDICTOR
2119 - name: smith_predictor_delay
2120 description: "Expected delay of the gyro signal. In milliseconds"
2122 field: smithPredictorDelay
2123 condition: USE_SMITH_PREDICTOR
2126 - name: smith_predictor_lpf_hz
2127 description: "Cutoff frequency for the Smith Predictor Low Pass Filter"
2129 field: smithPredictorFilterHz
2130 condition: USE_SMITH_PREDICTOR
2133 - name: fw_level_pitch_gain
2134 description: "I-gain for the pitch trim for self-leveling flight modes. Higher values means that AUTOTRIM will be faster but might introduce oscillations"
2136 field: fixedWingLevelTrimGain
2140 - name: PG_PID_AUTOTUNE_CONFIG
2141 type: pidAutotuneConfig_t
2142 condition: USE_AUTOTUNE_FIXED_WING
2144 - name: fw_autotune_min_stick
2145 description: "Minimum stick input [%], after applying deadband and expo, to start recording the plane's response to stick input."
2150 - name: fw_autotune_rate_adjustment
2151 description: "`AUTO` and `LIMIT` adjust the rates to match the capabilities of the airplane, with `LIMIT` they are never increased above the starting rates setting. `FIXED` does not adjust the rates. Rates are not changed when tuning in `ANGLE` mode."
2152 default_value: "AUTO"
2153 field: fw_rate_adjustment
2154 table: autotune_rate_adjustment
2156 - name: fw_autotune_max_rate_deflection
2157 description: "The target percentage of maximum mixer output used for determining the rates in `AUTO` and `LIMIT`."
2159 field: fw_max_rate_deflection
2163 - name: PG_POSITION_ESTIMATION_CONFIG
2164 type: positionEstimationConfig_t
2166 - name: inav_auto_mag_decl
2167 description: "Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored."
2169 field: automatic_mag_declination
2171 - name: inav_gravity_cal_tolerance
2172 description: "Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value."
2174 field: gravity_calibration_tolerance
2177 - name: inav_use_gps_velned
2178 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."
2180 field: use_gps_velned
2182 - name: inav_use_gps_no_baro
2183 field: use_gps_no_baro
2186 - name: inav_allow_dead_reckoning
2187 description: "Defines if INAV will dead-reckon over short GPS outages. May also be useful for indoors OPFLOW navigation"
2189 field: allow_dead_reckoning
2191 - name: inav_reset_altitude
2192 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)"
2193 default_value: "FIRST_ARM"
2194 field: reset_altitude_type
2196 - name: inav_reset_home
2197 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"
2198 default_value: "FIRST_ARM"
2199 field: reset_home_type
2201 - name: inav_max_surface_altitude
2202 description: "Max allowed altitude for surface following mode. [cm]"
2204 field: max_surface_altitude
2207 - name: inav_w_z_surface_p
2208 field: w_z_surface_p
2212 - name: inav_w_z_surface_v
2213 field: w_z_surface_v
2217 - name: inav_w_xy_flow_p
2222 - name: inav_w_xy_flow_v
2227 - name: inav_w_z_baro_p
2228 description: "Weight of barometer measurements in estimated altitude and climb rate"
2233 - name: inav_w_z_gps_p
2234 description: "Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes"
2239 - name: inav_w_z_gps_v
2240 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"
2245 - name: inav_w_xy_gps_p
2246 description: "Weight of GPS coordinates in estimated UAV position and speed."
2251 - name: inav_w_xy_gps_v
2252 description: "Weight of GPS velocity data in estimated UAV speed"
2257 - name: inav_w_z_res_v
2258 description: "Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost"
2263 - name: inav_w_xy_res_v
2264 description: "Decay coefficient for estimated velocity when GPS reference for position is lost"
2269 - name: inav_w_xyz_acc_p
2274 - name: inav_w_acc_bias
2275 description: "Weight for accelerometer drift estimation"
2280 - name: inav_max_eph_epv
2281 description: "Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm]"
2286 - name: inav_baro_epv
2287 description: "Uncertainty value for barometric sensor [cm]"
2293 - name: PG_NAV_CONFIG
2295 headers: ["navigation/navigation.h"]
2297 - name: nav_disarm_on_landing
2298 description: "If set to ON, INAV disarms the FC after landing"
2300 field: general.flags.disarm_on_landing
2302 - name: nav_land_detect_sensitivity
2303 description: "Changes sensitivity of landing detection. Higher values increase speed of detection but also increase risk of false detection. Default value should work in most cases."
2305 field: general.land_detect_sensitivity
2308 - name: nav_use_midthr_for_althold
2309 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"
2311 field: general.flags.use_thr_mid_for_althold
2313 - name: nav_extra_arming_safety
2314 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"
2316 field: general.flags.extra_arming_safety
2317 table: nav_extra_arming_safety
2318 - name: nav_user_control_mode
2319 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."
2320 default_value: "ATTI"
2321 field: general.flags.user_control_mode
2322 table: nav_user_control_mode
2323 - name: nav_position_timeout
2324 description: "If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable)"
2326 field: general.pos_failure_timeout
2329 - name: nav_wp_load_on_boot
2330 description: "If set to ON, waypoints will be automatically loaded from EEPROM to the FC during startup."
2332 field: general.waypoint_load_on_boot
2334 - name: nav_wp_radius
2335 description: "Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius"
2337 field: general.waypoint_radius
2340 - name: nav_wp_enforce_altitude
2341 description: "Forces craft to achieve the set WP altitude as well as position before moving to next WP. Position is held and altitude adjusted as required before moving on. 0 = disabled, otherwise setting defines altitude capture tolerance [cm], e.g. 100 means required altitude is achieved when within 100cm of waypoint altitude setting."
2343 field: general.waypoint_enforce_altitude
2346 - name: nav_wp_max_safe_distance
2347 description: "First waypoint in the mission should be closer than this value [m]. A value of 0 disables this check."
2349 field: general.waypoint_safe_distance
2352 - name: nav_wp_mission_restart
2353 description: "Sets restart behaviour for a WP mission when interrupted mid mission. START from first WP, RESUME from last active WP or SWITCH between START and RESUME each time WP Mode is reselected ON. SWITCH effectively allows resuming once only from a previous mid mission waypoint after which the mission will restart from the first waypoint."
2354 default_value: "RESUME"
2355 field: general.flags.waypoint_mission_restart
2356 table: nav_wp_mission_restart
2357 - name: nav_wp_multi_mission_index
2358 description: "Index of active mission selected from multi mission WP entry loaded in flight controller. Limited to a maximum of 9 missions."
2360 field: general.waypoint_multi_mission_index
2361 condition: USE_MULTI_MISSION
2364 - name: nav_fw_wp_tracking_accuracy
2365 description: "Waypoint tracking accuracy forces the craft to quickly head toward and track along the waypoint course line as closely as possible. Settings 1 to 10 adjust the course tracking response. Higher values dampen the response reducing possible overshoot. A value of 5 is a good starting point. Set to 0 to disable."
2367 field: fw.wp_tracking_accuracy
2370 - name: nav_fw_wp_tracking_max_angle
2371 description: "Sets the maximum allowed alignment convergence angle to the waypoint course line when nav_fw_wp_tracking_accuracy is active [degrees]. Lower values result in smoother alignment with the course line but will take more distance until this is achieved."
2373 field: fw.wp_tracking_max_angle
2376 - name: nav_fw_wp_turn_smoothing
2377 description: "Smooths turns during WP missions by switching to a loiter turn at waypoints. When set to ON the craft will reach the waypoint during the turn. When set to ON-CUT the craft will turn inside the waypoint without actually reaching it (cuts the corner)."
2378 default_value: "OFF"
2379 field: fw.wp_turn_smoothing
2380 table: nav_fw_wp_turn_smoothing
2381 - name: nav_auto_speed
2382 description: "Speed in fully autonomous modes (RTH, WP) [cm/s]. Used for WP mode when no specific WP speed set. [Multirotor only]"
2384 field: general.auto_speed
2387 - name: nav_max_auto_speed
2388 description: "Maximum speed allowed in fully autonomous modes (RTH, WP) [cm/s] [Multirotor only]"
2390 field: general.max_auto_speed
2393 - name: nav_auto_climb_rate
2394 description: "Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s]"
2396 field: general.max_auto_climb_rate
2399 - name: nav_manual_speed
2400 description: "Maximum speed allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only]"
2402 field: general.max_manual_speed
2405 - name: nav_manual_climb_rate
2406 description: "Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s]"
2408 field: general.max_manual_climb_rate
2411 - name: nav_land_minalt_vspd
2412 description: "Vertical descent velocity under nav_land_slowdown_minalt during the RTH landing phase. [cm/s]"
2414 field: general.land_minalt_vspd
2417 - name: nav_land_maxalt_vspd
2418 description: "Vertical descent velocity above nav_land_slowdown_maxalt during the RTH landing phase. [cm/s]"
2420 field: general.land_maxalt_vspd
2423 - name: nav_land_slowdown_minalt
2424 description: "Defines at what altitude the descent velocity should start to be `nav_land_minalt_vspd` [cm]"
2426 field: general.land_slowdown_minalt
2429 - name: nav_land_slowdown_maxalt
2430 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]"
2432 field: general.land_slowdown_maxalt
2435 - name: nav_emerg_landing_speed
2436 description: "Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s]"
2438 field: general.emerg_descent_rate
2441 - name: nav_min_rth_distance
2442 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."
2444 field: general.min_rth_distance
2447 - name: nav_overrides_motor_stop
2448 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"
2449 default_value: "ALL_NAV"
2450 field: general.flags.nav_overrides_motor_stop
2451 table: nav_overrides_motor_stop
2452 - name: nav_fw_soaring_motor_stop
2453 description: "Stops motor when Soaring mode enabled."
2455 field: general.flags.soaring_motor_stop
2457 - name: nav_fw_soaring_pitch_deadband
2458 description: "Pitch Angle deadband when soaring mode enabled (deg). Angle mode inactive within deadband allowing pitch to free float whilst soaring."
2460 field: fw.soaring_pitch_deadband
2463 - name: nav_rth_climb_first
2464 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)"
2466 field: general.flags.rth_climb_first
2467 table: nav_rth_climb_first
2468 - name: nav_rth_climb_first_stage_mode
2469 description: "This determines how rth_climb_first_stage_altitude is used. Default is AT_LEAST."
2470 default_value: "AT_LEAST"
2471 field: general.flags.rth_climb_first_stage_mode
2472 table: nav_rth_climb_first_stage_modes
2473 - name: nav_rth_climb_first_stage_altitude
2474 description: "The altitude [cm] at which climb first will transition to turn first. How the altitude is used, is determined by nav_rth_climb_first_stage_mode. Default=0; feature disabled."
2476 field: general.rth_climb_first_stage_altitude
2478 - name: nav_rth_climb_ignore_emerg
2479 description: "If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status."
2481 field: general.flags.rth_climb_ignore_emerg
2483 - name: nav_rth_tail_first
2484 description: "If set to ON drone will return tail-first. Obviously meaningless for airplanes."
2486 field: general.flags.rth_tail_first
2488 - name: nav_rth_allow_landing
2489 description: "If set to ON drone will land as a last phase of RTH."
2490 default_value: "ALWAYS"
2491 field: general.flags.rth_allow_landing
2492 table: nav_rth_allow_landing
2493 - name: nav_rth_alt_mode
2494 description: "Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details"
2495 default_value: "AT_LEAST"
2496 field: general.flags.rth_alt_control_mode
2497 table: nav_rth_alt_mode
2498 - name: nav_rth_alt_control_override
2499 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)"
2501 field: general.flags.rth_alt_control_override
2503 - name: nav_rth_abort_threshold
2504 description: "RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. Set to 0 to disable. [cm]"
2505 default_value: 50000
2506 field: general.rth_abort_threshold
2509 - name: nav_max_terrain_follow_alt
2510 field: general.max_terrain_follow_altitude
2511 default_value: "100"
2512 description: "Max allowed above the ground altitude for terrain following mode"
2515 - name: nav_max_altitude
2516 field: general.max_altitude
2517 description: "Max allowed altitude (above Home Point) that applies to all NAV modes (including Altitude Hold). 0 means limit is disabled"
2521 - name: nav_rth_altitude
2522 description: "Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters)"
2524 field: general.rth_altitude
2526 - name: nav_rth_home_altitude
2527 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]"
2529 field: general.rth_home_altitude
2531 - name: nav_rth_trackback_mode
2532 description: "Useage modes for RTH Trackback. OFF = disabled, ON = Normal and Failsafe RTH, FS = Failsafe RTH only."
2533 default_value: "OFF"
2534 field: general.flags.rth_trackback_mode
2535 table: rth_trackback_mode
2536 - name: nav_rth_trackback_distance
2537 description: "Maximum distance allowed for RTH trackback. Normal RTH is executed once this distance is exceeded [m]."
2539 field: general.rth_trackback_distance
2542 - name: safehome_max_distance
2543 description: "In order for a safehome to be used, it must be less than this distance (in cm) from the arming point."
2544 default_value: 20000
2545 field: general.safehome_max_distance
2548 - name: safehome_usage_mode
2549 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."
2550 default_value: "RTH"
2551 field: general.flags.safehome_usage_mode
2552 table: safehome_usage_mode
2553 - name: nav_mission_planner_reset
2554 description: "With Reset ON WP Mission Planner waypoint count can be reset to 0 by toggling the mode switch ON-OFF-ON."
2556 field: general.flags.mission_planner_reset
2558 - name: nav_mc_bank_angle
2559 description: "Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude"
2561 field: mc.max_bank_angle
2564 - name: nav_auto_disarm_delay
2565 description: "Delay before craft disarms when `nav_disarm_on_landing` is set (ms)"
2567 field: general.auto_disarm_delay
2570 - name: nav_mc_braking_speed_threshold
2571 description: "min speed in cm/s above which braking can happen"
2573 field: mc.braking_speed_threshold
2574 condition: USE_MR_BRAKING_MODE
2577 - name: nav_mc_braking_disengage_speed
2578 description: "braking is disabled when speed goes below this value"
2580 field: mc.braking_disengage_speed
2581 condition: USE_MR_BRAKING_MODE
2584 - name: nav_mc_braking_timeout
2585 description: "timeout in ms for braking"
2587 field: mc.braking_timeout
2588 condition: USE_MR_BRAKING_MODE
2591 - name: nav_mc_braking_boost_factor
2592 description: "acceleration factor for BOOST phase"
2594 field: mc.braking_boost_factor
2595 condition: USE_MR_BRAKING_MODE
2598 - name: nav_mc_braking_boost_timeout
2599 description: "how long in ms BOOST phase can happen"
2601 field: mc.braking_boost_timeout
2602 condition: USE_MR_BRAKING_MODE
2605 - name: nav_mc_braking_boost_speed_threshold
2606 description: "BOOST can be enabled when speed is above this value"
2608 field: mc.braking_boost_speed_threshold
2609 condition: USE_MR_BRAKING_MODE
2612 - name: nav_mc_braking_boost_disengage_speed
2613 description: "BOOST will be disabled when speed goes below this value"
2615 field: mc.braking_boost_disengage_speed
2616 condition: USE_MR_BRAKING_MODE
2619 - name: nav_mc_braking_bank_angle
2620 description: "max angle that MR is allowed to bank in BOOST mode"
2622 field: mc.braking_bank_angle
2623 condition: USE_MR_BRAKING_MODE
2626 - name: nav_mc_pos_deceleration_time
2627 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"
2629 field: mc.posDecelerationTime
2632 - name: nav_mc_pos_expo
2633 description: "Expo for PosHold control"
2635 field: mc.posResponseExpo
2638 - name: nav_mc_wp_slowdown
2639 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."
2641 field: mc.slowDownForTurning
2643 - name: nav_fw_bank_angle
2644 description: "Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll"
2646 field: fw.max_bank_angle
2649 - name: nav_fw_climb_angle
2650 description: "Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2652 field: fw.max_climb_angle
2655 - name: nav_fw_dive_angle
2656 description: "Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit"
2658 field: fw.max_dive_angle
2661 - name: nav_fw_pitch2thr_smoothing
2662 description: "How smoothly the autopilot makes pitch to throttle correction inside a deadband defined by pitch_to_throttle_thresh."
2664 field: fw.pitch_to_throttle_smooth
2667 - name: fw_min_throttle_down_pitch
2668 description: "Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees)"
2670 field: fw.minThrottleDownPitchAngle
2673 - name: nav_fw_pitch2thr_threshold
2674 description: "Threshold from average pitch where momentary pitch_to_throttle correction kicks in. [decidegrees]"
2676 field: fw.pitch_to_throttle_thresh
2679 - name: nav_fw_loiter_radius
2680 description: "PosHold radius. 3000 to 7500 is a good value (30-75m) [cm]"
2682 field: fw.loiter_radius
2685 - name: fw_loiter_direction
2686 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."
2687 default_value: "RIGHT"
2688 field: fw.loiter_direction
2690 - name: nav_fw_cruise_speed
2691 description: "Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s"
2693 field: fw.cruise_speed
2696 - name: nav_fw_control_smoothness
2697 description: "How smoothly the autopilot controls the airplane to correct the navigation error"
2699 field: fw.control_smoothness
2703 - name: nav_fw_land_dive_angle
2704 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"
2706 field: fw.land_dive_angle
2707 condition: NAV_FIXED_WING_LANDING
2711 - name: nav_fw_launch_velocity
2712 description: "Forward velocity threshold for swing-launch detection [cm/s]"
2714 field: fw.launch_velocity_thresh
2717 - name: nav_fw_launch_accel
2718 description: "Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s"
2720 field: fw.launch_accel_thresh
2723 - name: nav_fw_launch_max_angle
2724 description: "Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg]"
2726 field: fw.launch_max_angle
2729 - name: nav_fw_launch_detect_time
2730 description: "Time for which thresholds have to breached to consider launch happened [ms]"
2732 field: fw.launch_time_thresh
2735 - name: nav_fw_launch_idle_motor_delay
2736 description: "Delay between raising throttle and motor starting at idle throttle (ms)"
2738 field: fw.launch_idle_motor_timer
2741 - name: nav_fw_launch_motor_delay
2742 description: "Delay between detected launch and launch sequence start and throttling up (ms)"
2744 field: fw.launch_motor_timer
2747 - name: nav_fw_launch_spinup_time
2748 description: "Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller"
2750 field: fw.launch_motor_spinup_time
2753 - name: nav_fw_launch_end_time
2754 description: "Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms]"
2756 field: fw.launch_end_time
2759 - name: nav_fw_launch_min_time
2760 description: "Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]."
2762 field: fw.launch_min_time
2765 - name: nav_fw_launch_timeout
2766 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)"
2768 field: fw.launch_timeout
2770 - name: nav_fw_launch_max_altitude
2771 description: "Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]."
2773 field: fw.launch_max_altitude
2776 - name: nav_fw_launch_climb_angle
2777 description: "Climb angle (attitude of model, not climb slope) for launch sequence (degrees), is also restrained by global max_angle_inclination_pit"
2779 field: fw.launch_climb_angle
2782 - name: nav_fw_launch_manual_throttle
2783 description: "Allows launch with manually controlled throttle. INAV only levels wings and controls climb pitch during launch. Throttle is controlled directly by throttle stick movement. IF USED WITHOUT A GPS LOCK plane must be launched immediately after throttle is increased to avoid issues with climb out stabilisation and the launch ending sooner than expected (launch end timer starts as soon as the throttle stick is raised)."
2785 field: fw.launch_manual_throttle
2787 - name: nav_fw_launch_abort_deadband
2788 description: "Launch abort stick deadband in [r/c points], applied after r/c deadband and expo. The Roll/Pitch stick needs to be deflected beyond this deadband to abort the launch."
2790 field: fw.launch_abort_deadband
2793 - name: nav_fw_cruise_yaw_rate
2794 description: "Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]"
2796 field: fw.cruise_yaw_rate
2799 - name: nav_fw_allow_manual_thr_increase
2800 description: "Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing"
2802 field: fw.allow_manual_thr_increase
2804 - name: nav_use_fw_yaw_control
2805 description: "Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats"
2807 field: fw.useFwNavYawControl
2809 - name: nav_fw_yaw_deadband
2810 description: "Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course"
2812 field: fw.yawControlDeadband
2816 - name: PG_TELEMETRY_CONFIG
2817 type: telemetryConfig_t
2818 headers: ["io/serial.h", "telemetry/telemetry.h", "telemetry/frsky_d.h", "telemetry/sim.h"]
2819 condition: USE_TELEMETRY
2821 - name: telemetry_switch
2822 description: "Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed."
2825 - name: telemetry_inverted
2826 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."
2829 - name: frsky_default_latitude
2830 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."
2832 field: gpsNoFixLatitude
2835 - name: frsky_default_longitude
2836 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."
2838 field: gpsNoFixLongitude
2841 - name: frsky_coordinates_format
2842 description: "D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA"
2844 field: frsky_coordinate_format
2846 max: FRSKY_FORMAT_NMEA
2847 type: uint8_t # TODO: This seems to use an enum, we should use table:
2849 description: "Not used? [METRIC/IMPERIAL]"
2850 default_value: "METRIC"
2853 - name: frsky_vfas_precision
2854 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"
2856 min: FRSKY_VFAS_PRECISION_LOW
2857 max: FRSKY_VFAS_PRECISION_HIGH
2858 - name: frsky_pitch_roll
2859 description: "S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data"
2862 - name: report_cell_voltage
2863 description: "S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON"
2866 - name: hott_alarm_sound_interval
2867 description: "Battery alarm delay in seconds for Hott telemetry"
2869 field: hottAlarmSoundInterval
2872 - name: telemetry_halfduplex
2873 description: "S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details"
2877 - name: smartport_fuel_unit
2878 description: "S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH]"
2879 default_value: "MAH"
2880 field: smartportFuelUnit
2881 condition: USE_TELEMETRY_SMARTPORT
2883 table: smartport_fuel_unit
2884 - name: ibus_telemetry_type
2885 description: "Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details."
2887 field: ibusTelemetryType
2890 - name: ltm_update_rate
2891 description: "Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details."
2892 default_value: "NORMAL"
2893 field: ltmUpdateRate
2894 condition: USE_TELEMETRY_LTM
2896 - name: sim_ground_station_number
2897 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."
2899 field: simGroundStationNumber
2900 condition: USE_TELEMETRY_SIM
2902 description: "PIN code for the SIM module"
2903 default_value: "0000"
2905 condition: USE_TELEMETRY_SIM
2906 - name: sim_transmit_interval
2907 description: "Text message transmission interval in seconds for SIM module. Minimum value: 10"
2909 field: simTransmitInterval
2910 condition: USE_TELEMETRY_SIM
2912 min: SIM_MIN_TRANSMIT_INTERVAL
2914 - name: sim_transmit_flags
2915 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`"
2916 default_value: :SIM_TX_FLAG_FAILSAFE
2917 field: simTransmitFlags
2918 condition: USE_TELEMETRY_SIM
2920 - name: acc_event_threshold_high
2921 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."
2923 field: accEventThresholdHigh
2924 condition: USE_TELEMETRY_SIM
2928 - name: acc_event_threshold_low
2929 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."
2931 field: accEventThresholdLow
2932 condition: USE_TELEMETRY_SIM
2936 - name: acc_event_threshold_neg_x
2937 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."
2939 field: accEventThresholdNegX
2940 condition: USE_TELEMETRY_SIM
2944 - name: sim_low_altitude
2945 description: "Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`."
2946 default_value: -32767
2947 field: simLowAltitude
2948 condition: USE_TELEMETRY_SIM
2952 - name: mavlink_ext_status_rate
2953 field: mavlink.extended_status_rate
2958 - name: mavlink_rc_chan_rate
2959 field: mavlink.rc_channels_rate
2964 - name: mavlink_pos_rate
2965 field: mavlink.position_rate
2970 - name: mavlink_extra1_rate
2971 field: mavlink.extra1_rate
2976 - name: mavlink_extra2_rate
2977 field: mavlink.extra2_rate
2982 - name: mavlink_extra3_rate
2983 field: mavlink.extra3_rate
2988 - name: mavlink_version
2989 field: mavlink.version
2990 description: "Version of MAVLink to use"
2996 - name: PG_LED_STRIP_CONFIG
2997 type: ledStripConfig_t
2998 headers: ["common/color.h", "io/ledstrip.h"]
2999 condition: USE_LED_STRIP
3001 - name: ledstrip_visual_beeper
3006 - name: PG_OSD_CONFIG
3008 headers: ["io/osd.h", "drivers/osd.h"]
3011 - name: osd_telemetry
3012 description: "To enable OSD telemetry for antenna tracker. Possible values are `OFF`, `ON` and `TEST`"
3013 table: osd_telemetry
3016 default_value: "OFF"
3017 - name: osd_video_system
3018 description: "Video system used. Possible values are `AUTO`, `PAL`, `NTSC`, `HDZERO`, 'DJIWTF', 'AVATAR' and `BF43COMPAT`"
3019 default_value: "AUTO"
3020 table: osd_video_system
3023 - name: osd_row_shiftdown
3024 description: "Number of rows to shift the OSD display (increase if top rows are cut off)"
3026 field: row_shiftdown
3029 - name: osd_msp_displayport_fullframe_interval
3030 description: "Full Frame redraw interval for MSP DisplayPort [deciseconds]. This is how often a full frame update is sent to the DisplayPort, to cut down on OSD artifacting. The default value should be fine for most pilots. Though long range pilots may benefit from increasing the refresh time, especially near the edge of range. -1 = disabled (legacy mode) | 0 = every frame (not recommended) | default = 10 (1 second)"
3035 field: msp_displayport_fullframe_interval
3037 description: "IMPERIAL, METRIC, UK"
3038 default_value: "METRIC"
3042 - name: osd_stats_energy_unit
3043 description: "Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour)"
3044 default_value: "MAH"
3045 field: stats_energy_unit
3046 table: osd_stats_energy_unit
3048 - name: osd_stats_min_voltage_unit
3049 description: "Display minimum voltage of the `BATTERY` or the average per `CELL` in the OSD stats."
3050 default_value: "BATTERY"
3051 field: stats_min_voltage_unit
3052 table: osd_stats_min_voltage_unit
3054 - name: osd_stats_page_auto_swap_time
3055 description: "Auto swap display time interval between disarm stats pages (seconds). Reverts to manual control when Roll stick used to change pages. Disabled when set to 0."
3057 field: stats_page_auto_swap_time
3060 - name: osd_rssi_alarm
3061 description: "Value below which to make the OSD RSSI indicator blink"
3066 - name: osd_time_alarm
3067 description: "Value above which to make the OSD flight time indicator blink (minutes)"
3072 - name: osd_alt_alarm
3073 description: "Value above which to make the OSD relative altitude indicator blink (meters)"
3078 - name: osd_dist_alarm
3079 description: "Value above which to make the OSD distance from home indicator blink (meters)"
3084 - name: osd_neg_alt_alarm
3085 description: "Value below which (negative altitude) to make the OSD relative altitude indicator blink (meters)"
3087 field: neg_alt_alarm
3090 - name: osd_current_alarm
3091 description: "Value above which the OSD current consumption element will start blinking. Measured in full Amperes."
3093 field: current_alarm
3096 - name: osd_gforce_alarm
3097 description: "Value above which the OSD g force indicator will blink (g)"
3102 - name: osd_gforce_axis_alarm_min
3103 description: "Value under which the OSD axis g force indicators will blink (g)"
3105 field: gforce_axis_alarm_min
3108 - name: osd_gforce_axis_alarm_max
3109 description: "Value above which the OSD axis g force indicators will blink (g)"
3111 field: gforce_axis_alarm_max
3114 - name: osd_imu_temp_alarm_min
3115 description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3117 field: imu_temp_alarm_min
3120 - name: osd_imu_temp_alarm_max
3121 description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3123 field: imu_temp_alarm_max
3126 - name: osd_esc_temp_alarm_max
3127 description: "Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3129 field: esc_temp_alarm_max
3132 - name: osd_esc_temp_alarm_min
3133 description: "Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade)"
3135 field: esc_temp_alarm_min
3138 - name: osd_baro_temp_alarm_min
3139 description: "Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3141 field: baro_temp_alarm_min
3145 - name: osd_baro_temp_alarm_max
3146 description: "Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade)"
3148 field: baro_temp_alarm_max
3152 - name: osd_snr_alarm
3153 condition: USE_SERIALRX_CRSF
3154 description: "Value below which Crossfire SNR Alarm pops-up. (dB)"
3159 - name: osd_link_quality_alarm
3160 condition: USE_SERIALRX_CRSF
3161 description: "LQ % indicator blinks below this value. For Crossfire use 70%, for Tracer use 50%"
3163 field: link_quality_alarm
3166 - name: osd_rssi_dbm_alarm
3167 condition: USE_SERIALRX_CRSF
3168 description: "RSSI dBm indicator blinks below this value [dBm]. 0 disables this alarm"
3170 field: rssi_dbm_alarm
3173 - name: osd_rssi_dbm_max
3174 condition: USE_SERIALRX_CRSF
3175 description: "RSSI dBm upper end of curve. Perfect rssi (max) = 100%"
3180 - name: osd_rssi_dbm_min
3181 condition: USE_SERIALRX_CRSF
3182 description: "RSSI dBm lower end of curve or RX sensitivity level. Worst rssi (min) = 0%"
3187 - name: osd_temp_label_align
3188 description: "Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT`"
3189 default_value: "LEFT"
3190 field: temp_label_align
3191 condition: USE_TEMPERATURE_SENSOR
3192 table: osd_alignment
3194 - name: osd_airspeed_alarm_min
3195 condition: USE_PITOT
3196 description: "Airspeed under which the airspeed OSD element will start blinking (cm/s)"
3198 field: airspeed_alarm_min
3200 max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3201 - name: osd_airspeed_alarm_max
3202 condition: USE_PITOT
3203 description: "Airspeed above which the airspeed OSD element will start blinking (cm/s)"
3205 field: airspeed_alarm_max
3207 max: 27000 # (1000km/h * 1000 * 100 / 60 / 60)
3208 - name: osd_ahi_reverse_roll
3209 description: "Switches the artificial horizon in the OSD to instead be a bank indicator, by reversing the direction of its movement."
3210 field: ahi_reverse_roll
3213 - name: osd_ahi_max_pitch
3214 description: "Max pitch, in degrees, for OSD artificial horizon"
3216 field: ahi_max_pitch
3220 - name: osd_crosshairs_style
3221 description: "To set the visual type for the crosshair"
3222 default_value: "DEFAULT"
3223 field: crosshairs_style
3224 table: osd_crosshairs_style
3226 - name: osd_crsf_lq_format
3227 description: "To select LQ format"
3228 default_value: "TYPE1"
3229 field: crsf_lq_format
3230 table: osd_crsf_lq_format
3232 - name: osd_horizon_offset
3233 description: "To vertically adjust the whole OSD and AHI and scrolling bars"
3235 field: horizon_offset
3238 - name: osd_camera_uptilt
3239 description: "Set the camera uptilt for the FPV camera in degres, positive is up, negative is down, relative to the horizontal. Used for correct display of HUD items and AHI (when enabled)."
3241 field: camera_uptilt
3244 - name: osd_ahi_camera_uptilt_comp
3245 description: "When set to `ON`, the AHI position is adjusted by `osd_camera_uptilt`. For example, with a cammera uptilt of 30 degrees, the AHI will appear in the middle of the OSD when the aircraft is pitched forward 30 degrees. When set to `OFF`, the AHI will appear in the center of the OSD regardless of camera angle, but can still be shifted up and down using `osd_horizon_offset` (`osd_ahi_vertical_offset` for pixel-OSD)."
3247 field: ahi_camera_uptilt_comp
3249 - name: osd_camera_fov_h
3250 description: "Horizontal field of view for the camera in degres"
3255 - name: osd_camera_fov_v
3256 description: "Vertical field of view for the camera in degres"
3261 - name: osd_hud_margin_h
3262 description: "Left and right margins for the hud area"
3267 - name: osd_hud_margin_v
3268 description: "Top and bottom margins for the hud area"
3273 - name: osd_hud_homing
3274 description: "To display little arrows around the crossair showing where the home point is in the hud"
3278 - name: osd_hud_homepoint
3279 description: "To 3D-display the home point location in the hud"
3281 field: hud_homepoint
3283 - name: osd_hud_radar_disp
3284 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"
3286 field: hud_radar_disp
3289 - name: osd_hud_radar_range_min
3290 description: "In meters, radar aircrafts closer than this will not be displayed in the hud"
3292 field: hud_radar_range_min
3295 - name: osd_hud_radar_range_max
3296 description: "In meters, radar aircrafts further away than this will not be displayed in the hud"
3298 field: hud_radar_range_max
3301 - name: osd_hud_radar_alt_difference_display_time
3302 description: "Time in seconds to display the altitude difference in radar"
3303 field: hud_radar_alt_difference_display_time
3307 - name: osd_hud_radar_distance_display_time
3308 description: "Time in seconds to display the distance in radar"
3309 field: hud_radar_distance_display_time
3313 - name: osd_hud_wp_disp
3314 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)"
3319 - name: osd_left_sidebar_scroll
3320 field: left_sidebar_scroll
3321 table: osd_sidebar_scroll
3324 - name: osd_right_sidebar_scroll
3325 field: right_sidebar_scroll
3326 table: osd_sidebar_scroll
3329 - name: osd_sidebar_scroll_arrows
3330 field: sidebar_scroll_arrows
3333 - name: osd_main_voltage_decimals
3334 description: "Number of decimals for the battery voltages displayed in the OSD [1-2]."
3336 field: main_voltage_decimals
3339 - name: osd_coordinate_digits
3340 field: coordinate_digits
3345 - name: osd_estimations_wind_compensation
3346 description: "Use wind estimation for remaining flight time/distance estimation"
3348 condition: USE_WIND_ESTIMATOR
3349 field: estimations_wind_compensation
3352 - name: osd_failsafe_switch_layout
3353 description: "If enabled the OSD automatically switches to the first layout during failsafe"
3357 - name: osd_plus_code_digits
3358 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."
3359 field: plus_code_digits
3363 - name: osd_plus_code_short
3364 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."
3365 field: plus_code_short
3367 table: osd_plus_code_short
3369 - name: osd_ahi_style
3370 description: "Sets OSD Artificial Horizon style \"DEFAULT\" or \"LINE\" for the FrSky Graphical OSD."
3372 default_value: "DEFAULT"
3373 table: osd_ahi_style
3376 - name: osd_force_grid
3380 description: Force OSD to work in grid mode even if the OSD device supports pixel level access (mainly used for development)
3382 - name: osd_ahi_bordered
3385 description: Shows a border/corners around the AHI region (pixel OSD only)
3388 - name: osd_ahi_width
3391 description: AHI width in pixels (pixel OSD only)
3394 - name: osd_ahi_height
3397 description: AHI height in pixels (pixel OSD only)
3400 - name: osd_ahi_vertical_offset
3401 field: ahi_vertical_offset
3404 description: AHI vertical offset from center (pixel OSD only)
3407 - name: osd_sidebar_horizontal_offset
3408 field: sidebar_horizontal_offset
3412 description: Sidebar horizontal offset from default position. Positive values move the sidebars closer to the edges.
3414 - name: osd_left_sidebar_scroll_step
3415 field: left_sidebar_scroll_step
3418 description: How many units each sidebar step represents. 0 means the default value for the scroll type.
3420 - name: osd_right_sidebar_scroll_step
3421 field: right_sidebar_scroll_step
3424 description: Same as left_sidebar_scroll_step, but for the right sidebar
3426 - name: osd_sidebar_height
3427 field: sidebar_height
3431 description: Height of sidebars in rows. 0 leaves only the level indicator arrows (Not for pixel OSD)
3433 - name: osd_ahi_pitch_interval
3434 field: ahi_pitch_interval
3438 description: Draws AHI at increments of the set pitch interval over the full pitch range. AHI line is drawn with ends offset when pitch first exceeds interval with offset increasing with increasing pitch. Offset direction changes between climb and dive. Set to 0 to disable (Not for pixel OSD)
3440 - name: osd_home_position_arm_screen
3443 description: Should home position coordinates be displayed on the arming screen.
3445 - name: osd_pan_servo_index
3446 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.
3447 field: pan_servo_index
3452 - name: osd_pan_servo_pwm2centideg
3453 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.
3454 field: pan_servo_pwm2centideg
3459 - name: osd_esc_rpm_precision
3460 description: Number of characters used to display the RPM value.
3461 field: esc_rpm_precision
3466 - name: osd_mah_used_precision
3467 description: Number of digits used to display mAh used.
3468 field: mAh_used_precision
3473 - name: osd_switch_indicator_zero_name
3474 description: "Character to use for OSD switch incicator 0."
3475 field: osd_switch_indicator0_name
3478 default_value: "FLAP"
3479 - name: osd_switch_indicator_one_name
3480 description: "Character to use for OSD switch incicator 1."
3481 field: osd_switch_indicator1_name
3484 default_value: "GEAR"
3485 - name: osd_switch_indicator_two_name
3486 description: "Character to use for OSD switch incicator 2."
3487 field: osd_switch_indicator2_name
3490 default_value: "CAM"
3491 - name: osd_switch_indicator_three_name
3492 description: "Character to use for OSD switch incicator 3."
3493 field: osd_switch_indicator3_name
3496 default_value: "LIGT"
3497 - name: osd_switch_indicator_zero_channel
3498 description: "RC Channel to use for OSD switch indicator 0."
3499 field: osd_switch_indicator0_channel
3501 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3503 - name: osd_switch_indicator_one_channel
3504 description: "RC Channel to use for OSD switch indicator 1."
3505 field: osd_switch_indicator1_channel
3507 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3509 - name: osd_switch_indicator_two_channel
3510 description: "RC Channel to use for OSD switch indicator 2."
3511 field: osd_switch_indicator2_channel
3513 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3515 - name: osd_switch_indicator_three_channel
3516 description: "RC Channel to use for OSD switch indicator 3."
3517 field: osd_switch_indicator3_channel
3519 max: MAX_SUPPORTED_RC_CHANNEL_COUNT
3521 - name: osd_switch_indicators_align_left
3522 description: "Align text to left of switch indicators"
3523 field: osd_switch_indicators_align_left
3526 - name: osd_system_msg_display_time
3527 description: System message display cycle time for multiple messages (milliseconds).
3528 field: system_msg_display_time
3533 - name: PG_OSD_COMMON_CONFIG
3534 type: osdCommonConfig_t
3535 headers: ["io/osd_common.h"]
3536 condition: USE_OSD || USE_DJI_HD_OSD
3538 - name: osd_speed_source
3539 description: "Sets the speed type displayed by the DJI OSD and OSD canvas (FrSky Pixel): GROUND, 3D, AIR"
3540 default_value: "GROUND"
3542 table: osdSpeedSource
3545 - name: PG_SYSTEM_CONFIG
3546 type: systemConfig_t
3547 headers: ["fc/config.h"]
3550 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)"
3551 default_value: "400KHZ"
3554 - name: cpu_underclock
3555 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"
3557 field: cpuUnderclock
3558 condition: USE_UNDERCLOCK
3561 description: "Defines debug values exposed in debug variables (developer / debugging setting)"
3562 default_value: "NONE"
3564 - name: ground_test_mode
3565 description: "For developer ground test use. Disables motors, sets heading status = Trusted on FW."
3566 condition: USE_DEV_TOOLS
3568 field: groundTestMode
3570 - name: throttle_tilt_comp_str
3571 description: "Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled."
3573 field: throttle_tilt_compensation_strength
3577 description: "Craft name"
3580 max: MAX_NAME_LENGTH
3582 description: "Pilot name"
3585 max: MAX_NAME_LENGTH
3587 - name: PG_MODE_ACTIVATION_OPERATOR_CONFIG
3588 type: modeActivationOperatorConfig_t
3589 headers: ["fc/rc_modes.h"]
3591 - name: mode_range_logic_operator
3592 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."
3594 field: modeActivationOperator
3598 - name: PG_STATS_CONFIG
3600 headers: ["fc/stats.h"]
3601 condition: USE_STATS
3604 description: "General switch of the statistics recording feature (a.k.a. odometer)"
3606 field: stats_enabled
3608 - name: stats_total_time
3609 description: "Total flight time [in seconds]. The value is updated on every disarm when \"stats\" are enabled."
3612 - name: stats_total_dist
3613 description: "Total flight distance [in meters]. The value is updated on every disarm when \"stats\" are enabled."
3616 - name: stats_total_energy
3617 description: "Total energy consumption [in mWh]. The value is updated on every disarm when \"stats\" are enabled."
3622 - name: PG_TIME_CONFIG
3624 headers: ["common/time.h"]
3627 description: "Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs"
3631 - name: tz_automatic_dst
3632 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`."
3633 default_value: "OFF"
3635 table: tz_automatic_dst
3637 - name: PG_DISPLAY_CONFIG
3638 type: displayConfig_t
3639 headers: ["drivers/display.h"]
3641 - name: display_force_sw_blink
3642 description: "OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON"
3644 field: force_sw_blink
3647 - name: PG_VTX_CONFIG
3649 headers: ["io/vtx_control.h"]
3650 condition: USE_VTX_CONTROL
3652 - name: vtx_halfduplex
3653 description: "Use half duplex UART to communicate with the VTX, using only a TX pin in the FC."
3657 - name: vtx_smartaudio_early_akk_workaround
3658 description: "Enable workaround for early AKK SAudio-enabled VTX bug."
3660 field: smartAudioEarlyAkkWorkaroundEnable
3662 - name: vtx_smartaudio_alternate_softserial_method
3663 description: "Enable the alternate softserial method. This is the method used in INAV 3.0 and ealier."
3665 field: smartAudioAltSoftSerialMethod
3667 - name: vtx_softserial_shortstop
3668 description: "Enable the 3x shorter stopbit on softserial. Need for some IRC Tramp VTXes."
3670 field: softSerialShortStop
3672 - name: vtx_smartaudio_stopbits
3673 description: "Set stopbit count for serial (TBS Sixty9 SmartAudio 2.1 require value of 1 bit)"
3675 field: smartAudioStopBits
3679 - name: PG_VTX_SETTINGS_CONFIG
3680 type: vtxSettingsConfig_t
3681 headers: ["drivers/vtx_common.h", "io/vtx.h"]
3682 condition: USE_VTX_SMARTAUDIO || USE_VTX_TRAMP
3685 description: "Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race."
3688 min: VTX_SETTINGS_NO_BAND
3689 max: VTX_SETTINGS_MAX_BAND
3691 description: "Channel to use within the configured `vtx_band`. Valid values are [1, 8]."
3694 min: VTX_SETTINGS_MIN_CHANNEL
3695 max: VTX_SETTINGS_MAX_CHANNEL
3697 description: "VTX RF power level to use. The exact number of mw depends on the VTX hardware."
3700 min: VTX_SETTINGS_MIN_POWER
3701 max: VTX_SETTINGS_MAX_POWER
3702 - name: vtx_low_power_disarm
3703 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."
3704 default_value: "OFF"
3705 field: lowPowerDisarm
3706 table: vtx_low_power_disarm
3708 - name: vtx_pit_mode_chan
3710 min: VTX_SETTINGS_MIN_CHANNEL
3711 max: VTX_SETTINGS_MAX_CHANNEL
3713 - name: vtx_max_power_override
3714 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"
3716 field: maxPowerOverride
3719 - name: vtx_frequency_group
3720 field: frequencyGroup
3721 description: "VTx Frequency group to use. Frequency groups: FREQUENCYGROUP_5G8: 5.8GHz, FREQUENCYGROUP_2G4: 2.4GHz, FREQUENCYGROUP_1G3: 1.3GHz."
3722 table: vtx_frequency_groups
3725 default_value: FREQUENCYGROUP_5G8
3727 - name: PG_PINIOBOX_CONFIG
3728 type: pinioBoxConfig_t
3729 headers: ["io/piniobox.h"]
3730 condition: USE_PINIOBOX
3733 field: permanentId[0]
3734 description: "Mode assignment for PINIO#1"
3735 default_value: "target specific"
3738 default_value: :BOX_PERMANENT_ID_NONE
3741 field: permanentId[1]
3742 default_value: "target specific"
3743 description: "Mode assignment for PINIO#1"
3746 default_value: :BOX_PERMANENT_ID_NONE
3749 field: permanentId[2]
3750 default_value: "target specific"
3751 description: "Mode assignment for PINIO#1"
3754 default_value: :BOX_PERMANENT_ID_NONE
3757 field: permanentId[3]
3758 default_value: "target specific"
3759 description: "Mode assignment for PINIO#1"
3762 default_value: :BOX_PERMANENT_ID_NONE
3765 - name: PG_LOG_CONFIG
3767 headers: ["common/log.h"]
3773 description: "Defines serial debugging log level. See `docs/development/serial_printf_debugging.md` for usage."
3774 default_value: "ERROR"
3779 description: "Defines serial debugging log topic. See `docs/development/serial_printf_debugging.md` for usage."
3782 - name: PG_ESC_SENSOR_CONFIG
3783 type: escSensorConfig_t
3784 headers: ["sensors/esc_sensor.h"]
3785 condition: USE_ESC_SENSOR
3787 - name: esc_sensor_listen_only
3789 description: "Enable when BLHeli32 Auto Telemetry function is used. Disable in every other case"
3794 - name: PG_SMARTPORT_MASTER_CONFIG
3795 type: smartportMasterConfig_t
3796 headers: ["io/smartport_master.h"]
3797 condition: USE_SMARTPORT_MASTER
3799 - name: smartport_master_halfduplex
3803 - name: smartport_master_inverted
3808 - name: PG_DJI_OSD_CONFIG
3809 type: djiOsdConfig_t
3810 headers: ["io/osd_dji_hd.h"]
3811 condition: USE_DJI_HD_OSD
3813 - name: dji_workarounds
3814 description: "Enables workarounds for different versions of MSP protocol used"
3815 field: proto_workarounds
3819 - name: dji_use_name_for_messages
3820 description: "Re-purpose the craft name field for messages."
3822 field: use_name_for_messages
3824 - name: dji_esc_temp_source
3825 description: "Re-purpose the ESC temperature field for IMU/BARO temperature"
3826 default_value: "ESC"
3827 field: esc_temperature_source
3828 table: djiOsdTempSource
3830 - name: dji_message_speed_source
3831 description: "Sets the speed type displayed by the DJI OSD in craft name: GROUND, 3D, AIR"
3833 field: messageSpeedSource
3834 table: osdSpeedSource
3836 - name: dji_rssi_source
3837 description: "Source of the DJI RSSI field: RSSI, CRSF_LQ"
3838 default_value: "RSSI"
3840 table: djiRssiSource
3842 - name: dji_use_adjustments
3843 description: "Show inflight adjustments in craft name field"
3846 field: useAdjustments
3847 - name: dji_cn_alternating_duration
3848 description: "Alternating duration of craft name elements, in tenths of a second"
3852 field: craftNameAlternatingDuration
3855 - name: PG_BEEPER_CONFIG
3856 type: beeperConfig_t
3857 headers: [ "fc/config.h" ]
3859 - name: dshot_beeper_enabled
3860 description: "Whether using DShot motors as beepers is enabled"
3862 field: dshot_beeper_enabled
3864 - name: dshot_beeper_tone
3865 description: "Sets the DShot beeper tone"
3869 field: dshot_beeper_tone
3871 - name: beeper_pwm_mode
3875 description: "Allows disabling PWM mode for beeper on some targets. Switch from ON to OFF if the external beeper sound is weak. Do not switch from OFF to ON without checking if the board supports PWM beeper mode"
3877 - name: PG_POWER_LIMITS_CONFIG
3878 type: powerLimitsConfig_t
3879 headers: ["flight/power_limits.h"]
3880 condition: USE_POWER_LIMITS
3883 description: "Throttle attenuation PI control P term"
3888 description: "Throttle attenuation PI control I term"
3892 - name: limit_attn_filter_cutoff
3893 description: "Throttle attenuation PI control output filter cutoff frequency"
3895 field: attnFilterCutoff