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"
78 #include "pg/rx_pwm.h"
79 #include "pg/sdcard.h"
85 #include "rx/cc2500_frsky_common.h"
86 #include "rx/spektrum.h"
88 #include "sensors/acceleration.h"
89 #include "sensors/barometer.h"
90 #include "sensors/battery.h"
91 #include "sensors/boardalignment.h"
92 #include "sensors/compass.h"
93 #include "sensors/esc_sensor.h"
94 #include "sensors/gyro.h"
95 #include "sensors/rangefinder.h"
97 #include "telemetry/frsky_hub.h"
98 #include "telemetry/ibus_shared.h"
99 #include "telemetry/telemetry.h"
101 // Sensor names (used in lookup tables for *_hardware settings and in status command output)
102 // sync with accelerationSensor_e
103 const char * const lookupTableAccHardware
[] = {
104 "AUTO", "NONE", "ADXL345", "MPU6050", "MMA8452", "BMA280", "LSM303DLHC",
105 "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
109 // sync with gyroSensor_e
110 const char * const lookupTableGyroHardware
[] = {
111 "AUTO", "NONE", "MPU6050", "L3G4200D", "MPU3050", "L3GD20",
112 "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20649", "ICM20689",
116 #if defined(USE_SENSOR_NAMES) || defined(USE_BARO)
117 // sync with baroSensor_e
118 const char * const lookupTableBaroHardware
[] = {
119 "AUTO", "NONE", "BMP085", "MS5611", "BMP280", "LPS", "QMP6988"
122 #if defined(USE_SENSOR_NAMES) || defined(USE_MAG)
123 // sync with magSensor_e
124 const char * const lookupTableMagHardware
[] = {
125 "AUTO", "NONE", "HMC5883", "AK8975", "AK8963", "QMC5883"
128 #if defined(USE_SENSOR_NAMES) || defined(USE_RANGEFINDER)
129 const char * const lookupTableRangefinderHardware
[] = {
130 "NONE", "HCSR04", "TFMINI", "TF02"
134 static const char * const lookupTableOffOn
[] = {
138 static const char * const lookupTableCrashRecovery
[] = {
142 static const char * const lookupTableUnit
[] = {
146 static const char * const lookupTableAlignment
[] = {
159 static const char * const lookupTableGyro
[] = {
160 "FIRST", "SECOND", "BOTH"
165 static const char * const lookupTableGPSProvider
[] = {
169 static const char * const lookupTableGPSSBASMode
[] = {
170 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
175 static const char * const lookupTableGimbalMode
[] = {
181 static const char * const lookupTableBlackboxDevice
[] = {
182 "NONE", "SPIFLASH", "SDCARD", "SERIAL"
185 static const char * const lookupTableBlackboxMode
[] = {
186 "NORMAL", "MOTOR_TEST", "ALWAYS"
191 static const char * const lookupTableSerialRX
[] = {
209 // sync with rx_spi_protocol_e
210 static const char * const lookupTableRxSpi
[] = {
227 static const char * const lookupTableGyroHardwareLpf
[] = {
233 #ifdef USE_32K_CAPABLE_GYRO
234 static const char * const lookupTableGyro32khzHardwareLpf
[] = {
240 #ifdef USE_CAMERA_CONTROL
241 static const char * const lookupTableCameraControlMode
[] = {
248 static const char * const lookupTablePwmProtocol
[] = {
249 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
251 "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200", "PROSHOT1000"
255 static const char * const lookupTableRcInterpolation
[] = {
256 "OFF", "PRESET", "AUTO", "MANUAL"
259 static const char * const lookupTableRcInterpolationChannels
[] = {
263 static const char * const lookupTableLowpassType
[] = {
266 #if defined(USE_FIR_FILTER_DENOISE)
276 static const char * const lookupTableDtermLowpassType
[] = {
279 #if defined(USE_FIR_FILTER_DENOISE)
285 static const char * const lookupTableFailsafe
[] = {
286 "AUTO-LAND", "DROP", "GPS-RESCUE"
289 static const char * const lookupTableBusType
[] = {
290 "NONE", "I2C", "SPI", "SLAVE"
294 static const char * const lookupTableMax7456Clock
[] = {
295 "HALF", "DEFAULT", "FULL"
299 #ifdef USE_GYRO_OVERFLOW_CHECK
300 static const char * const lookupTableGyroOverflowCheck
[] = {
305 static const char * const lookupTableRatesType
[] = {
306 "BETAFLIGHT", "RACEFLIGHT"
310 static const char * const lookupOverclock
[] = {
312 #if defined(STM32F40_41xxx)
313 "192MHZ", "216MHZ", "240MHZ"
314 #elif defined(STM32F411xE)
316 #elif defined(STM32F7)
323 static const char * const lookupLedStripFormatRGB
[] = {
328 static const char * const lookupTableThrottleLimitType
[] = {
329 "OFF", "SCALE", "CLIP"
333 #ifdef USE_GPS_RESCUE
334 static const char * const lookupTableRescueSanityType
[] = {
335 "RESCUE_SANITY_OFF", "RESCUE_SANITY_ON", "RESCUE_SANITY_FS_ONLY"
340 static const char * const lookupTableVideoSystem
[] = {
341 "AUTO", "PAL", "NTSC"
343 #endif // USE_MAX7456
345 #define LOOKUP_TABLE_ENTRY(name) { name, ARRAYLEN(name) }
347 const lookupTableEntry_t lookupTables
[] = {
348 LOOKUP_TABLE_ENTRY(lookupTableOffOn
),
349 LOOKUP_TABLE_ENTRY(lookupTableUnit
),
350 LOOKUP_TABLE_ENTRY(lookupTableAlignment
),
352 LOOKUP_TABLE_ENTRY(lookupTableGPSProvider
),
353 LOOKUP_TABLE_ENTRY(lookupTableGPSSBASMode
),
354 #ifdef USE_GPS_RESCUE
355 LOOKUP_TABLE_ENTRY(lookupTableRescueSanityType
),
359 LOOKUP_TABLE_ENTRY(lookupTableBlackboxDevice
),
360 LOOKUP_TABLE_ENTRY(lookupTableBlackboxMode
),
362 LOOKUP_TABLE_ENTRY(currentMeterSourceNames
),
363 LOOKUP_TABLE_ENTRY(voltageMeterSourceNames
),
365 LOOKUP_TABLE_ENTRY(lookupTableGimbalMode
),
368 LOOKUP_TABLE_ENTRY(lookupTableSerialRX
),
371 LOOKUP_TABLE_ENTRY(lookupTableRxSpi
),
373 LOOKUP_TABLE_ENTRY(lookupTableGyroHardwareLpf
),
374 #ifdef USE_32K_CAPABLE_GYRO
375 LOOKUP_TABLE_ENTRY(lookupTableGyro32khzHardwareLpf
),
377 LOOKUP_TABLE_ENTRY(lookupTableAccHardware
),
379 LOOKUP_TABLE_ENTRY(lookupTableBaroHardware
),
382 LOOKUP_TABLE_ENTRY(lookupTableMagHardware
),
384 LOOKUP_TABLE_ENTRY(debugModeNames
),
385 LOOKUP_TABLE_ENTRY(lookupTablePwmProtocol
),
386 LOOKUP_TABLE_ENTRY(lookupTableRcInterpolation
),
387 LOOKUP_TABLE_ENTRY(lookupTableRcInterpolationChannels
),
388 LOOKUP_TABLE_ENTRY(lookupTableLowpassType
),
389 LOOKUP_TABLE_ENTRY(lookupTableDtermLowpassType
),
390 LOOKUP_TABLE_ENTRY(lookupTableFailsafe
),
391 LOOKUP_TABLE_ENTRY(lookupTableCrashRecovery
),
392 #ifdef USE_CAMERA_CONTROL
393 LOOKUP_TABLE_ENTRY(lookupTableCameraControlMode
),
395 LOOKUP_TABLE_ENTRY(lookupTableBusType
),
397 LOOKUP_TABLE_ENTRY(lookupTableMax7456Clock
),
399 #ifdef USE_RANGEFINDER
400 LOOKUP_TABLE_ENTRY(lookupTableRangefinderHardware
),
402 #ifdef USE_GYRO_OVERFLOW_CHECK
403 LOOKUP_TABLE_ENTRY(lookupTableGyroOverflowCheck
),
405 LOOKUP_TABLE_ENTRY(lookupTableRatesType
),
407 LOOKUP_TABLE_ENTRY(lookupOverclock
),
410 LOOKUP_TABLE_ENTRY(lookupLedStripFormatRGB
),
413 LOOKUP_TABLE_ENTRY(lookupTableGyro
),
415 LOOKUP_TABLE_ENTRY(lookupTableThrottleLimitType
),
417 LOOKUP_TABLE_ENTRY(lookupTableVideoSystem
),
418 #endif // USE_MAX7456
421 #undef LOOKUP_TABLE_ENTRY
423 const clivalue_t valueTable
[] = {
425 { "align_gyro", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_align
) },
426 { "gyro_hardware_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO_HARDWARE_LPF
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_hardware_lpf
) },
427 #ifdef USE_32K_CAPABLE_GYRO
428 { "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
) },
430 #if defined(USE_GYRO_SPI_ICM20649)
431 { "gyro_high_range", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_high_fsr
) },
433 { "gyro_sync_denom", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, 32 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_sync_denom
) },
435 { "gyro_lowpass_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_LOWPASS_TYPE
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass_type
) },
436 { "gyro_lowpass_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass_hz
) },
437 { "gyro_lowpass_order", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, GYRO_LPF_ORDER_MAX
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass_order
) },
439 { "gyro_lowpass2_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_LOWPASS_TYPE
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass2_type
) },
440 { "gyro_lowpass2_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass2_hz
) },
441 { "gyro_lowpass2_order", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, GYRO_LPF_ORDER_MAX
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lowpass2_order
) },
443 { "gyro_notch1_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_hz_1
) },
444 { "gyro_notch1_cutoff", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_cutoff_1
) },
445 { "gyro_notch2_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_hz_2
) },
446 { "gyro_notch2_cutoff", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_soft_notch_cutoff_2
) },
448 { "gyro_lma_depth", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= {0, 11}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lma_depth
)},
449 { "gyro_lma_weight", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= {0, 100}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_lma_weight
)},
451 { "gyro_calib_duration", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 50, 3000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyroCalibrationDuration
) },
452 { "gyro_calib_noise_limit", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyroMovementCalibrationThreshold
) },
453 { "gyro_offset_yaw", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -1000, 1000 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_offset_yaw
) },
454 #ifdef USE_GYRO_OVERFLOW_CHECK
455 { "gyro_overflow_detect", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO_OVERFLOW_CHECK
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, checkOverflow
) },
457 #ifdef USE_YAW_SPIN_RECOVERY
458 { "yaw_spin_recovery", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, yaw_spin_recovery
) },
459 { "yaw_spin_threshold", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 500, 1950 }, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, yaw_spin_threshold
) },
462 #if defined(GYRO_USES_SPI)
463 #ifdef USE_32K_CAPABLE_GYRO
464 { "gyro_use_32khz", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_use_32khz
) },
468 { "gyro_to_use", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GYRO
}, PG_GYRO_CONFIG
, offsetof(gyroConfig_t
, gyro_to_use
) },
471 // PG_ACCELEROMETER_CONFIG
472 { "align_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_align
) },
473 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ACC_HARDWARE
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_hardware
) },
474 #if defined(USE_GYRO_SPI_ICM20649)
475 { "acc_high_range", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_high_fsr
) },
477 { "acc_lpf_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 400 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, acc_lpf_hz
) },
478 { "acc_trim_pitch", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -300, 300 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accelerometerTrims
.values
.pitch
) },
479 { "acc_trim_roll", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -300, 300 }, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accelerometerTrims
.values
.roll
) },
480 { "acc_calibration", VAR_INT16
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= XYZ_AXIS_COUNT
, PG_ACCELEROMETER_CONFIG
, offsetof(accelerometerConfig_t
, accZero
.raw
) },
484 { "align_mag", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_ALIGNMENT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_align
) },
485 { "mag_bustype", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BUS_TYPE
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_bustype
) },
486 { "mag_i2c_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2CDEV_COUNT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_i2c_device
) },
487 { "mag_i2c_address", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2C_ADDR7_MAX
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_i2c_address
) },
488 { "mag_spi_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_spi_device
) },
489 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MAG_HARDWARE
}, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_hardware
) },
490 { "mag_declination", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -18000, 18000 }, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, mag_declination
) },
491 { "mag_calibration", VAR_INT16
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= XYZ_AXIS_COUNT
, PG_COMPASS_CONFIG
, offsetof(compassConfig_t
, magZero
.raw
) },
494 // PG_BAROMETER_CONFIG
496 { "baro_bustype", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BUS_TYPE
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_bustype
) },
497 { "baro_spi_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 5 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_spi_device
) },
498 { "baro_i2c_device", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 5 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_i2c_device
) },
499 { "baro_i2c_address", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2C_ADDR7_MAX
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_i2c_address
) },
500 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BARO_HARDWARE
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_hardware
) },
501 { "baro_tab_size", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, BARO_SAMPLE_COUNT_MAX
}, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_sample_count
) },
502 { "baro_noise_lpf", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_noise_lpf
) },
503 { "baro_cf_vel", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_cf_vel
) },
504 { "baro_cf_alt", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 1000 }, PG_BAROMETER_CONFIG
, offsetof(barometerConfig_t
, baro_cf_alt
) },
508 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1200, 1700 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, midrc
) },
509 { "min_check", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, mincheck
) },
510 { "max_check", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, maxcheck
) },
511 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_channel
) },
512 { "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
) },
513 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { RSSI_SCALE_MIN
, RSSI_SCALE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_scale
) },
514 { "rssi_invert", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rssi_invert
) },
515 { "rc_interp", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_INTERPOLATION
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolation
) },
516 { "rc_interp_ch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RC_INTERPOLATION_CHANNELS
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolationChannels
) },
517 { "rc_interp_int", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, 50 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, rcInterpolationInterval
) },
518 { "fpv_mix_degrees", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 50 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, fpvCamAngleDegrees
) },
519 { "max_aux_channels", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, MAX_AUX_CHANNEL_COUNT
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, max_aux_channel
) },
521 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_SERIAL_RX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, serialrx_provider
) },
522 { "serialrx_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, serialrx_inverted
) },
524 #ifdef USE_SPEKTRUM_BIND
525 { "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
) },
526 { "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
) },
528 { "airmode_start_throttle_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_RX_CONFIG
, offsetof(rxConfig_t
, airModeActivateThreshold
) },
529 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rx_min_usec
) },
530 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rx_max_usec
) },
531 { "serialrx_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, halfDuplex
) },
533 { "rx_spi_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RX_SPI
}, PG_RX_CONFIG
, offsetof(rxConfig_t
, rx_spi_protocol
) },
538 { "adc_device", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { 0, ADCDEV_COUNT
}, PG_ADC_CONFIG
, offsetof(adcConfig_t
, device
) },
543 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PWM_CONFIG
, offsetof(pwmConfig_t
, inputFilteringMode
) },
546 // PG_BLACKBOX_CONFIG
548 { "blackbox_p_ratio", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, p_ratio
) },
549 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BLACKBOX_DEVICE
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, device
) },
550 { "blackbox_record_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, record_acc
) },
551 { "blackbox_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_BLACKBOX_MODE
}, PG_BLACKBOX_CONFIG
, offsetof(blackboxConfig_t
, mode
) },
555 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, minthrottle
) },
556 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, maxthrottle
) },
557 { "min_command", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, mincommand
) },
559 { "dshot_idle_value", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 2000 }, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, digitalIdleOffsetValue
) },
560 #ifdef USE_DSHOT_DMAR
561 { "dshot_burst", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.useBurstDshot
) },
564 { "use_unsynced_pwm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.useUnsyncedPwm
) },
565 { "motor_pwm_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MOTOR_PWM_PROTOCOL
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmProtocol
) },
566 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 200, 32000 }, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmRate
) },
567 { "motor_pwm_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, dev
.motorPwmInversion
) },
568 { "motor_poles", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 4, UINT8_MAX
}, PG_MOTOR_CONFIG
, offsetof(motorConfig_t
, motorPoleCount
) },
570 // PG_THROTTLE_CORRECTION_CONFIG
571 { "thr_corr_value", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 150 }, PG_THROTTLE_CORRECTION_CONFIG
, offsetof(throttleCorrectionConfig_t
, throttle_correction_value
) },
572 { "thr_corr_angle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1, 900 }, PG_THROTTLE_CORRECTION_CONFIG
, offsetof(throttleCorrectionConfig_t
, throttle_correction_angle
) },
574 // PG_FAILSAFE_CONFIG
575 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_delay
) },
576 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_off_delay
) },
577 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_throttle
) },
578 { "failsafe_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_kill_switch
) },
579 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 300 }, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_throttle_low_delay
) },
580 { "failsafe_procedure", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_FAILSAFE
}, PG_FAILSAFE_CONFIG
, offsetof(failsafeConfig_t
, failsafe_procedure
) },
582 // PG_BOARDALIGNMENT_CONFIG
583 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, rollDegrees
) },
584 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, pitchDegrees
) },
585 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -180, 360 }, PG_BOARD_ALIGNMENT
, offsetof(boardAlignment_t
, yawDegrees
) },
589 { "gimbal_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GIMBAL_MODE
}, PG_GIMBAL_CONFIG
, offsetof(gimbalConfig_t
, mode
) },
593 { "bat_capacity", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 20000 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, batteryCapacity
) },
594 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatmaxcellvoltage
) },
595 { "vbat_full_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatfullcellvoltage
) },
596 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatmincellvoltage
) },
597 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 10, 50 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatwarningcellvoltage
) },
598 { "vbat_hysteresis", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 250 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbathysteresis
) },
599 { "current_meter", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CURRENT_METER
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, currentMeterSource
) },
600 { "battery_meter", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_VOLTAGE_METER
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, voltageMeterSource
) },
601 { "vbat_detect_cell_voltage", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, vbatnotpresentcellvoltage
) },
602 { "use_vbat_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, useVBatAlerts
) },
603 { "use_cbat_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, useConsumptionAlerts
) },
604 { "cbat_alert_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, consumptionWarningPercentage
) },
605 { "vbat_cutoff_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_BATTERY_CONFIG
, offsetof(batteryConfig_t
, lvcPercentage
) },
607 // PG_VOLTAGE_SENSOR_ADC_CONFIG
608 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_SCALE_MIN
, VBAT_SCALE_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatscale
) },
609 { "vbat_divider", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_DIVIDER_MIN
, VBAT_DIVIDER_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatresdivval
) },
610 { "vbat_multiplier", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VBAT_MULTIPLIER_MIN
, VBAT_MULTIPLIER_MAX
}, PG_VOLTAGE_SENSOR_ADC_CONFIG
, offsetof(voltageSensorADCConfig_t
, vbatresdivmultiplier
) },
612 // PG_CURRENT_SENSOR_ADC_CONFIG
613 { "ibata_scale", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG
, offsetof(currentSensorADCConfig_t
, scale
) },
614 { "ibata_offset", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -32000, 32000 }, PG_CURRENT_SENSOR_ADC_CONFIG
, offsetof(currentSensorADCConfig_t
, offset
) },
615 // PG_CURRENT_SENSOR_ADC_CONFIG
616 #ifdef USE_VIRTUAL_CURRENT_METER
617 { "ibatv_scale", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG
, offsetof(currentSensorVirtualConfig_t
, scale
) },
618 { "ibatv_offset", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG
, offsetof(currentSensorVirtualConfig_t
, offset
) },
622 // PG_BEEPER_DEV_CONFIG
623 { "beeper_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, isInverted
) },
624 { "beeper_od", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, isOpenDrain
) },
625 { "beeper_frequency", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { 0, 16000 }, PG_BEEPER_DEV_CONFIG
, offsetof(beeperDevConfig_t
, frequency
) },
629 { "beeper_dshot_beacon_tone", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= {0, DSHOT_CMD_BEACON5
}, PG_BEEPER_CONFIG
, offsetof(beeperConfig_t
, dshotBeaconTone
) },
634 { "yaw_motors_reversed", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MIXER_CONFIG
, offsetof(mixerConfig_t
, yaw_motors_reversed
) },
635 { "crashflip_motor_percent", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_MIXER_CONFIG
, offsetof(mixerConfig_t
, crashflip_motor_percent
) },
637 // PG_MOTOR_3D_CONFIG
638 { "3d_deadband_low", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_RANGE_MIDDLE
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_low
) },
639 { "3d_deadband_high", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_RANGE_MIDDLE
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_high
) },
640 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, neutral3d
) },
641 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, deadband3d_throttle
) },
642 { "3d_limit_low", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_RANGE_MIDDLE
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, limit3d_low
) },
643 { "3d_limit_high", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_RANGE_MIDDLE
, PWM_PULSE_MAX
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, limit3d_high
) },
644 { "3d_switched_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_MOTOR_3D_CONFIG
, offsetof(flight3DConfig_t
, switched_mode3d
) },
648 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, dev
.servoCenterPulse
) },
649 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 50, 498 }, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, dev
.servoPwmRate
) },
650 { "servo_lowpass_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 400}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, servo_lowpass_freq
) },
651 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, tri_unarmed_servo
) },
652 { "channel_forwarding_start", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { AUX1
, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, PG_SERVO_CONFIG
, offsetof(servoConfig_t
, channelForwardingStartChannel
) },
655 // PG_CONTROLRATE_PROFILES
656 { "thr_mid", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, thrMid8
) },
657 { "thr_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, thrExpo8
) },
658 { "rates_type", VAR_UINT8
| PROFILE_RATE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RATES_TYPE
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, rates_type
) },
659 { "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
]) },
660 { "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
]) },
661 { "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
]) },
662 { "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
]) },
663 { "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
]) },
664 { "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
]) },
665 { "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
]) },
666 { "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
]) },
667 { "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
]) },
668 { "tpa_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_TPA_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, dynThrPID
) },
669 { "tpa_breakpoint", VAR_UINT16
| PROFILE_RATE_VALUE
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, tpa_breakpoint
) },
670 { "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
) },
671 { "throttle_limit_percent", VAR_UINT8
| PROFILE_RATE_VALUE
, .config
.minmax
= { 25, 100 }, PG_CONTROL_RATE_PROFILES
, offsetof(controlRateConfig_t
, throttle_limit_percent
) },
674 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 48, 126 }, PG_SERIAL_CONFIG
, offsetof(serialConfig_t
, reboot_character
) },
675 { "serial_update_rate_hz", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 100, 2000 }, PG_SERIAL_CONFIG
, offsetof(serialConfig_t
, serial_update_rate_hz
) },
678 { "accxy_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, accDeadband
.xy
) },
679 { "accz_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, accDeadband
.z
) },
680 { "acc_unarmedcal", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_IMU_CONFIG
, offsetof(imuConfig_t
, acc_unarmedcal
) },
681 { "imu_dcm_kp", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 32000 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, dcm_kp
) },
682 { "imu_dcm_ki", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 32000 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, dcm_ki
) },
683 { "small_angle", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 180 }, PG_IMU_CONFIG
, offsetof(imuConfig_t
, small_angle
) },
686 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 60 }, PG_ARMING_CONFIG
, offsetof(armingConfig_t
, auto_disarm_delay
) },
687 { "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
) },
692 { "gps_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_PROVIDER
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, provider
) },
693 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_SBAS_MODE
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, sbasMode
) },
694 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, autoConfig
) },
695 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_GPS_CONFIG
, offsetof(gpsConfig_t
, autoBaud
) },
697 #ifdef USE_GPS_RESCUE
699 { "gps_rescue_angle", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 200 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, angle
) },
700 { "gps_rescue_initial_alt", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 20, 100 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, initialAltitude
) },
701 { "gps_rescue_descent_dist", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 30, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, descentDistance
) },
702 { "gps_rescue_ground_speed", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 30, 3000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, rescueGroundspeed
) },
703 { "gps_rescue_throttle_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleP
) },
704 { "gps_rescue_throttle_i", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleI
) },
705 { "gps_rescue_throttle_d", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleD
) },
706 { "gps_rescue_velocity_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velP
) },
707 { "gps_rescue_velocity_i", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velI
) },
708 { "gps_rescue_velocity_d", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, velD
) },
709 { "gps_rescue_yaw_p", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 500 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, yawP
) },
711 { "gps_rescue_throttle_min", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleMin
) },
712 { "gps_rescue_throttle_max", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleMax
) },
713 { "gps_rescue_throttle_hover", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 1000, 2000 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, throttleHover
) },
714 { "gps_rescue_sanity_checks", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_GPS_RESCUE
}, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, sanityChecks
) },
715 { "gps_rescue_min_sats", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 50 }, PG_GPS_RESCUE
, offsetof(gpsRescueConfig_t
, minSats
) },
719 { "deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 32 }, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, deadband
) },
720 { "yaw_deadband", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, yaw_deadband
) },
721 { "yaw_control_reversed", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RC_CONTROLS_CONFIG
, offsetof(rcControlsConfig_t
, yaw_control_reversed
) },
724 { "pid_process_denom", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 1, MAX_PID_PROCESS_DENOM
}, PG_PID_CONFIG
, offsetof(pidConfig_t
, pid_process_denom
) },
725 #ifdef USE_RUNAWAY_TAKEOFF
726 { "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
727 { "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
728 { "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
732 { "dterm_lowpass_type", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_DTERM_LOWPASS_TYPE
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_filter_type
) },
733 { "dterm_lowpass_hz", VAR_INT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_lowpass_hz
) },
734 { "dterm_lowpass2_hz", VAR_INT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_lowpass2_hz
) },
735 { "dterm_notch_hz", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_notch_hz
) },
736 { "dterm_notch_cutoff", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 16000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dterm_notch_cutoff
) },
737 { "vbat_pid_gain", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, vbatPidCompensation
) },
738 { "pid_at_min_throttle", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidAtMinThrottle
) },
739 { "anti_gravity_threshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 20, 1000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermThrottleThreshold
) },
740 { "anti_gravity_gain", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 1000, 30000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermAcceleratorGain
) },
741 { "setpoint_relax_ratio", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, setpointRelaxRatio
) },
742 { "dterm_setpoint_weight", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, dtermSetpointWeight
) },
743 { "acc_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, yawRateAccelLimit
) },
744 { "acc_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, rateAccelLimit
) },
745 { "crash_dthreshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_dthreshold
) },
746 { "crash_gthreshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_gthreshold
) },
747 { "crash_setpoint_threshold", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 2000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_setpoint_threshold
) },
748 { "crash_time", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 5000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_time
) },
749 { "crash_delay", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_delay
) },
750 { "crash_recovery_angle", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 30 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery_angle
) },
751 { "crash_recovery_rate", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 255 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery_rate
) },
752 { "crash_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 1000 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_limit_yaw
) },
753 { "crash_recovery", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CRASH_RECOVERY
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, crash_recovery
) },
755 { "iterm_rotation", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, iterm_rotation
) },
756 { "iterm_windup", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 30, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermWindupPointPercent
) },
757 { "iterm_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, itermLimit
) },
758 { "pidsum_limit", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { PIDSUM_LIMIT_MIN
, PIDSUM_LIMIT_MAX
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidSumLimit
) },
759 { "pidsum_limit_yaw", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { PIDSUM_LIMIT_MIN
, PIDSUM_LIMIT_MAX
}, PG_PID_PROFILE
, offsetof(pidProfile_t
, pidSumLimitYaw
) },
760 { "yaw_lowpass_hz", VAR_UINT16
| PROFILE_VALUE
, .config
.minmax
= { 0, 500 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, yaw_lowpass_hz
) },
762 { "throttle_boost", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 100 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, throttle_boost
) },
763 { "throttle_boost_cutoff", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 5, 50 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, throttle_boost_cutoff
) },
765 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].P
) },
766 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].I
) },
767 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_PITCH
].D
) },
768 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].P
) },
769 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].I
) },
770 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_ROLL
].D
) },
771 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].P
) },
772 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].I
) },
773 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_YAW
].D
) },
775 { "p_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].P
) },
776 { "i_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].I
) },
777 { "d_level", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 200 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, pid
[PID_LEVEL
].D
) },
779 { "level_limit", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 10, 90 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, levelAngleLimit
) },
781 { "horizon_tilt_effect", VAR_UINT8
| PROFILE_VALUE
, .config
.minmax
= { 0, 250 }, PG_PID_PROFILE
, offsetof(pidProfile_t
, horizon_tilt_effect
) },
782 { "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
) },
784 // PG_TELEMETRY_CONFIG
786 { "tlm_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, telemetry_inverted
) },
787 { "tlm_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, halfDuplex
) },
788 #if defined(USE_TELEMETRY_FRSKY_HUB)
790 { "frsky_default_lat", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -9000, 9000 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, gpsNoFixLatitude
) },
791 { "frsky_default_long", VAR_INT16
| MASTER_VALUE
, .config
.minmax
= { -18000, 18000 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, gpsNoFixLongitude
) },
792 { "frsky_gps_format", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, FRSKY_FORMAT_NMEA
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, frsky_coordinate_format
) },
793 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_UNIT
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, frsky_unit
) },
795 { "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
) },
796 #endif // USE_TELEMETRY_FRSKY_HUB
797 { "hott_alarm_int", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 120 }, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, hottAlarmSoundInterval
) },
798 { "pid_in_tlm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= {TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, pidValuesAsTelemetry
) },
799 { "report_cell_voltage", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, report_cell_voltage
) },
800 #if defined(USE_TELEMETRY_IBUS)
801 { "ibus_sensor", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= IBUS_SENSOR_COUNT
, PG_TELEMETRY_CONFIG
, offsetof(telemetryConfig_t
, flysky_sensors
)},
803 #endif // USE_TELEMETRY
805 // PG_LED_STRIP_CONFIG
807 { "ledstrip_visual_beeper", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_LED_STRIP_CONFIG
, offsetof(ledStripConfig_t
, ledstrip_visual_beeper
) },
808 { "ledstrip_grb_rgb", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RGB_GRB
}, PG_LED_STRIP_CONFIG
, offsetof(ledStripConfig_t
, ledstrip_grb_rgb
) },
813 { "sdcard_dma", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDCARD_CONFIG
, offsetof(sdcardConfig_t
, useDma
) },
815 #ifdef USE_SDCARD_SDIO
816 { "sdio_clk_bypass", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDIO_CONFIG
, offsetof(sdioConfig_t
, clockBypass
) },
817 { "sdio_use_cache", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SDIO_CONFIG
, offsetof(sdioConfig_t
, useCache
) },
822 { "osd_units", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_UNIT
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, units
) },
824 { "osd_warn_arming_disable", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_ARMING_DISABLE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
825 { "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
)},
826 { "osd_warn_batt_warning", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_BATTERY_WARNING
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
827 { "osd_warn_batt_critical", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_BATTERY_CRITICAL
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
828 { "osd_warn_visual_beeper", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_VISUAL_BEEPER
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
829 { "osd_warn_crash_flip", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_CRASH_FLIP
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
830 { "osd_warn_esc_fail", VAR_UINT16
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_WARNING_ESC_FAIL
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabledWarnings
)},
832 { "osd_rssi_alarm", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 100 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, rssi_alarm
) },
833 { "osd_cap_alarm", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 20000 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, cap_alarm
) },
834 { "osd_alt_alarm", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, 10000 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, alt_alarm
) },
835 { "osd_esc_temp_alarm", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { INT8_MIN
, INT8_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, esc_temp_alarm
) },
836 { "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
) },
837 { "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
) },
839 { "osd_ah_max_pit", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 90 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, ahMaxPitch
) },
840 { "osd_ah_max_rol", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 90 }, PG_OSD_CONFIG
, offsetof(osdConfig_t
, ahMaxRoll
) },
842 { "osd_tim1", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, timers
[OSD_TIMER_1
]) },
843 { "osd_tim2", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, INT16_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, timers
[OSD_TIMER_2
]) },
845 { "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
]) },
846 { "osd_rssi_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_RSSI_VALUE
]) },
847 { "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
]) },
848 { "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
]) },
849 { "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
]) },
850 { "osd_flymode_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_FLYMODE
]) },
851 { "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
]) },
852 { "osd_throttle_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_THROTTLE_POS
]) },
853 { "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
]) },
854 { "osd_crosshairs_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CROSSHAIRS
]) },
855 { "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
]) },
856 { "osd_ah_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ARTIFICIAL_HORIZON
]) },
857 { "osd_current_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_CURRENT_DRAW
]) },
858 { "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
]) },
859 { "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
]) },
860 { "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
]) },
861 { "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
]) },
862 { "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
]) },
863 { "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
]) },
864 { "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
]) },
865 { "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
]) },
866 { "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
]) },
867 { "osd_altitude_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_ALTITUDE
]) },
868 { "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
]) },
869 { "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
]) },
870 { "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
]) },
871 { "osd_debug_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_DEBUG
]) },
872 { "osd_power_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_POWER
]) },
873 { "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
]) },
874 { "osd_warnings_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_WARNINGS
]) },
875 { "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
]) },
876 { "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
]) },
877 { "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
]) },
878 { "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
]) },
879 { "osd_disarmed_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_DISARMED
]) },
880 { "osd_nheading_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_NUMERICAL_HEADING
]) },
881 { "osd_nvario_pos", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, OSD_POSCFG_MAX
}, PG_OSD_CONFIG
, offsetof(osdConfig_t
, item_pos
[OSD_NUMERICAL_VARIO
]) },
882 { "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
]) },
883 { "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
]) },
884 { "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
]) },
885 { "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
]) },
886 { "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
]) },
888 // OSD stats enabled flags are stored as bitmapped values inside a 32bit parameter
889 // 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
890 { "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
)},
891 { "osd_stat_tim_1", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_TIMER_1
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
892 { "osd_stat_tim_2", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_TIMER_2
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
893 { "osd_stat_max_spd", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_SPEED
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
894 { "osd_stat_max_dist", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_DISTANCE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
895 { "osd_stat_min_batt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MIN_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
896 { "osd_stat_endbatt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_END_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
897 { "osd_stat_battery", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BATTERY
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
898 { "osd_stat_min_rssi", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MIN_RSSI
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
899 { "osd_stat_max_curr", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_CURRENT
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
900 { "osd_stat_used_mah", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_USED_MAH
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
901 { "osd_stat_max_alt", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_MAX_ALTITUDE
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
902 { "osd_stat_bbox", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BLACKBOX
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
903 { "osd_stat_bb_no", VAR_UINT32
| MASTER_VALUE
| MODE_BITSET
, .config
.bitpos
= OSD_STAT_BLACKBOX_NUMBER
, PG_OSD_CONFIG
, offsetof(osdConfig_t
, enabled_stats
)},
908 #ifndef SKIP_TASK_STATISTICS
909 { "task_statistics", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, task_statistics
) },
911 { "debug_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_DEBUG
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, debug_mode
) },
912 { "rate_6pos_switch", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, rateProfile6PosSwitch
) },
914 { "cpu_overclock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OVERCLOCK
}, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, cpu_overclock
) },
916 { "pwr_on_arm_grace", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 30 }, PG_SYSTEM_CONFIG
, offsetof(systemConfig_t
, powerOnArmingGraceTime
) },
919 #ifdef USE_VTX_COMMON
920 { "vtx_band", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VTX_SETTINGS_NO_BAND
, VTX_SETTINGS_MAX_BAND
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, band
) },
921 { "vtx_channel", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { VTX_SETTINGS_MIN_CHANNEL
, VTX_SETTINGS_MAX_CHANNEL
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, channel
) },
922 { "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
) },
923 { "vtx_low_power_disarm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, lowPowerDisarm
) },
924 #ifdef VTX_SETTINGS_FREQCMD
925 { "vtx_freq", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, VTX_SETTINGS_MAX_FREQUENCY_MHZ
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, freq
) },
926 { "vtx_pit_mode_freq", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 0, VTX_SETTINGS_MAX_FREQUENCY_MHZ
}, PG_VTX_SETTINGS_CONFIG
, offsetof(vtxSettingsConfig_t
, pitModeFreq
) },
931 #if defined(USE_VTX_CONTROL) && defined(USE_VTX_COMMON)
932 { "vtx_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_VTX_CONFIG
, offsetof(vtxConfig_t
, halfDuplex
) },
937 { "vcd_video_system", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_VIDEO_SYSTEM
}, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, video_system
) },
938 { "vcd_h_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -32, 31 }, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, h_offset
) },
939 { "vcd_v_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -15, 16 }, PG_VCD_CONFIG
, offsetof(vcdProfile_t
, v_offset
) },
944 { "max7456_clock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_MAX7456_CLOCK
}, PG_MAX7456_CONFIG
, offsetof(max7456Config_t
, clockConfig
) },
945 { "max7456_spi_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_MAX7456_CONFIG
, offsetof(max7456Config_t
, spiDevice
) },
948 // PG_DISPLAY_PORT_MSP_CONFIG
949 #ifdef USE_MSP_DISPLAYPORT
950 { "displayport_msp_col_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG
, offsetof(displayPortProfile_t
, colAdjust
) },
951 { "displayport_msp_row_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -3, 0 }, PG_DISPLAY_PORT_MSP_CONFIG
, offsetof(displayPortProfile_t
, rowAdjust
) },
954 // PG_DISPLAY_PORT_MSP_CONFIG
956 { "displayport_max7456_col_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -6, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, colAdjust
) },
957 { "displayport_max7456_row_adjust", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, rowAdjust
) },
958 { "displayport_max7456_inv", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, invert
) },
959 { "displayport_max7456_blk", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 3 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, blackBrightness
) },
960 { "displayport_max7456_wht", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 3 }, PG_DISPLAY_PORT_MAX7456_CONFIG
, offsetof(displayPortProfile_t
, whiteBrightness
) },
963 #ifdef USE_ESC_SENSOR
964 { "esc_sensor_halfduplex", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_ESC_SENSOR_CONFIG
, offsetof(escSensorConfig_t
, halfDuplex
) },
967 #ifdef USE_RX_FRSKY_SPI
968 { "frsky_spi_autobind", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, autoBind
) },
969 { "frsky_spi_tx_id", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= 2, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindTxId
) },
970 { "frsky_spi_offset", VAR_INT8
| MASTER_VALUE
, .config
.minmax
= { -127, 127 }, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindOffset
) },
971 { "frsky_spi_bind_hop_data", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= 50, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, bindHopData
) },
972 { "frsky_x_rx_num", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, 255 }, PG_RX_FRSKY_SPI_CONFIG
, offsetof(rxFrSkySpiConfig_t
, rxNum
) },
973 { "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
) },
975 { "led_inversion", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, ((1 << STATUS_LED_NUMBER
) - 1) }, PG_STATUS_LED_CONFIG
, offsetof(statusLedConfig_t
, inversion
) },
977 { "dashboard_i2c_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, I2CDEV_COUNT
}, PG_DASHBOARD_CONFIG
, offsetof(dashboardConfig_t
, device
) },
978 { "dashboard_i2c_addr", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { I2C_ADDR7_MIN
, I2C_ADDR7_MAX
}, PG_DASHBOARD_CONFIG
, offsetof(dashboardConfig_t
, address
) },
981 // PG_CAMERA_CONTROL_CONFIG
982 #ifdef USE_CAMERA_CONTROL
983 { "camera_control_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_CAMERA_CONTROL_MODE
}, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, mode
) },
984 { "camera_control_ref_voltage", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 200, 400 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, refVoltage
) },
985 { "camera_control_key_delay", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 100, 500 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, keyDelayMs
) },
986 { "camera_control_internal_resistance", VAR_UINT16
| MASTER_VALUE
, .config
.minmax
= { 10, 1000 }, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, internalResistance
) },
987 { "camera_control_inverted", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_CAMERA_CONTROL_CONFIG
, offsetof(cameraControlConfig_t
, inverted
) },
990 // PG_RANGEFINDER_CONFIG
991 #ifdef USE_RANGEFINDER
992 { "rangefinder_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_RANGEFINDER_HARDWARE
}, PG_RANGEFINDER_CONFIG
, offsetof(rangefinderConfig_t
, rangefinder_hardware
) },
997 { "pinio_config", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= PINIO_COUNT
, PG_PINIO_CONFIG
, offsetof(pinioConfig_t
, config
) },
999 { "pinio_box", VAR_UINT8
| MASTER_VALUE
| MODE_ARRAY
, .config
.array
.length
= PINIO_COUNT
, PG_PINIOBOX_CONFIG
, offsetof(pinioBoxConfig_t
, permanentId
) },
1004 #ifdef USE_USB_CDC_HID
1005 { "usb_hid_cdc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_USB_CONFIG
, offsetof(usbDev_t
, type
) },
1008 { "usb_msc_pin_pullup", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, .config
.lookup
= { TABLE_OFF_ON
}, PG_USB_CONFIG
, offsetof(usbDev_t
, mscButtonUsePullup
) },
1012 { "flash_spi_bus", VAR_UINT8
| MASTER_VALUE
, .config
.minmax
= { 0, SPIDEV_COUNT
}, PG_FLASH_CONFIG
, offsetof(flashConfig_t
, spiDevice
) },
1016 const uint16_t valueTableEntryCount
= ARRAYLEN(valueTable
);
1018 void settingsBuildCheck() {
1019 BUILD_BUG_ON(LOOKUP_TABLE_COUNT
!= ARRAYLEN(lookupTables
));