2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
26 #include "build/debug.h"
28 #include "blackbox/blackbox.h"
32 #include "common/utils.h"
34 #include "drivers/adc.h"
35 #include "drivers/bus_i2c.h"
36 #include "drivers/bus_spi.h"
37 #include "drivers/camera_control.h"
38 #include "drivers/light_led.h"
39 #include "drivers/pinio.h"
40 #include "drivers/vtx_common.h"
42 #include "fc/config.h"
43 #include "fc/controlrate_profile.h"
44 #include "fc/fc_core.h"
45 #include "fc/rc_adjustments.h"
46 #include "fc/rc_controls.h"
48 #include "flight/failsafe.h"
49 #include "flight/gps_rescue.h"
50 #include "flight/imu.h"
51 #include "flight/mixer.h"
52 #include "flight/pid.h"
53 #include "flight/position.h"
54 #include "flight/servos.h"
56 #include "interface/settings.h"
58 #include "io/beeper.h"
59 #include "io/dashboard.h"
60 #include "io/gimbal.h"
62 #include "io/ledstrip.h"
65 #include "io/vtx_control.h"
66 #include "io/vtx_rtc6705.h"
69 #include "pg/beeper.h"
70 #include "pg/beeper_dev.h"
71 #include "pg/dashboard.h"
73 #include "pg/max7456.h"
75 #include "pg/pg_ids.h"
77 #include "pg/piniobox.h"
79 #include "pg/rx_spi.h"
80 #include "pg/rx_pwm.h"
81 #include "pg/sdcard.h"
87 #include "rx/cc2500_frsky_common.h"
88 #include "rx/spektrum.h"
90 #include "sensors/acceleration.h"
91 #include "sensors/barometer.h"
92 #include "sensors/battery.h"
93 #include "sensors/boardalignment.h"
94 #include "sensors/compass.h"
95 #include "sensors/esc_sensor.h"
96 #include "sensors/gyro.h"
97 #include "sensors/rangefinder.h"
99 #include "telemetry/frsky_hub.h"
100 #include "telemetry/ibus_shared.h"
101 #include "telemetry/telemetry.h"
103 // Sensor names (used in lookup tables for *_hardware settings and in status command output)
104 // sync with accelerationSensor_e
105 const char * const lookupTableAccHardware
[] = {
106 "AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC",
107 "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
111 // sync with gyroSensor_e
112 const char * const lookupTableGyroHardware
[] = {
113 "AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20",
114 "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
118 #if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
119 // sync with baroSensor_e
120 const char * const lookupTableBaroHardware
[] = {
121 "AUTO", "NONE", "BMP085", "MS5611", "BMP280", "LPS", "QMP6988"
124 #if defined(USE_SENSOR_NAMES) || defined(USE_MAG)
125 // sync with magSensor_e
126 const char * const lookupTableMagHardware
[] = {
127 "AUTO", "NONE", "HMC5883", "AK8975", "AK8963", "QMC5883"
130 #if defined(USE_SENSOR_NAMES) || defined(USE_RANGEFINDER)
131 const char * const lookupTableRangefinderHardware
[] = {
132 "NONE", "HCSR04", "TFMINI", "TF02"
136 static const char * const lookupTableOffOn
[] = {
140 static const char * const lookupTableCrashRecovery
[] = {
144 static const char * const lookupTableUnit
[] = {
148 static const char * const lookupTableAlignment
[] = {
161 static const char * const lookupTableGyro
[] = {
162 "FIRST", "SECOND", "BOTH"
167 static const char * const lookupTableGPSProvider
[] = {
171 static const char * const lookupTableGPSSBASMode
[] = {
172 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
177 static const char * const lookupTableGimbalMode
[] = {
183 static const char * const lookupTableBlackboxDevice
[] = {
184 "NONE", "SPIFLASH", "SDCARD", "SERIAL"
187 static const char * const lookupTableBlackboxMode
[] = {
188 "NORMAL", "MOTOR_TEST", "ALWAYS"
193 static const char * const lookupTableSerialRX
[] = {
211 // sync with rx_spi_protocol_e
212 static const char * const lookupTableRxSpi
[] = {
229 static const char * const lookupTableGyroHardwareLpf
[] = {
235 #ifdef USE_32K_CAPABLE_GYRO
236 static const char * const lookupTableGyro32khzHardwareLpf
[] = {
242 #ifdef USE_CAMERA_CONTROL
243 static const char * const lookupTableCameraControlMode
[] = {
250 static const char * const lookupTablePwmProtocol
[] = {
251 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
253 "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "PROSHOT1000"
257 static const char * const lookupTableRcInterpolation
[] = {
258 "OFF", "PRESET", "AUTO", "MANUAL"
261 static const char * const lookupTableRcInterpolationChannels
[] = {
262 "RP", "RPY", "RPYT", "T", "RPT",
265 static const char * const lookupTableLowpassType
[] = {
270 static const char * const lookupTableDtermLowpassType
[] = {
276 static const char * const lookupTableFailsafe
[] = {
277 "AUTO-LAND", "DROP", "GPS-RESCUE"
280 static const char * const lookupTableFailsafeSwitchMode
[] = {
281 "STAGE1", "KILL", "STAGE2"
284 static const char * const lookupTableBusType
[] = {
285 "NONE", "I2C", "SPI", "SLAVE"
289 static const char * const lookupTableMax7456Clock
[] = {
290 "HALF", "DEFAULT", "FULL"
294 #ifdef USE_GYRO_OVERFLOW_CHECK
295 static const char * const lookupTableGyroOverflowCheck
[] = {
300 static const char * const lookupTableRatesType
[] = {
301 "BETAFLIGHT", "RACEFLIGHT"
305 static const char * const lookupOverclock
[] = {
307 #if defined(STM32F40_41xxx)
308 "192MHZ", "216MHZ", "240MHZ"
309 #elif defined(STM32F411xE)
311 #elif defined(STM32F7)
318 static const char * const lookupLedStripFormatRGB
[] = {
323 static const char * const lookupTableThrottleLimitType
[] = {
324 "OFF", "SCALE", "CLIP"
328 #ifdef USE_GPS_RESCUE
329 static const char * const lookupTableRescueSanityType
[] = {
330 "RESCUE_SANITY_OFF", "RESCUE_SANITY_ON", "RESCUE_SANITY_FS_ONLY"
335 static const char * const lookupTableVideoSystem
[] = {
336 "AUTO", "PAL", "NTSC"
338 #endif // USE_MAX7456
340 #if defined(USE_ITERM_RELAX)
341 static const char * const lookupTableItermRelax
[] = {
346 #ifdef USE_ACRO_TRAINER
347 static const char * const lookupTableAcroTrainerDebug
[] = {
350 #endif // USE_ACRO_TRAINER
352 #ifdef USE_RC_SMOOTHING_FILTER
353 static const char * const lookupTableRcSmoothingType
[] = {
354 "INTERPOLATION", "FILTER"
356 static const char * const lookupTableRcSmoothingDebug
[] = {
357 "ROLL", "PITCH", "YAW", "THROTTLE"
359 static const char * const lookupTableRcSmoothingInputType
[] = {
362 static const char * const lookupTableRcSmoothingDerivativeType
[] = {
363 "OFF", "PT1", "BIQUAD"
365 #endif // USE_RC_SMOOTHING_FILTER
367 #define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
369 const lookupTableEntry_t lookupTables
[] = {
370 LOOKUP_TABLE_ENTRY(lookupTableOffOn
),
371 LOOKUP_TABLE_ENTRY(lookupTableUnit
),
372 LOOKUP_TABLE_ENTRY(lookupTableAlignment
),
374 LOOKUP_TABLE_ENTRY(lookupTableGPSProvider
),
375 LOOKUP_TABLE_ENTRY(lookupTableGPSSBASMode
),
376 #ifdef USE_GPS_RESCUE
377 LOOKUP_TABLE_ENTRY(lookupTableRescueSanityType
),
381 LOOKUP_TABLE_ENTRY(lookupTableBlackboxDevice
),
382 LOOKUP_TABLE_ENTRY(lookupTableBlackboxMode
),
384 LOOKUP_TABLE_ENTRY(currentMeterSourceNames
),
385 LOOKUP_TABLE_ENTRY(voltageMeterSourceNames
),
387 LOOKUP_TABLE_ENTRY(lookupTableGimbalMode
),
390 LOOKUP_TABLE_ENTRY(lookupTableSerialRX
),
393 LOOKUP_TABLE_ENTRY(lookupTableRxSpi
),
395 LOOKUP_TABLE_ENTRY(lookupTableGyroHardwareLpf
),
396 #ifdef USE_32K_CAPABLE_GYRO
397 LOOKUP_TABLE_ENTRY(lookupTableGyro32khzHardwareLpf
),
399 LOOKUP_TABLE_ENTRY(lookupTableAccHardware
),
401 LOOKUP_TABLE_ENTRY(lookupTableBaroHardware
),
404 LOOKUP_TABLE_ENTRY(lookupTableMagHardware
),
406 LOOKUP_TABLE_ENTRY(debugModeNames
),
407 LOOKUP_TABLE_ENTRY(lookupTablePwmProtocol
),
408 LOOKUP_TABLE_ENTRY(lookupTableRcInterpolation
),
409 LOOKUP_TABLE_ENTRY(lookupTableRcInterpolationChannels
),
410 LOOKUP_TABLE_ENTRY(lookupTableLowpassType
),
411 LOOKUP_TABLE_ENTRY(lookupTableDtermLowpassType
),
412 LOOKUP_TABLE_ENTRY(lookupTableFailsafe
),
413 LOOKUP_TABLE_ENTRY(lookupTableFailsafeSwitchMode
),
414 LOOKUP_TABLE_ENTRY(lookupTableCrashRecovery
),
415 #ifdef USE_CAMERA_CONTROL
416 LOOKUP_TABLE_ENTRY(lookupTableCameraControlMode
),
418 LOOKUP_TABLE_ENTRY(lookupTableBusType
),
420 LOOKUP_TABLE_ENTRY(lookupTableMax7456Clock
),
422 #ifdef USE_RANGEFINDER
423 LOOKUP_TABLE_ENTRY(lookupTableRangefinderHardware
),
425 #ifdef USE_GYRO_OVERFLOW_CHECK
426 LOOKUP_TABLE_ENTRY(lookupTableGyroOverflowCheck
),
428 LOOKUP_TABLE_ENTRY(lookupTableRatesType
),
430 LOOKUP_TABLE_ENTRY(lookupOverclock
),
433 LOOKUP_TABLE_ENTRY(lookupLedStripFormatRGB
),
436 LOOKUP_TABLE_ENTRY(lookupTableGyro
),
438 LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType
),
440 LOOKUP_TABLE_ENTRY(lookupTableVideoSystem
),
441 #endif // USE_MAX7456
442 #if defined(USE_ITERM_RELAX)
443 LOOKUP_TABLE_ENTRY(lookupTableItermRelax
),
445 #ifdef USE_ACRO_TRAINER
446 LOOKUP_TABLE_ENTRY(lookupTableAcroTrainerDebug
),
447 #endif // USE_ACRO_TRAINER
448 #ifdef USE_RC_SMOOTHING_FILTER
449 LOOKUP_TABLE_ENTRY(lookupTableRcSmoothingType
),
450 LOOKUP_TABLE_ENTRY(lookupTableRcSmoothingDebug
),
451 LOOKUP_TABLE_ENTRY(lookupTableRcSmoothingInputType
),
452 LOOKUP_TABLE_ENTRY(lookupTableRcSmoothingDerivativeType
),
453 #endif // USE_RC_SMOOTHING_FILTER
456 #undef LOOKUP_TABLE_ENTRY
458 const clivalue_t valueTable
[] = {
460 { "align_gyro", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_align
) },
461 { "gyro_hardware_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO_HARDWARE_LPF
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_hardware_lpf
) },
462 #ifdef USE_32K_CAPABLE_GYRO
463 { "gyro_32khz_hardware_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO_32KHZ_HARDWARE_LPF
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_32khz_hardware_lpf
) },
465 #if defined(USE_GYRO_SPI_ICM20649)
466 { "gyro_high_range", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_high_fsr
) },
468 { "gyro_sync_denom", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, 32 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_sync_denom
) },
470 { "gyro_lowpass_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_LOWPASS_TYPE
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass_type
) },
471 { "gyro_lowpass_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass_hz
) },
473 { "gyro_lowpass2_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_LOWPASS_TYPE
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass2_type
) },
474 { "gyro_lowpass2_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass2_hz
) },
476 { "gyro_notch1_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_hz_1
) },
477 { "gyro_notch1_cutoff", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_cutoff_1
) },
478 { "gyro_notch2_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_hz_2
) },
479 { "gyro_notch2_cutoff", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_cutoff_2
) },
481 { "gyro_calib_duration", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 50, 3000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyroCalibrationDuration
) },
482 { "gyro_calib_noise_limit", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyroMovementCalibrationThreshold
) },
483 { "gyro_offset_yaw", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -1000, 1000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_offset_yaw
) },
484 #ifdef USE_GYRO_OVERFLOW_CHECK
485 { "gyro_overflow_detect", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO_OVERFLOW_CHECK
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, checkOverflow
) },
487 #ifdef USE_YAW_SPIN_RECOVERY
488 { "yaw_spin_recovery", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, yaw_spin_recovery
) },
489 { "yaw_spin_threshold", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 500, 1950 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, yaw_spin_threshold
) },
492 #if defined(GYRO_USES_SPI)
493 #ifdef USE_32K_CAPABLE_GYRO
494 { "gyro_use_32khz", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_use_32khz
) },
498 { "gyro_to_use", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_to_use
) },
501 // PG_ACCELEROMETER_CONFIG
502 { "align_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_align
) },
503 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ACC_HARDWARE
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_hardware
) },
504 #if defined(USE_GYRO_SPI_ICM20649)
505 { "acc_high_range", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_high_fsr
) },
507 { "acc_lpf_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 400 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_lpf_hz
) },
508 { "acc_trim_pitch", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -300, 300 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accelerometerTrims
.values
.pitch
) },
509 { "acc_trim_roll", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -300, 300 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accelerometerTrims
.values
.roll
) },
510 { "acc_calibration", VAR_INT16
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= XYZ_AXIS_COUNT
, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accZero
.raw
) },
514 { "align_mag", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_align
) },
515 { "mag_bustype", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BUS_TYPE
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_bustype
) },
516 { "mag_i2c_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2CDEV_COUNT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_i2c_device
) },
517 { "mag_i2c_address", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2C_ADDR7_MAX
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_i2c_address
) },
518 { "mag_spi_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_spi_device
) },
519 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MAG_HARDWARE
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_hardware
) },
520 { "mag_declination", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -18000, 18000 }, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_declination
) },
521 { "mag_calibration", VAR_INT16
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= XYZ_AXIS_COUNT
, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, magZero
.raw
) },
524 // PG_BAROMETER_CONFIG
526 { "baro_bustype", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BUS_TYPE
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_bustype
) },
527 { "baro_spi_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 5 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_spi_device
) },
528 { "baro_i2c_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 5 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_i2c_device
) },
529 { "baro_i2c_address", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2C_ADDR7_MAX
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_i2c_address
) },
530 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BARO_HARDWARE
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_hardware
) },
531 { "baro_tab_size", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, BARO_SAMPLE_COUNT_MAX
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_sample_count
) },
532 { "baro_noise_lpf", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_noise_lpf
) },
533 { "baro_cf_vel", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_cf_vel
) },
534 { "baro_cf_alt", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_cf_alt
) },
538 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1200, 1700 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, midrc
) },
539 { "min_check", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, mincheck
) },
540 { "max_check", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, maxcheck
) },
541 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_channel
) },
542 { "rssi_src_frame_errors", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_src_frame_errors
) },
543 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { RSSI_SCALE_MIN
, RSSI_SCALE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_scale
) },
544 { "rssi_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -100, 100 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_offset
) },
545 { "rssi_invert", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_invert
) },
546 { "rc_interp", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_INTERPOLATION
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolation
) },
547 { "rc_interp_ch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_INTERPOLATION_CHANNELS
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolationChannels
) },
548 { "rc_interp_int", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, 50 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolationInterval
) },
550 #ifdef USE_RC_SMOOTHING_FILTER
551 { "rc_smoothing_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_SMOOTHING_TYPE
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_type
) },
552 { "rc_smoothing_input_hz", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, UINT8_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_input_cutoff
) },
553 { "rc_smoothing_derivative_hz", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, UINT8_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_derivative_cutoff
) },
554 { "rc_smoothing_debug_axis", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_SMOOTHING_DEBUG
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_debug_axis
) },
555 { "rc_smoothing_input_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_SMOOTHING_INPUT_TYPE
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_input_type
) },
556 { "rc_smoothing_derivative_type",VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_SMOOTHING_DERIVATIVE_TYPE
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rc_smoothing_derivative_type
) },
557 #endif // USE_RC_SMOOTHING_FILTER
559 { "fpv_mix_degrees", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 50 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, fpvCamAngleDegrees
) },
560 { "max_aux_channels", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, MAX_AUX_CHANNEL_COUNT
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, max_aux_channel
) },
562 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_SERIAL_RX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, serialrx_provider
) },
563 { "serialrx_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, serialrx_inverted
) },
565 #ifdef USE_SPEKTRUM_BIND
566 { "spektrum_sat_bind", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { SPEKTRUM_SAT_BIND_DISABLED
, SPEKTRUM_SAT_BIND_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, spektrum_sat_bind
) },
567 { "spektrum_sat_bind_autoreset",VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, spektrum_sat_bind_autoreset
) },
569 { "airmode_start_throttle_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, airModeActivateThreshold
) },
570 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rx_min_usec
) },
571 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rx_max_usec
) },
572 { "serialrx_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, halfDuplex
) },
574 { "rx_spi_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RX_SPI
}, PG_RX_SPI_CONFIG
, offsetof(rxSpiConfig_t
, rx_spi_protocol
) },
575 { "rx_spi_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_RX_SPI_CONFIG
, offsetof(rxSpiConfig_t
, spibus
) },
580 { "adc_device", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { 0, ADCDEV_COUNT
}, PG_ADC_CONFIG
, offsetof(adcConfig_t
, device
) },
585 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PWM_CONFIG
, offsetof(pwmConfig_t
, inputFilteringMode
) },
588 // PG_BLACKBOX_CONFIG
590 { "blackbox_p_ratio", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, p_ratio
) },
591 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BLACKBOX_DEVICE
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, device
) },
592 { "blackbox_record_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, record_acc
) },
593 { "blackbox_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BLACKBOX_MODE
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, mode
) },
597 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, minthrottle
) },
598 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, maxthrottle
) },
599 { "min_command", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, mincommand
) },
601 { "dshot_idle_value", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 2000 }, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, digitalIdleOffsetValue
) },
602 #ifdef USE_DSHOT_DMAR
603 { "dshot_burst", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.useBurstDshot
) },
606 { "use_unsynced_pwm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.useUnsyncedPwm
) },
607 { "motor_pwm_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MOTOR_PWM_PROTOCOL
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmProtocol
) },
608 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 200, 32000 }, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmRate
) },
609 { "motor_pwm_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmInversion
) },
610 { "motor_poles", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 4, UINT8_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, motorPoleCount
) },
612 // PG_THROTTLE_CORRECTION_CONFIG
613 { "thr_corr_value", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 150 }, PG_THROTTLE_CORRECTION_CONFIG
, offsetof(throttleCorrectionConfig_t
, throttle_correction_value
) },
614 { "thr_corr_angle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1, 900 }, PG_THROTTLE_CORRECTION_CONFIG
, offsetof(throttleCorrectionConfig_t
, throttle_correction_angle
) },
616 // PG_FAILSAFE_CONFIG
617 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_delay
) },
618 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_off_delay
) },
619 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_throttle
) },
620 { "failsafe_switch_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_FAILSAFE_SWITCH_MODE
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_switch_mode
) },
621 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 300 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_throttle_low_delay
) },
622 { "failsafe_procedure", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_FAILSAFE
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_procedure
) },
624 // PG_BOARDALIGNMENT_CONFIG
625 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, rollDegrees
) },
626 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, pitchDegrees
) },
627 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, yawDegrees
) },
631 { "gimbal_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GIMBAL_MODE
}, PG_GIMBAL_CONFIG
, offsetof(gimbalConfig_t
, mode
) },
635 { "bat_capacity", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 20000 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, batteryCapacity
) },
636 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatmaxcellvoltage
) },
637 { "vbat_full_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatfullcellvoltage
) },
638 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatmincellvoltage
) },
639 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatwarningcellvoltage
) },
640 { "vbat_hysteresis", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 250 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbathysteresis
) },
641 { "current_meter", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CURRENT_METER
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, currentMeterSource
) },
642 { "battery_meter", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_VOLTAGE_METER
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, voltageMeterSource
) },
643 { "vbat_detect_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatnotpresentcellvoltage
) },
644 { "use_vbat_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, useVBatAlerts
) },
645 { "use_cbat_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, useConsumptionAlerts
) },
646 { "cbat_alert_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, consumptionWarningPercentage
) },
647 { "vbat_cutoff_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, lvcPercentage
) },
649 // PG_VOLTAGE_SENSOR_ADC_CONFIG
650 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_SCALE_MIN
, VBAT_SCALE_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatscale
) },
651 { "vbat_divider", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_DIVIDER_MIN
, VBAT_DIVIDER_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatresdivval
) },
652 { "vbat_multiplier", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_MULTIPLIER_MIN
, VBAT_MULTIPLIER_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatresdivmultiplier
) },
654 // PG_CURRENT_SENSOR_ADC_CONFIG
655 { "ibata_scale", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG
, offsetof(currentSensorADCConfig_t
, scale
) },
656 { "ibata_offset", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -32000, 32000 }, PG_CURRENT_SENSOR_ADC_CONFIG
, offsetof(currentSensorADCConfig_t
, offset
) },
657 // PG_CURRENT_SENSOR_ADC_CONFIG
658 #ifdef USE_VIRTUAL_CURRENT_METER
659 { "ibatv_scale", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG
, offsetof(currentSensorVirtualConfig_t
, scale
) },
660 { "ibatv_offset", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG
, offsetof(currentSensorVirtualConfig_t
, offset
) },
664 // PG_BEEPER_DEV_CONFIG
665 { "beeper_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, isInverted
) },
666 { "beeper_od", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, isOpenDrain
) },
667 { "beeper_frequency", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, frequency
) },
671 { "beeper_dshot_beacon_tone", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= {1, DSHOT_CMD_BEACON5
}, PG_BEEPER_CONFIG
, offsetof(beeperConfig_t
, dshotBeaconTone
) },
676 { "yaw_motors_reversed", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MIXER_CONFIG
, offsetof(mixerConfig_t
, yaw_motors_reversed
) },
677 { "crashflip_motor_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_MIXER_CONFIG
, offsetof(mixerConfig_t
, crashflip_motor_percent
) },
679 // PG_MOTOR_3D_CONFIG
680 { "3d_deadband_low", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_RANGE_MIDDLE
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_low
) },
681 { "3d_deadband_high", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_RANGE_MIDDLE
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_high
) },
682 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, neutral3d
) },
683 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_throttle
) },
684 { "3d_limit_low", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_RANGE_MIDDLE
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, limit3d_low
) },
685 { "3d_limit_high", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_RANGE_MIDDLE
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, limit3d_high
) },
686 { "3d_switched_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, switched_mode3d
) },
690 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, dev
.servoCenterPulse
) },
691 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 50, 498 }, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, dev
.servoPwmRate
) },
692 { "servo_lowpass_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 400}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, servo_lowpass_freq
) },
693 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, tri_unarmed_servo
) },
694 { "channel_forwarding_start", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { AUX1
, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, channelForwardingStartChannel
) },
697 // PG_CONTROLRATE_PROFILES
698 { "thr_mid", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, thrMid8
) },
699 { "thr_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, thrExpo8
) },
700 { "rates_type", VAR_UINT8
| PROFILE_RATE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RATES_TYPE
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rates_type
) },
701 { "roll_rc_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcRates
[FD_ROLL
]) },
702 { "pitch_rc_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcRates
[FD_PITCH
]) },
703 { "yaw_rc_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_RATES_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcRates
[FD_YAW
]) },
704 { "roll_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcExpo
[FD_ROLL
]) },
705 { "pitch_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcExpo
[FD_PITCH
]) },
706 { "yaw_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RC_EXPO_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rcExpo
[FD_YAW
]) },
707 { "roll_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RATE_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rates
[FD_ROLL
]) },
708 { "pitch_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RATE_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rates
[FD_PITCH
]) },
709 { "yaw_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_RATE_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rates
[FD_YAW
]) },
710 { "tpa_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_TPA_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, dynThrPID
) },
711 { "tpa_breakpoint", VAR_UINT16
| PROFILE_RATE_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, tpa_breakpoint
) },
712 { "throttle_limit_type", VAR_UINT8
| PROFILE_RATE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_THROTTLE_LIMIT_TYPE
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, throttle_limit_type
) },
713 { "throttle_limit_percent", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 25, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, throttle_limit_percent
) },
716 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 48, 126 }, PG_SERIAL_CONFIG
, offsetof(serialConfig_t
, reboot_character
) },
717 { "serial_update_rate_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 100, 2000 }, PG_SERIAL_CONFIG
, offsetof(serialConfig_t
, serial_update_rate_hz
) },
720 { "accxy_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, accDeadband
.xy
) },
721 { "accz_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, accDeadband
.z
) },
722 { "acc_unarmedcal", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_IMU_CONFIG
, offsetof(imuConfig_t
, acc_unarmedcal
) },
723 { "imu_dcm_kp", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 32000 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, dcm_kp
) },
724 { "imu_dcm_ki", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 32000 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, dcm_ki
) },
725 { "small_angle", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 180 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, small_angle
) },
728 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 60 }, PG_ARMING_CONFIG
, offsetof(armingConfig_t
, auto_disarm_delay
) },
729 { "gyro_cal_on_first_arm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_ARMING_CONFIG
, offsetof(armingConfig_t
, gyro_cal_on_first_arm
) },
734 { "gps_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_PROVIDER
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, provider
) },
735 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_SBAS_MODE
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, sbasMode
) },
736 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, autoConfig
) },
737 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, autoBaud
) },
738 { "gps_ublox_use_galileo", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, gps_ublox_use_galileo
) },
740 #ifdef USE_GPS_RESCUE
742 { "gps_rescue_angle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, angle
) },
743 { "gps_rescue_initial_alt", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 20, 100 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, initialAltitude
) },
744 { "gps_rescue_descent_dist", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 30, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, descentDistance
) },
745 { "gps_rescue_ground_speed", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 30, 3000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, rescueGroundspeed
) },
746 { "gps_rescue_throttle_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleP
) },
747 { "gps_rescue_throttle_i", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleI
) },
748 { "gps_rescue_throttle_d", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleD
) },
749 { "gps_rescue_velocity_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velP
) },
750 { "gps_rescue_velocity_i", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velI
) },
751 { "gps_rescue_velocity_d", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velD
) },
752 { "gps_rescue_yaw_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, yawP
) },
754 { "gps_rescue_throttle_min", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleMin
) },
755 { "gps_rescue_throttle_max", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleMax
) },
756 { "gps_rescue_throttle_hover", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleHover
) },
757 { "gps_rescue_sanity_checks", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_RESCUE
}, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, sanityChecks
) },
758 { "gps_rescue_min_sats", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 50 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, minSats
) },
762 { "deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 32 }, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, deadband
) },
763 { "yaw_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, yaw_deadband
) },
764 { "yaw_control_reversed", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, yaw_control_reversed
) },
767 { "pid_process_denom", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, MAX_PID_PROCESS_DENOM
}, PG_PID_CONFIG
, offsetof(pidConfig_t
, pid_process_denom
) },
768 #ifdef USE_RUNAWAY_TAKEOFF
769 { "runaway_takeoff_prevention", VAR_UINT8
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_CONFIG
, offsetof(pidConfig_t
, runaway_takeoff_prevention
) }, // enables/disables runaway takeoff prevention
770 { "runaway_takeoff_deactivate_delay", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 100, 1000 }, PG_PID_CONFIG
, offsetof(pidConfig_t
, runaway_takeoff_deactivate_delay
) }, // deactivate time in ms
771 { "runaway_takeoff_deactivate_throttle_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_PID_CONFIG
, offsetof(pidConfig_t
, runaway_takeoff_deactivate_throttle
) }, // minimum throttle percentage during deactivation phase
775 { "dterm_lowpass_type", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_DTERM_LOWPASS_TYPE
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_filter_type
) },
776 { "dterm_lowpass_hz", VAR_INT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_lowpass_hz
) },
777 { "dterm_lowpass2_hz", VAR_INT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_lowpass2_hz
) },
778 { "dterm_notch_hz", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_notch_hz
) },
779 { "dterm_notch_cutoff", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_notch_cutoff
) },
780 { "vbat_pid_gain", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, vbatPidCompensation
) },
781 { "pid_at_min_throttle", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidAtMinThrottle
) },
782 { "anti_gravity_threshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 20, 1000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermThrottleThreshold
) },
783 { "anti_gravity_gain", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 1000, 30000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermAcceleratorGain
) },
784 { "setpoint_relax_ratio", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, setpointRelaxRatio
) },
785 { "dterm_setpoint_weight", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dtermSetpointWeight
) },
786 { "acc_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, yawRateAccelLimit
) },
787 { "acc_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, rateAccelLimit
) },
788 { "crash_dthreshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_dthreshold
) },
789 { "crash_gthreshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_gthreshold
) },
790 { "crash_setpoint_threshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_setpoint_threshold
) },
791 { "crash_time", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 5000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_time
) },
792 { "crash_delay", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_delay
) },
793 { "crash_recovery_angle", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 30 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery_angle
) },
794 { "crash_recovery_rate", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 255 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery_rate
) },
795 { "crash_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 1000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_limit_yaw
) },
796 { "crash_recovery", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CRASH_RECOVERY
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery
) },
798 { "iterm_rotation", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, iterm_rotation
) },
799 #if defined(USE_SMART_FEEDFORWARD)
800 { "smart_feedforward", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, smart_feedforward
) },
802 #if defined(USE_ITERM_RELAX)
803 { "iterm_relax", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ITERM_RELAX
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, iterm_relax
) },
805 { "iterm_relax_cutoff_low", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 1, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, iterm_relax_cutoff_low
) },
806 { "iterm_relax_cutoff_high", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 1, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, iterm_relax_cutoff_high
) },
807 { "iterm_windup", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 30, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermWindupPointPercent
) },
808 { "iterm_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermLimit
) },
809 { "pidsum_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { PIDSUM_LIMIT_MIN
, PIDSUM_LIMIT_MAX
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidSumLimit
) },
810 { "pidsum_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { PIDSUM_LIMIT_MIN
, PIDSUM_LIMIT_MAX
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidSumLimitYaw
) },
811 { "yaw_lowpass_hz", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, yaw_lowpass_hz
) },
813 #if defined(USE_THROTTLE_BOOST)
814 { "throttle_boost", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, throttle_boost
) },
815 { "throttle_boost_cutoff", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 5, 50 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, throttle_boost_cutoff
) },
818 #ifdef USE_ACRO_TRAINER
819 { "acro_trainer_angle_limit", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 10, 80 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, acro_trainer_angle_limit
) },
820 { "acro_trainer_lookahead_ms", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 10, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, acro_trainer_lookahead_ms
) },
821 { "acro_trainer_debug_axis", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ACRO_TRAINER_DEBUG
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, acro_trainer_debug_axis
) },
822 { "acro_trainer_gain", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 25, 255 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, acro_trainer_gain
) },
823 #endif // USE_ACRO_TRAINER
825 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].P
) },
826 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].I
) },
827 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].D
) },
828 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].P
) },
829 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].I
) },
830 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].D
) },
831 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].P
) },
832 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].I
) },
833 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].D
) },
835 { "p_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].P
) },
836 { "i_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].I
) },
837 { "d_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].D
) },
839 { "level_limit", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 10, 90 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, levelAngleLimit
) },
841 { "horizon_tilt_effect", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 250 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, horizon_tilt_effect
) },
842 { "horizon_tilt_expert_mode", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, horizon_tilt_expert_mode
) },
844 #if defined(USE_ABSOLUTE_CONTROL)
845 { "abs_control_gain", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 20 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, abs_control_gain
) },
846 { "abs_control_limit", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 10, 255 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, abs_control_limit
) },
847 { "abs_control_error_limit", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 1, 45 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, abs_control_error_limit
) },
851 // PG_TELEMETRY_CONFIG
853 { "tlm_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, telemetry_inverted
) },
854 { "tlm_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, halfDuplex
) },
855 #if defined(USE_TELEMETRY_FRSKY_HUB)
857 { "frsky_default_lat", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -9000, 9000 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, gpsNoFixLatitude
) },
858 { "frsky_default_long", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -18000, 18000 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, gpsNoFixLongitude
) },
859 { "frsky_gps_format", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, FRSKY_FORMAT_NMEA
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, frsky_coordinate_format
) },
860 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_UNIT
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, frsky_unit
) },
862 { "frsky_vfas_precision", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { FRSKY_VFAS_PRECISION_LOW
, FRSKY_VFAS_PRECISION_HIGH
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, frsky_vfas_precision
) },
863 #endif // USE_TELEMETRY_FRSKY_HUB
864 { "hott_alarm_int", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 120 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, hottAlarmSoundInterval
) },
865 { "pid_in_tlm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= {TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, pidValuesAsTelemetry
) },
866 { "report_cell_voltage", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, report_cell_voltage
) },
867 #if defined(USE_TELEMETRY_IBUS)
868 { "ibus_sensor", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= IBUS_SENSOR_COUNT
, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, flysky_sensors
)},
870 #endif // USE_TELEMETRY
872 // PG_LED_STRIP_CONFIG
874 { "ledstrip_visual_beeper", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_LED_STRIP_CONFIG
, offsetof(ledStripConfig_t
, ledstrip_visual_beeper
) },
875 { "ledstrip_grb_rgb", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RGB_GRB
}, PG_LED_STRIP_CONFIG
, offsetof(ledStripConfig_t
, ledstrip_grb_rgb
) },
880 { "sdcard_dma", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDCARD_CONFIG
, offsetof(sdcardConfig_t
, useDma
) },
882 #ifdef USE_SDCARD_SDIO
883 { "sdio_clk_bypass", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDIO_CONFIG
, offsetof(sdioConfig_t
, clockBypass
) },
884 { "sdio_use_cache", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDIO_CONFIG
, offsetof(sdioConfig_t
, useCache
) },
889 { "osd_units", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_UNIT
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, units
) },
891 { "osd_warn_arming_disable", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_ARMING_DISABLE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
892 { "osd_warn_batt_not_full", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_BATTERY_NOT_FULL
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
893 { "osd_warn_batt_warning", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_BATTERY_WARNING
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
894 { "osd_warn_batt_critical", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_BATTERY_CRITICAL
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
895 { "osd_warn_visual_beeper", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_VISUAL_BEEPER
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
896 { "osd_warn_crash_flip", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_CRASH_FLIP
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
897 { "osd_warn_esc_fail", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_ESC_FAIL
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
898 #ifdef USE_ADC_INTERNAL
899 { "osd_warn_core_temp", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_CORE_TEMPERATURE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
902 { "osd_rssi_alarm", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, rssi_alarm
) },
903 { "osd_cap_alarm", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 20000 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, cap_alarm
) },
904 { "osd_alt_alarm", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 10000 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, alt_alarm
) },
905 { "osd_esc_temp_alarm", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { INT8_MIN
, INT8_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, esc_temp_alarm
) },
906 { "osd_esc_rpm_alarm", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { ESC_RPM_ALARM_OFF
, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, esc_rpm_alarm
) },
907 { "osd_esc_current_alarm", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { ESC_CURRENT_ALARM_OFF
, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, esc_current_alarm
) },
908 #ifdef USE_ADC_INTERNAL
909 { "osd_core_temp_alarm", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, UINT8_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, core_temp_alarm
) },
912 { "osd_ah_max_pit", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 90 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, ahMaxPitch
) },
913 { "osd_ah_max_rol", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 90 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, ahMaxRoll
) },
915 { "osd_tim1", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, timers
[OSD_TIMER_1
]) },
916 { "osd_tim2", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, timers
[OSD_TIMER_2
]) },
918 { "osd_vbat_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_MAIN_BATT_VOLTAGE
]) },
919 { "osd_rssi_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_RSSI_VALUE
]) },
920 { "osd_tim_1_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ITEM_TIMER_1
]) },
921 { "osd_tim_2_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ITEM_TIMER_2
]) },
922 { "osd_remaining_time_estimate_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_REMAINING_TIME_ESTIMATE
]) },
923 { "osd_flymode_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_FLYMODE
]) },
924 { "osd_anti_gravity_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ANTI_GRAVITY
]) },
925 { "osd_throttle_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_THROTTLE_POS
]) },
926 { "osd_vtx_channel_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_VTX_CHANNEL
]) },
927 { "osd_crosshairs_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CROSSHAIRS
]) },
928 { "osd_ah_sbar_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_HORIZON_SIDEBARS
]) },
929 { "osd_ah_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ARTIFICIAL_HORIZON
]) },
930 { "osd_current_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CURRENT_DRAW
]) },
931 { "osd_mah_drawn_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_MAH_DRAWN
]) },
932 { "osd_craft_name_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CRAFT_NAME
]) },
933 { "osd_gps_speed_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_GPS_SPEED
]) },
934 { "osd_gps_lon_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_GPS_LON
]) },
935 { "osd_gps_lat_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_GPS_LAT
]) },
936 { "osd_gps_sats_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_GPS_SATS
]) },
937 { "osd_home_dir_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_HOME_DIR
]) },
938 { "osd_home_dist_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_HOME_DIST
]) },
939 { "osd_compass_bar_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_COMPASS_BAR
]) },
940 { "osd_altitude_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ALTITUDE
]) },
941 { "osd_pid_roll_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ROLL_PIDS
]) },
942 { "osd_pid_pitch_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_PITCH_PIDS
]) },
943 { "osd_pid_yaw_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_YAW_PIDS
]) },
944 { "osd_debug_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_DEBUG
]) },
945 { "osd_power_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_POWER
]) },
946 { "osd_pidrate_profile_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_PIDRATE_PROFILE
]) },
947 { "osd_warnings_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_WARNINGS
]) },
948 { "osd_avg_cell_voltage_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_AVG_CELL_VOLTAGE
]) },
949 { "osd_pit_ang_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_PITCH_ANGLE
]) },
950 { "osd_rol_ang_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ROLL_ANGLE
]) },
951 { "osd_battery_usage_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_MAIN_BATT_USAGE
]) },
952 { "osd_disarmed_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_DISARMED
]) },
953 { "osd_nheading_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_NUMERICAL_HEADING
]) },
954 { "osd_nvario_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_NUMERICAL_VARIO
]) },
955 { "osd_esc_tmp_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ESC_TMP
]) },
956 { "osd_esc_rpm_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ESC_RPM
]) },
957 { "osd_rtc_date_time_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_RTC_DATETIME
]) },
958 { "osd_adjustment_range_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ADJUSTMENT_RANGE
]) },
959 #ifdef USE_ADC_INTERNAL
960 { "osd_core_temp_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CORE_TEMPERATURE
]) },
963 // OSD stats enabled flags are stored as bitmapped values inside a 32bit parameter
964 // It is recommended to keep the settings order the same as the enumeration. This way the settings are displayed in the cli in the same order making it easier on the users
965 { "osd_stat_rtc_date_time", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_RTC_DATE_TIME
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
966 { "osd_stat_tim_1", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_TIMER_1
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
967 { "osd_stat_tim_2", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_TIMER_2
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
968 { "osd_stat_max_spd", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_SPEED
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
969 { "osd_stat_max_dist", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_DISTANCE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
970 { "osd_stat_min_batt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MIN_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
971 { "osd_stat_endbatt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_END_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
972 { "osd_stat_battery", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
973 { "osd_stat_min_rssi", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MIN_RSSI
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
974 { "osd_stat_max_curr", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_CURRENT
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
975 { "osd_stat_used_mah", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_USED_MAH
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
976 { "osd_stat_max_alt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_ALTITUDE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
977 { "osd_stat_bbox", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BLACKBOX
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
978 { "osd_stat_bb_no", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BLACKBOX_NUMBER
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
983 #ifndef SKIP_TASK_STATISTICS
984 { "task_statistics", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, task_statistics
) },
986 { "debug_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_DEBUG
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, debug_mode
) },
987 { "rate_6pos_switch", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, rateProfile6PosSwitch
) },
989 { "cpu_overclock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OVERCLOCK
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, cpu_overclock
) },
991 { "pwr_on_arm_grace", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 30 }, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, powerOnArmingGraceTime
) },
994 #ifdef USE_VTX_COMMON
995 { "vtx_band", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VTX_SETTINGS_NO_BAND
, VTX_SETTINGS_MAX_BAND
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, band
) },
996 { "vtx_channel", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VTX_SETTINGS_MIN_CHANNEL
, VTX_SETTINGS_MAX_CHANNEL
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, channel
) },
997 { "vtx_power", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VTX_SETTINGS_MIN_POWER
, VTX_SETTINGS_POWER_COUNT
-1 }, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, power
) },
998 { "vtx_low_power_disarm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, lowPowerDisarm
) },
999 #ifdef VTX_SETTINGS_FREQCMD
1000 { "vtx_freq", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, VTX_SETTINGS_MAX_FREQUENCY_MHZ
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, freq
) },
1001 { "vtx_pit_mode_freq", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, VTX_SETTINGS_MAX_FREQUENCY_MHZ
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, pitModeFreq
) },
1006 #if defined(USE_VTX_CONTROL) && defined(USE_VTX_COMMON)
1007 { "vtx_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_VTX_CONFIG
, offsetof(vtxConfig_t
, halfDuplex
) },
1012 { "vcd_video_system", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_VIDEO_SYSTEM
}, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, video_system
) },
1013 { "vcd_h_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -32, 31 }, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, h_offset
) },
1014 { "vcd_v_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -15, 16 }, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, v_offset
) },
1017 // PG_MAX7456_CONFIG
1019 { "max7456_clock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MAX7456_CLOCK
}, PG_MAX7456_CONFIG
, offsetof(max7456Config_t
, clockConfig
) },
1020 { "max7456_spi_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_MAX7456_CONFIG
, offsetof(max7456Config_t
, spiDevice
) },
1023 // PG_DISPLAY_PORT_MSP_CONFIG
1024 #ifdef USE_MSP_DISPLAYPORT
1025 { "displayport_msp_col_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG
, offsetof(displayPortProfile_t
, colAdjust
) },
1026 { "displayport_msp_row_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -3, 0 }, PG_DISPLAY_PORT_MSP_CONFIG
, offsetof(displayPortProfile_t
, rowAdjust
) },
1029 // PG_DISPLAY_PORT_MSP_CONFIG
1031 { "displayport_max7456_col_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -6, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, colAdjust
) },
1032 { "displayport_max7456_row_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, rowAdjust
) },
1033 { "displayport_max7456_inv", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, invert
) },
1034 { "displayport_max7456_blk", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 3 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, blackBrightness
) },
1035 { "displayport_max7456_wht", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 3 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, whiteBrightness
) },
1038 #ifdef USE_ESC_SENSOR
1039 { "esc_sensor_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_ESC_SENSOR_CONFIG
, offsetof(escSensorConfig_t
, halfDuplex
) },
1040 { "esc_sensor_current_offset", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_ESC_SENSOR_CONFIG
, offsetof(escSensorConfig_t
, offset
) },
1043 #ifdef USE_RX_FRSKY_SPI
1044 { "frsky_spi_autobind", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, autoBind
) },
1045 { "frsky_spi_tx_id", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= 2, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindTxId
) },
1046 { "frsky_spi_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -127, 127 }, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindOffset
) },
1047 { "frsky_spi_bind_hop_data", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= 50, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindHopData
) },
1048 { "frsky_x_rx_num", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 255 }, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, rxNum
) },
1049 { "frsky_spi_use_external_adc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, useExternalAdc
) },
1051 { "led_inversion", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, ((1 << STATUS_LED_NUMBER
) - 1) }, PG_STATUS_LED_CONFIG
, offsetof(statusLedConfig_t
, inversion
) },
1052 #ifdef USE_DASHBOARD
1053 { "dashboard_i2c_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2CDEV_COUNT
}, PG_DASHBOARD_CONFIG
, offsetof(dashboardConfig_t
, device
) },
1054 { "dashboard_i2c_addr", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { I2C_ADDR7_MIN
, I2C_ADDR7_MAX
}, PG_DASHBOARD_CONFIG
, offsetof(dashboardConfig_t
, address
) },
1057 // PG_CAMERA_CONTROL_CONFIG
1058 #ifdef USE_CAMERA_CONTROL
1059 { "camera_control_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CAMERA_CONTROL_MODE
}, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, mode
) },
1060 { "camera_control_ref_voltage", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 200, 400 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, refVoltage
) },
1061 { "camera_control_key_delay", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 100, 500 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, keyDelayMs
) },
1062 { "camera_control_internal_resistance", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 10, 1000 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, internalResistance
) },
1063 { "camera_control_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, inverted
) },
1066 // PG_RANGEFINDER_CONFIG
1067 #ifdef USE_RANGEFINDER
1068 { "rangefinder_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RANGEFINDER_HARDWARE
}, PG_RANGEFINDER_CONFIG
, offsetof(rangefinderConfig_t
, rangefinder_hardware
) },
1073 { "pinio_config", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= PINIO_COUNT
, PG_PINIO_CONFIG
, offsetof(pinioConfig_t
, config
) },
1075 { "pinio_box", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= PINIO_COUNT
, PG_PINIOBOX_CONFIG
, offsetof(pinioBoxConfig_t
, permanentId
) },
1080 #ifdef USE_USB_CDC_HID
1081 { "usb_hid_cdc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_USB_CONFIG
, offsetof(usbDev_t
, type
) },
1084 { "usb_msc_pin_pullup", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_USB_CONFIG
, offsetof(usbDev_t
, mscButtonUsePullup
) },
1088 { "flash_spi_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_FLASH_CONFIG
, offsetof(flashConfig_t
, spiDevice
) },
1092 const uint16_t valueTableEntryCount
= ARRAYLEN(valueTable
);
1094 void settingsBuildCheck() {
1095 BUILD_BUG_ON(LOOKUP_TABLE_COUNT
!= ARRAYLEN(lookupTables
));