CF/BF - Fix HoTT telemetry.
[betaflight.git] / src / main / fc / cli.c
blobce54866dd65fc8e9c7778277d3639b3bfb71708c
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <stdarg.h>
22 #include <string.h>
23 #include <math.h>
24 #include <ctype.h>
26 #include "platform.h"
28 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
29 // signal that we're in cli mode
30 uint8_t cliMode = 0;
31 extern uint8_t __config_start; // configured via linker script when building binaries.
32 extern uint8_t __config_end;
34 #ifdef USE_CLI
36 #include "blackbox/blackbox.h"
38 #include "build/build_config.h"
39 #include "build/debug.h"
40 #include "build/version.h"
42 #include "cms/cms.h"
44 #include "common/axis.h"
45 #include "common/color.h"
46 #include "common/maths.h"
47 #include "common/printf.h"
48 #include "common/typeconversion.h"
49 #include "common/utils.h"
51 #include "config/config_eeprom.h"
52 #include "config/feature.h"
53 #include "config/parameter_group.h"
54 #include "config/parameter_group_ids.h"
56 #include "drivers/accgyro.h"
57 #include "drivers/buf_writer.h"
58 #include "drivers/bus_i2c.h"
59 #include "drivers/compass.h"
60 #include "drivers/display.h"
61 #include "drivers/dma.h"
62 #include "drivers/flash.h"
63 #include "drivers/io.h"
64 #include "drivers/io_impl.h"
65 #include "drivers/rx_pwm.h"
66 #include "drivers/sdcard.h"
67 #include "drivers/sensor.h"
68 #include "drivers/serial.h"
69 #include "drivers/serial_escserial.h"
70 #include "drivers/sonar_hcsr04.h"
71 #include "drivers/stack_check.h"
72 #include "drivers/system.h"
73 #include "drivers/timer.h"
74 #include "drivers/vcd.h"
76 #include "fc/cli.h"
77 #include "fc/config.h"
78 #include "fc/controlrate_profile.h"
79 #include "fc/fc_core.h"
80 #include "fc/rc_adjustments.h"
81 #include "fc/rc_controls.h"
82 #include "fc/runtime_config.h"
83 #include "fc/fc_msp.h"
85 #include "flight/altitude.h"
86 #include "flight/failsafe.h"
87 #include "flight/imu.h"
88 #include "flight/mixer.h"
89 #include "flight/navigation.h"
90 #include "flight/pid.h"
91 #include "flight/servos.h"
93 #include "io/asyncfatfs/asyncfatfs.h"
94 #include "io/beeper.h"
95 #include "io/flashfs.h"
96 #include "io/displayport_max7456.h"
97 #include "io/displayport_msp.h"
98 #include "io/gimbal.h"
99 #include "io/gps.h"
100 #include "io/ledstrip.h"
101 #include "io/osd.h"
102 #include "io/serial.h"
103 #include "io/vtx_rtc6705.h"
104 #include "io/vtx_control.h"
106 #include "rx/rx.h"
107 #include "rx/spektrum.h"
109 #include "scheduler/scheduler.h"
111 #include "sensors/acceleration.h"
112 #include "sensors/barometer.h"
113 #include "sensors/battery.h"
114 #include "sensors/boardalignment.h"
115 #include "sensors/compass.h"
116 #include "sensors/gyro.h"
117 #include "sensors/sensors.h"
119 #include "telemetry/frsky.h"
120 #include "telemetry/telemetry.h"
123 static serialPort_t *cliPort;
124 static bufWriter_t *cliWriter;
125 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 128];
127 static char cliBuffer[64];
128 static uint32_t bufferIndex = 0;
130 static const char* const emptyName = "-";
132 #ifndef USE_QUAD_MIXER_ONLY
133 // sync this with mixerMode_e
134 static const char * const mixerNames[] = {
135 "TRI", "QUADP", "QUADX", "BI",
136 "GIMBAL", "Y6", "HEX6",
137 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
138 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
139 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
140 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
142 #endif
144 // sync this with features_e
145 static const char * const featureNames[] = {
146 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
147 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
148 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
149 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
150 "UNUSED", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
151 "SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_SENSOR", "ANTI_GRAVITY", NULL
154 // sync this with rxFailsafeChannelMode_e
155 static const char rxFailsafeModeCharacters[] = "ahs";
157 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
158 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
159 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
162 // sync this with accelerationSensor_e
163 static const char * const lookupTableAccHardware[] = {
164 "AUTO",
165 "NONE",
166 "ADXL345",
167 "MPU6050",
168 "MMA8452",
169 "BMA280",
170 "LSM303DLHC",
171 "MPU6000",
172 "MPU6500",
173 "MPU9250",
174 "ICM20601",
175 "ICM20602",
176 "ICM20608",
177 "ICM20689",
178 "BMI160",
179 "FAKE"
182 #ifdef BARO
183 // sync this with baroSensor_e
184 static const char * const lookupTableBaroHardware[] = {
185 "AUTO",
186 "NONE",
187 "BMP085",
188 "MS5611",
189 "BMP280"
191 #endif
193 #ifdef MAG
194 // sync this with magSensor_e
195 static const char * const lookupTableMagHardware[] = {
196 "AUTO",
197 "NONE",
198 "HMC5883",
199 "AK8975",
200 "AK8963"
202 #endif
204 #if defined(USE_SENSOR_NAMES)
205 // sync this with sensors_e
206 static const char * const sensorTypeNames[] = {
207 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
210 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
212 static const char * const sensorHardwareNames[4][16] = {
213 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20689", "BMI160", "FAKE", NULL },
214 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "MPU9250", "ICM20601", "ICM20602", "ICM20608G", "ICM20689", "BMI160", "FAKE", NULL },
215 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
216 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
218 #endif /* USE_SENSOR_NAMES */
220 static const char * const lookupTableOffOn[] = {
221 "OFF", "ON"
224 static const char * const lookupTableUnit[] = {
225 "IMPERIAL", "METRIC"
228 static const char * const lookupTableAlignment[] = {
229 "DEFAULT",
230 "CW0",
231 "CW90",
232 "CW180",
233 "CW270",
234 "CW0FLIP",
235 "CW90FLIP",
236 "CW180FLIP",
237 "CW270FLIP"
240 #ifdef GPS
241 static const char * const lookupTableGPSProvider[] = {
242 "NMEA", "UBLOX"
245 static const char * const lookupTableGPSSBASMode[] = {
246 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
248 #endif
250 static const char * const lookupTableCurrentSensor[] = {
251 "NONE", "ADC", "VIRTUAL", "ESC"
254 static const char * const lookupTableBatterySensor[] = {
255 "NONE", "ADC", "ESC"
258 #ifdef USE_SERVOS
259 static const char * const lookupTableGimbalMode[] = {
260 "NORMAL", "MIXTILT"
262 #endif
264 #ifdef BLACKBOX
265 static const char * const lookupTableBlackboxDevice[] = {
266 "SERIAL", "SPIFLASH", "SDCARD"
268 #endif
270 #ifdef SERIAL_RX
271 static const char * const lookupTableSerialRX[] = {
272 "SPEK1024",
273 "SPEK2048",
274 "SBUS",
275 "SUMD",
276 "SUMH",
277 "XB-B",
278 "XB-B-RJ01",
279 "IBUS",
280 "JETIEXBUS",
281 "CRSF",
282 "SRXL"
284 #endif
286 #ifdef USE_RX_SPI
287 // sync with rx_spi_protocol_e
288 static const char * const lookupTableRxSpi[] = {
289 "V202_250K",
290 "V202_1M",
291 "SYMA_X",
292 "SYMA_X5C",
293 "CX10",
294 "CX10A",
295 "H8_3D",
296 "INAV"
298 #endif
300 static const char * const lookupTableGyroLpf[] = {
301 "OFF",
302 "188HZ",
303 "98HZ",
304 "42HZ",
305 "20HZ",
306 "10HZ",
307 "5HZ",
308 "EXPERIMENTAL"
311 static const char * const lookupTableDebug[DEBUG_COUNT] = {
312 "NONE",
313 "CYCLETIME",
314 "BATTERY",
315 "GYRO",
316 "ACCELEROMETER",
317 "MIXER",
318 "AIRMODE",
319 "PIDLOOP",
320 "NOTCH",
321 "RC_INTERPOLATION",
322 "VELOCITY",
323 "DFILTER",
324 "ANGLERATE",
325 "ESC_SENSOR",
326 "SCHEDULER",
327 "STACK",
328 "ESC_SENSOR_RPM",
329 "ESC_SENSOR_TMP",
330 "ALTITUDE"
333 #ifdef OSD
334 static const char * const lookupTableOsdType[] = {
335 "AUTO",
336 "PAL",
337 "NTSC"
339 #endif
341 static const char * const lookupTableSuperExpoYaw[] = {
342 "OFF", "ON", "ALWAYS"
345 static const char * const lookupTablePwmProtocol[] = {
346 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
347 #ifdef USE_DSHOT
348 "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200"
349 #endif
352 static const char * const lookupTableRcInterpolation[] = {
353 "OFF", "PRESET", "AUTO", "MANUAL"
356 static const char * const lookupTableRcInterpolationChannels[] = {
357 "RP", "RPY", "RPYT"
360 static const char * const lookupTableLowpassType[] = {
361 "PT1", "BIQUAD", "FIR"
364 static const char * const lookupTableFailsafe[] = {
365 "AUTO-LAND", "DROP"
368 typedef struct lookupTableEntry_s {
369 const char * const *values;
370 const uint8_t valueCount;
371 } lookupTableEntry_t;
373 typedef enum {
374 TABLE_OFF_ON = 0,
375 TABLE_UNIT,
376 TABLE_ALIGNMENT,
377 #ifdef GPS
378 TABLE_GPS_PROVIDER,
379 TABLE_GPS_SBAS_MODE,
380 #endif
381 #ifdef BLACKBOX
382 TABLE_BLACKBOX_DEVICE,
383 #endif
384 TABLE_CURRENT_METER,
385 TABLE_VOLTAGE_METER,
386 #ifdef USE_SERVOS
387 TABLE_GIMBAL_MODE,
388 #endif
389 #ifdef SERIAL_RX
390 TABLE_SERIAL_RX,
391 #endif
392 #ifdef USE_RX_SPI
393 TABLE_RX_SPI,
394 #endif
395 TABLE_GYRO_LPF,
396 TABLE_ACC_HARDWARE,
397 #ifdef BARO
398 TABLE_BARO_HARDWARE,
399 #endif
400 #ifdef MAG
401 TABLE_MAG_HARDWARE,
402 #endif
403 TABLE_DEBUG,
404 TABLE_SUPEREXPO_YAW,
405 TABLE_MOTOR_PWM_PROTOCOL,
406 TABLE_RC_INTERPOLATION,
407 TABLE_RC_INTERPOLATION_CHANNELS,
408 TABLE_LOWPASS_TYPE,
409 TABLE_FAILSAFE,
410 #ifdef OSD
411 TABLE_OSD,
412 #endif
413 LOOKUP_TABLE_COUNT
414 } lookupTableIndex_e;
416 static const lookupTableEntry_t lookupTables[] = {
417 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
418 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
419 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
420 #ifdef GPS
421 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
422 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
423 #endif
424 #ifdef BLACKBOX
425 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
426 #endif
427 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
428 { lookupTableBatterySensor, sizeof(lookupTableBatterySensor) / sizeof(char *) },
429 #ifdef USE_SERVOS
430 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
431 #endif
432 #ifdef SERIAL_RX
433 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
434 #endif
435 #ifdef USE_RX_SPI
436 { lookupTableRxSpi, sizeof(lookupTableRxSpi) / sizeof(char *) },
437 #endif
438 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
439 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
440 #ifdef BARO
441 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
442 #endif
443 #ifdef MAG
444 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
445 #endif
446 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
447 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
448 { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
449 { lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) },
450 { lookupTableRcInterpolationChannels, sizeof(lookupTableRcInterpolationChannels) / sizeof(char *) },
451 { lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
452 { lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
453 #ifdef OSD
454 { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
455 #endif
458 #define VALUE_TYPE_OFFSET 0
459 #define VALUE_SECTION_OFFSET 4
460 #define VALUE_MODE_OFFSET 6
462 typedef enum {
463 // value type, bits 0-3
464 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
465 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
466 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
467 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
469 // value section, bits 4-5
470 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
471 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
472 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET), // 0x20
473 // value mode
474 MODE_DIRECT = (0 << VALUE_MODE_OFFSET), // 0x40
475 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET) // 0x80
476 } cliValueFlag_e;
478 #define VALUE_TYPE_MASK (0x0F)
479 #define VALUE_SECTION_MASK (0x30)
480 #define VALUE_MODE_MASK (0xC0)
482 typedef union {
483 int8_t int8;
484 uint8_t uint8;
485 int16_t int16;
486 uint16_t uint16;
487 } cliVar_t;
489 typedef struct cliMinMaxConfig_s {
490 const int16_t min;
491 const int16_t max;
492 } cliMinMaxConfig_t;
494 typedef struct cliLookupTableConfig_s {
495 const lookupTableIndex_e tableIndex;
496 } cliLookupTableConfig_t;
498 typedef union {
499 cliLookupTableConfig_t lookup;
500 cliMinMaxConfig_t minmax;
501 } cliValueConfig_t;
503 typedef struct {
504 const char *name;
505 const uint8_t type; // see cliValueFlag_e
506 const cliValueConfig_t config;
508 pgn_t pgn;
509 uint16_t offset;
510 } __attribute__((packed)) clivalue_t;
512 static const clivalue_t valueTable[] = {
513 // PG_GYRO_CONFIG
514 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_align) },
515 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lpf) },
516 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_sync_denom) },
517 { "gyro_lowpass_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_type) },
518 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_hz) },
519 { "gyro_notch1_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_1) },
520 { "gyro_notch1_cutoff", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_cutoff_1) },
521 { "gyro_notch2_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_2) },
522 { "gyro_notch2_cutoff", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_cutoff_2) },
523 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyroMovementCalibrationThreshold) },
524 #if defined(GYRO_USES_SPI)
525 #if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
526 { "gyro_use_32khz", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_use_32khz) },
527 #endif
528 #if defined(USE_MPU_DATA_READY_SIGNAL)
529 { "gyro_isr_update", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_isr_update) },
530 #endif
531 #endif
532 #ifdef USE_DUAL_GYRO
533 { "gyro_to_use", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_to_use) },
534 #endif
536 // PG_ACCELEROMETER_CONFIG
537 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_align) },
538 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ACC_HARDWARE }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_hardware) },
539 { "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 400 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_lpf_hz) },
540 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.pitch) },
541 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.roll) },
543 // PG_COMPASS_CONFIG
544 #ifdef MAG
545 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_align) },
546 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAG_HARDWARE }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_hardware) },
547 { "mag_declination", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_declination) },
548 { "magzero_x", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[X]) },
549 { "magzero_y", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[Y]) },
550 { "magzero_z", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[Z]) },
551 #endif
553 // PG_BAROMETER_CONFIG
554 #ifdef BARO
555 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_hardware) },
556 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) },
557 { "baro_noise_lpf", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_noise_lpf) },
558 { "baro_cf_vel", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_cf_vel) },
559 { "baro_cf_alt", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 1000 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_cf_alt) },
560 #endif
562 // PG_RX_CONFIG
563 { "mid_rc", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1200, 1700 }, PG_RX_CONFIG, offsetof(rxConfig_t, midrc) },
564 { "min_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, mincheck) },
565 { "max_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, maxcheck) },
566 { "rssi_channel", VAR_INT8 | MASTER_VALUE, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_channel) },
567 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_scale) },
568 { "rssi_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_invert) },
569 { "rc_interp", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RC_INTERPOLATION }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolation) },
570 { "rc_interp_ch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RC_INTERPOLATION_CHANNELS }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolationChannels) },
571 { "rc_interp_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolationInterval) },
572 { "fpv_mix_degrees", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, fpvCamAngleDegrees) },
573 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, MAX_AUX_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, max_aux_channel) },
574 #ifdef SERIAL_RX
575 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
576 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) },
577 #endif
578 #ifdef SPEKTRUM_BIND_PIN
579 { "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) },
580 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
581 #endif
582 { "airmode_start_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1000, 2000 }, PG_RX_CONFIG, offsetof(rxConfig_t, airModeActivateThreshold) },
583 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_min_usec) },
584 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
585 #ifdef STM32F4
586 { "serialrx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, halfDuplex) },
587 #endif
589 // PG_PWM_CONFIG
590 #if defined(USE_PWM)
591 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PWM_CONFIG, offsetof(pwmConfig_t, inputFilteringMode) },
592 #endif
594 // PG_BLACKBOX_CONFIG
595 #ifdef BLACKBOX
596 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, rate_num) },
597 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, rate_denom) },
598 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
599 { "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) },
600 #endif
602 // PG_MOTOR_CONFIG
603 { "min_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, minthrottle) },
604 { "max_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, maxthrottle) },
605 { "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
606 #ifdef USE_DSHOT
607 { "digital_idle_value", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetValue) },
608 #endif
609 { "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
610 { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmProtocol) },
611 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 200, 32000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmRate) },
612 { "motor_pwm_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmInversion) },
614 // PG_THROTTLE_CORRECTION_CONFIG
615 { "thr_corr_value", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 150 }, PG_THROTTLE_CORRECTION_CONFIG, offsetof(throttleCorrectionConfig_t, throttle_correction_value) },
616 { "thr_corr_angle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 900 }, PG_THROTTLE_CORRECTION_CONFIG, offsetof(throttleCorrectionConfig_t, throttle_correction_angle) },
618 // PG_FAILSAFE_CONFIG
619 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_delay) },
620 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_off_delay) },
621 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle) },
622 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_kill_switch) },
623 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 300 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) },
624 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_procedure) },
626 // PG_BOARDALIGNMENT_CONFIG
627 { "align_board_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { 0, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, rollDegrees) },
628 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, .config.minmax = { 0, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, pitchDegrees) },
629 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, .config.minmax = { 0, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, yawDegrees) },
631 // PG_GIMBAL_CONFIG
632 #ifdef USE_SERVOS
633 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GIMBAL_MODE }, PG_GIMBAL_CONFIG, offsetof(gimbalConfig_t, mode) },
634 #endif
636 // PG_BATTERY_CONFIG
637 { "bat_capacity", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryCapacity) },
638 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmaxcellvoltage) },
639 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) },
640 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatwarningcellvoltage) },
641 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },
642 { "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) },
643 { "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) },
644 { "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) },
645 { "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useVBatAlerts) },
646 { "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
647 { "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
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) },
652 // PG_CURRENT_SENSOR_ADC_CONFIG
653 { "ibata_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, scale) },
654 { "ibata_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, offset) },
655 // PG_CURRENT_SENSOR_ADC_CONFIG
656 #ifdef USE_VIRTUAL_CURRENT_METER
657 { "ibatv_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, scale) },
658 { "ibatv_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, offset) },
659 #endif
661 // PG_BEEPER_DEV_CONFIG
662 #ifdef BEEPER
663 { "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isInverted) },
664 { "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isOpenDrain) },
665 { "beeper_frequency", VAR_INT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, frequency) },
666 #endif
668 // PG_MIXER_CONFIG
669 { "yaw_motors_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MIXER_CONFIG, offsetof(mixerConfig_t, yaw_motors_reversed) },
671 // PG_MOTOR_3D_CONFIG
672 { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_low) }, // FIXME upper limit should match code in the mixer, 1500 currently
673 { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_high) }, // FIXME lower limit should match code in the mixer, 1500 currently,
674 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) },
675 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_throttle) },
677 // PG_SERVO_CONFIG
678 #ifdef USE_SERVOS
679 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.servoCenterPulse) },
680 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 498 }, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.servoPwmRate) },
681 { "servo_lowpass_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 400}, PG_SERVO_CONFIG, offsetof(servoConfig_t, servo_lowpass_freq) },
682 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SERVO_CONFIG, offsetof(servoConfig_t, tri_unarmed_servo) },
683 { "channel_forwarding_start", VAR_UINT8 | MASTER_VALUE, .config.minmax = { AUX1, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_SERVO_CONFIG, offsetof(servoConfig_t, channelForwardingStartChannel) },
684 #endif
686 // PG_CONTROLRATE_PROFILES
687 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRate8) },
688 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawRate8) },
689 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo8) },
690 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
691 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrMid8) },
692 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrExpo8) },
693 { "roll_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_ROLL]) },
694 { "pitch_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_PITCH]) },
695 { "yaw_srate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rates[FD_YAW]) },
696 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, dynThrPID) },
697 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, tpa_breakpoint) },
699 // PG_SERIAL_CONFIG
700 { "reboot_character", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 48, 126 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, reboot_character) },
701 { "serial_update_rate_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 100, 2000 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, serial_update_rate_hz) },
703 // PG_IMU_CONFIG
704 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.xy) },
705 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.z) },
706 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_IMU_CONFIG, offsetof(imuConfig_t, acc_unarmedcal) },
707 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_kp) },
708 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_ki) },
709 { "small_angle", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
711 // PG_ARMING_CONFIG
712 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_ARMING_CONFIG, offsetof(armingConfig_t, auto_disarm_delay) },
713 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ARMING_CONFIG, offsetof(armingConfig_t, disarm_kill_switch) },
714 { "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) },
717 // PG_GPS_CONFIG
718 #ifdef GPS
719 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) },
720 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) },
721 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) },
722 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoBaud) },
723 #endif
725 // PG_NAVIGATION_CONFIG
726 #ifdef GPS
727 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, gps_wp_radius) },
728 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_controls_heading) },
729 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_min) },
730 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_max) },
731 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_slew_rate) },
732 #endif
734 // PG_AIRPLANE_CONFIG
735 { "fixedwing_althold_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_reversed) },
737 // PG_RC_CONTROLS_CONFIG
738 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_deadband) },
739 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_fast_change) },
740 { "deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 32 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, deadband) },
741 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_deadband) },
742 { "yaw_control_reversed", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_control_reversed) },
744 // PG_PID_CONFIG
745 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, MAX_PID_PROCESS_DENOM }, PG_PID_CONFIG, offsetof(pidConfig_t, pid_process_denom) },
747 // PG_PID_PROFILE
748 { "d_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) },
749 { "d_lowpass", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lpf_hz) },
750 { "d_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) },
751 { "d_notch_cut", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) },
752 { "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, vbatPidCompensation) },
753 { "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, pidAtMinThrottle) },
754 { "anti_gravity_thresh", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 20, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermThrottleThreshold) },
755 { "anti_gravity_gain", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 30000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermAcceleratorGain) },
756 { "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, setpointRelaxRatio) },
757 { "d_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 254 }, PG_PID_PROFILE, offsetof(pidProfile_t, dtermSetpointWeight) },
758 { "yaw_accel_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yawRateAccelLimit) },
759 { "accel_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, rateAccelLimit) },
761 { "iterm_windup", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 30, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermWindupPointPercent) },
762 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yaw_lpf_hz) },
763 { "pidsum_limit", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
764 { "pidsum_limit_yaw", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 100, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
766 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PITCH]) },
767 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PITCH]) },
768 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PITCH]) },
769 { "p_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[ROLL]) },
770 { "i_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[ROLL]) },
771 { "d_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[ROLL]) },
772 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[YAW]) },
773 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[YAW]) },
774 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[YAW]) },
776 { "p_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDALT]) },
777 { "i_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDALT]) },
778 { "d_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDALT]) },
780 { "p_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDLEVEL]) },
781 { "i_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDLEVEL]) },
782 { "d_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDLEVEL]) },
784 { "p_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDVEL]) },
785 { "i_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDVEL]) },
786 { "d_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDVEL]) },
788 { "level_sensitivity", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelSensitivity) },
789 { "level_limit", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 120 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelAngleLimit) },
790 #ifdef GPS
791 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOS]) },
792 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOS]) },
793 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOS]) },
794 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOSR]) },
795 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOSR]) },
796 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOSR]) },
797 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDNAVR]) },
798 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDNAVR]) },
799 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDNAVR]) },
800 #endif
802 // PG_TELEMETRY_CONFIG
803 #ifdef TELEMETRY
804 { "tlm_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_switch) },
805 { "tlm_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inversion) },
806 { "tlm_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, halfDuplex) },
807 { "frsky_default_lat", VAR_INT16 | MASTER_VALUE, .config.minmax = { -9000, 9000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) },
808 { "frsky_default_long", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) },
809 { "frsky_gps_format", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_coordinate_format) },
810 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_unit) },
811 { "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) },
812 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_vfas_cell_voltage) },
813 { "hott_alarm_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 120 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, hottAlarmSoundInterval) },
814 { "pid_in_tlm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = {TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, pidValuesAsTelemetry) },
815 #if defined(TELEMETRY_IBUS)
816 { "ibus_report_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, report_cell_voltage) },
817 #endif
818 #endif
820 // PG_LED_STRIP_CONFIG
821 #ifdef LED_STRIP
822 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ledstrip_visual_beeper) },
823 #endif
825 // PG_SDCARD_CONFIG
826 #ifdef USE_SDCARD
827 { "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) },
828 #endif
830 // PG_OSD_CONFIG
831 #ifdef OSD
832 { "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_OSD_CONFIG, offsetof(osdConfig_t, units) },
834 { "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
835 { "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
836 { "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_OSD_CONFIG, offsetof(osdConfig_t, time_alarm) },
837 { "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
839 { "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]) },
840 { "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_VALUE]) },
841 { "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYTIME]) },
842 { "osd_ontimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ONTIME]) },
843 { "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYMODE]) },
844 { "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_THROTTLE_POS]) },
845 { "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]) },
846 { "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CROSSHAIRS]) },
847 { "osd_horizon_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ARTIFICIAL_HORIZON]) },
848 { "osd_current_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CURRENT_DRAW]) },
849 { "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]) },
850 { "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]) },
851 { "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]) },
852 { "osd_gps_lon", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LON]) },
853 { "osd_gps_lat", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_GPS_LAT]) },
854 { "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]) },
855 { "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ALTITUDE]) },
856 { "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]) },
857 { "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]) },
858 { "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]) },
859 { "osd_power_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_POWER]) },
860 { "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]) },
861 { "osd_battery_warning_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_MAIN_BATT_WARNING]) },
862 { "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]) },
863 #endif
865 // PG_SYSTEM_CONFIG
866 #ifndef SKIP_TASK_STATISTICS
867 { "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
868 #endif
869 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },
871 // PG_VTX_CONFIG
872 #ifdef VTX_RTC6705
873 { "vtx_band", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 5 }, PG_VTX_RTC6705_CONFIG, offsetof(vtxRTC6705Config_t, band) },
874 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 8 }, PG_VTX_RTC6705_CONFIG, offsetof(vtxRTC6705Config_t, channel) },
875 { "vtx_power", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, RTC6705_POWER_COUNT - 1 }, PG_VTX_RTC6705_CONFIG, offsetof(vtxRTC6705Config_t, power) },
876 #endif
878 // PG_VCD_CONFIG
879 #ifdef USE_MAX7456
880 { "vcd_video_system", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 2 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, video_system) },
881 { "vcd_h_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -32, 31 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, h_offset) },
882 { "vcd_v_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -15, 16 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, v_offset) },
883 #endif
885 // PG_DISPLAY_PORT_MSP_CONFIG
886 #ifdef USE_MSP_DISPLAYPORT
887 { "displayport_msp_col_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
888 { "displayport_msp_row_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
889 #endif
891 // PG_DISPLAY_PORT_MSP_CONFIG
892 #ifdef USE_MAX7456
893 { "displayport_max7456_col_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
894 { "displayport_max7456_row_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
895 #endif
898 static gyroConfig_t gyroConfigCopy;
899 static accelerometerConfig_t accelerometerConfigCopy;
900 #ifdef MAG
901 static compassConfig_t compassConfigCopy;
902 #endif
903 #ifdef BARO
904 static barometerConfig_t barometerConfigCopy;
905 #endif
906 #ifdef PITOT
907 static pitotmeterConfig_t pitotmeterConfigCopy;
908 #endif
909 static featureConfig_t featureConfigCopy;
910 static rxConfig_t rxConfigCopy;
911 // PG_PWM_CONFIG
912 #ifdef USE_PWM
913 static pwmConfig_t pwmConfigCopy;
914 #endif
915 #ifdef BLACKBOX
916 static blackboxConfig_t blackboxConfigCopy;
917 #endif
918 static rxFailsafeChannelConfig_t rxFailsafeChannelConfigsCopy[MAX_SUPPORTED_RC_CHANNEL_COUNT];
919 static rxChannelRangeConfig_t rxChannelRangeConfigsCopy[NON_AUX_CHANNEL_COUNT];
920 static motorConfig_t motorConfigCopy;
921 static throttleCorrectionConfig_t throttleCorrectionConfigCopy;
922 static failsafeConfig_t failsafeConfigCopy;
923 static boardAlignment_t boardAlignmentCopy;
924 #ifdef USE_SERVOS
925 static servoConfig_t servoConfigCopy;
926 static gimbalConfig_t gimbalConfigCopy;
927 static servoMixer_t customServoMixersCopy[MAX_SERVO_RULES];
928 static servoParam_t servoParamsCopy[MAX_SUPPORTED_SERVOS];
929 #endif
930 static batteryConfig_t batteryConfigCopy;
931 static voltageSensorADCConfig_t voltageSensorADCConfigCopy[MAX_VOLTAGE_SENSOR_ADC];
932 static currentSensorADCConfig_t currentSensorADCConfigCopy;
933 #ifdef USE_VIRTUAL_CURRENT_METER
934 static currentSensorVirtualConfig_t currentSensorVirtualConfigCopy;
935 #endif
936 static motorMixer_t customMotorMixerCopy[MAX_SUPPORTED_MOTORS];
937 static mixerConfig_t mixerConfigCopy;
938 static flight3DConfig_t flight3DConfigCopy;
939 static serialConfig_t serialConfigCopy;
940 static serialPinConfig_t serialPinConfigCopy;
941 static imuConfig_t imuConfigCopy;
942 static armingConfig_t armingConfigCopy;
943 static rcControlsConfig_t rcControlsConfigCopy;
944 #ifdef GPS
945 static gpsConfig_t gpsConfigCopy;
946 static navigationConfig_t navigationConfigCopy;
947 #endif
948 static airplaneConfig_t airplaneConfigCopy;
949 #ifdef TELEMETRY
950 static telemetryConfig_t telemetryConfigCopy;
951 #endif
952 static modeActivationCondition_t modeActivationConditionsCopy[MAX_MODE_ACTIVATION_CONDITION_COUNT];
953 static adjustmentRange_t adjustmentRangesCopy[MAX_ADJUSTMENT_RANGE_COUNT];
954 #ifdef LED_STRIP
955 static ledStripConfig_t ledStripConfigCopy;
956 #endif
957 #ifdef USE_SDCARD
958 static sdcardConfig_t sdcardConfigCopy;
959 #endif
960 #ifdef OSD
961 static osdConfig_t osdConfigCopy;
962 #endif
963 static systemConfig_t systemConfigCopy;
964 #ifdef BEEPER
965 static beeperDevConfig_t beeperDevConfigCopy;
966 static beeperConfig_t beeperConfigCopy;
967 #endif
968 #ifdef VTX_RTC6705
969 static vtxRTC6705Config_t vtxRTC6705ConfigCopy;
970 #endif
971 #ifdef VTX_CONTROL
972 static vtxConfig_t vtxConfigCopy;
973 #endif
974 #ifdef USE_MAX7456
975 vcdProfile_t vcdProfileCopy;
976 #endif
977 #ifdef USE_MSP_DISPLAYPORT
978 displayPortProfile_t displayPortProfileMspCopy;
979 #endif
980 #ifdef USE_MAX7456
981 displayPortProfile_t displayPortProfileMax7456Copy;
982 #endif
983 static pidConfig_t pidConfigCopy;
984 static controlRateConfig_t controlRateProfilesCopy[CONTROL_RATE_PROFILE_COUNT];
985 static pidProfile_t pidProfileCopy[MAX_PROFILE_COUNT];
987 static void cliPrint(const char *str)
989 while (*str) {
990 bufWriterAppend(cliWriter, *str++);
992 bufWriterFlush(cliWriter);
995 #ifdef MINIMAL_CLI
996 #define cliPrintHashLine(str)
997 #else
998 static void cliPrintHashLine(const char *str)
1000 cliPrint("\r\n# ");
1001 cliPrint(str);
1002 cliPrint("\r\n");
1004 #endif
1006 static void cliPutp(void *p, char ch)
1008 bufWriterAppend(p, ch);
1011 typedef enum {
1012 DUMP_MASTER = (1 << 0),
1013 DUMP_PROFILE = (1 << 1),
1014 DUMP_RATES = (1 << 2),
1015 DUMP_ALL = (1 << 3),
1016 DO_DIFF = (1 << 4),
1017 SHOW_DEFAULTS = (1 << 5),
1018 HIDE_UNUSED = (1 << 6)
1019 } dumpFlags_e;
1021 static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
1023 if (!((dumpMask & DO_DIFF) && equalsDefault)) {
1024 va_list va;
1025 va_start(va, format);
1026 tfp_format(cliWriter, cliPutp, format, va);
1027 va_end(va);
1028 bufWriterFlush(cliWriter);
1029 return true;
1030 } else {
1031 return false;
1035 static void cliWrite(uint8_t ch)
1037 bufWriterAppend(cliWriter, ch);
1040 static bool cliDefaultPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
1042 if ((dumpMask & SHOW_DEFAULTS) && !equalsDefault) {
1043 cliWrite('#');
1045 va_list va;
1046 va_start(va, format);
1047 tfp_format(cliWriter, cliPutp, format, va);
1048 va_end(va);
1049 bufWriterFlush(cliWriter);
1050 return true;
1051 } else {
1052 return false;
1056 static void cliPrintf(const char *format, ...)
1058 va_list va;
1059 va_start(va, format);
1060 tfp_format(cliWriter, cliPutp, format, va);
1061 va_end(va);
1062 bufWriterFlush(cliWriter);
1065 static void printValuePointer(const clivalue_t *var, const void *valuePointer, bool full)
1067 cliVar_t value = { .uint16 = 0 };
1069 switch (var->type & VALUE_TYPE_MASK) {
1070 case VAR_UINT8:
1071 value.uint8 = *(uint8_t *)valuePointer;
1072 break;
1074 case VAR_INT8:
1075 value.int8 = *(int8_t *)valuePointer;
1076 break;
1078 case VAR_UINT16:
1079 value.uint16 = *(uint16_t *)valuePointer;
1080 break;
1082 case VAR_INT16:
1083 value.int16 = *(int16_t *)valuePointer;
1084 break;
1087 switch(var->type & VALUE_MODE_MASK) {
1088 case MODE_DIRECT:
1089 cliPrintf("%d", value);
1090 if (full) {
1091 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
1093 break;
1094 case MODE_LOOKUP:
1095 cliPrint(lookupTables[var->config.lookup.tableIndex].values[value.uint16]);
1096 break;
1100 static bool valuePtrEqualsDefault(uint8_t type, const void *ptr, const void *ptrDefault)
1102 bool result = false;
1103 switch (type & VALUE_TYPE_MASK) {
1104 case VAR_UINT8:
1105 result = *(uint8_t *)ptr == *(uint8_t *)ptrDefault;
1106 break;
1108 case VAR_INT8:
1109 result = *(int8_t *)ptr == *(int8_t *)ptrDefault;
1110 break;
1112 case VAR_UINT16:
1113 result = *(uint16_t *)ptr == *(uint16_t *)ptrDefault;
1114 break;
1116 case VAR_INT16:
1117 result = *(int16_t *)ptr == *(int16_t *)ptrDefault;
1118 break;
1121 return result;
1124 typedef struct cliCurrentAndDefaultConfig_s {
1125 const void *currentConfig; // the copy
1126 const void *defaultConfig; // the PG value as set by default
1127 } cliCurrentAndDefaultConfig_t;
1129 static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn)
1131 static cliCurrentAndDefaultConfig_t ret;
1133 switch (pgn) {
1134 case PG_GYRO_CONFIG:
1135 ret.currentConfig = &gyroConfigCopy;
1136 ret.defaultConfig = gyroConfig();
1137 break;
1138 case PG_ACCELEROMETER_CONFIG:
1139 ret.currentConfig = &accelerometerConfigCopy;
1140 ret.defaultConfig = accelerometerConfig();
1141 break;
1142 #ifdef MAG
1143 case PG_COMPASS_CONFIG:
1144 ret.currentConfig = &compassConfigCopy;
1145 ret.defaultConfig = compassConfig();
1146 break;
1147 #endif
1148 #ifdef BARO
1149 case PG_BAROMETER_CONFIG:
1150 ret.currentConfig = &barometerConfigCopy;
1151 ret.defaultConfig = barometerConfig();
1152 break;
1153 #endif
1154 #ifdef PITOT
1155 case PG_PITOTMETER_CONFIG:
1156 ret.currentConfig = &pitotmeterConfigCopy;
1157 ret.defaultConfig = pitotmeterConfig();
1158 break;
1159 #endif
1160 case PG_FEATURE_CONFIG:
1161 ret.currentConfig = &featureConfigCopy;
1162 ret.defaultConfig = featureConfig();
1163 break;
1164 case PG_RX_CONFIG:
1165 ret.currentConfig = &rxConfigCopy;
1166 ret.defaultConfig = rxConfig();
1167 break;
1168 #ifdef USE_PWM
1169 case PG_PWM_CONFIG:
1170 ret.currentConfig = &pwmConfigCopy;
1171 ret.defaultConfig = pwmConfig();
1172 break;
1173 #endif
1174 #ifdef BLACKBOX
1175 case PG_BLACKBOX_CONFIG:
1176 ret.currentConfig = &blackboxConfigCopy;
1177 ret.defaultConfig = blackboxConfig();
1178 break;
1179 #endif
1180 case PG_MOTOR_CONFIG:
1181 ret.currentConfig = &motorConfigCopy;
1182 ret.defaultConfig = motorConfig();
1183 break;
1184 case PG_THROTTLE_CORRECTION_CONFIG:
1185 ret.currentConfig = &throttleCorrectionConfigCopy;
1186 ret.defaultConfig = throttleCorrectionConfig();
1187 break;
1188 case PG_FAILSAFE_CONFIG:
1189 ret.currentConfig = &failsafeConfigCopy;
1190 ret.defaultConfig = failsafeConfig();
1191 break;
1192 case PG_BOARD_ALIGNMENT:
1193 ret.currentConfig = &boardAlignmentCopy;
1194 ret.defaultConfig = boardAlignment();
1195 break;
1196 case PG_MIXER_CONFIG:
1197 ret.currentConfig = &mixerConfigCopy;
1198 ret.defaultConfig = mixerConfig();
1199 break;
1200 case PG_MOTOR_3D_CONFIG:
1201 ret.currentConfig = &flight3DConfigCopy;
1202 ret.defaultConfig = flight3DConfig();
1203 break;
1204 #ifdef USE_SERVOS
1205 case PG_SERVO_CONFIG:
1206 ret.currentConfig = &servoConfigCopy;
1207 ret.defaultConfig = servoConfig();
1208 break;
1209 case PG_GIMBAL_CONFIG:
1210 ret.currentConfig = &gimbalConfigCopy;
1211 ret.defaultConfig = gimbalConfig();
1212 break;
1213 #endif
1214 case PG_BATTERY_CONFIG:
1215 ret.currentConfig = &batteryConfigCopy;
1216 ret.defaultConfig = batteryConfig();
1217 break;
1218 case PG_VOLTAGE_SENSOR_ADC_CONFIG:
1219 ret.currentConfig = &voltageSensorADCConfigCopy[0];
1220 ret.defaultConfig = voltageSensorADCConfig(0);
1221 break;
1222 case PG_CURRENT_SENSOR_ADC_CONFIG:
1223 ret.currentConfig = &currentSensorADCConfigCopy;
1224 ret.defaultConfig = currentSensorADCConfig();
1225 break;
1226 #ifdef USE_VIRTUAL_CURRENT_METER
1227 case PG_CURRENT_SENSOR_VIRTUAL_CONFIG:
1228 ret.currentConfig = &currentSensorVirtualConfigCopy;
1229 ret.defaultConfig = currentSensorVirtualConfig();
1230 break;
1231 #endif
1232 case PG_SERIAL_CONFIG:
1233 ret.currentConfig = &serialConfigCopy;
1234 ret.defaultConfig = serialConfig();
1235 break;
1236 case PG_SERIAL_PIN_CONFIG:
1237 ret.currentConfig = &serialPinConfigCopy;
1238 ret.defaultConfig = serialPinConfig();
1239 break;
1240 case PG_IMU_CONFIG:
1241 ret.currentConfig = &imuConfigCopy;
1242 ret.defaultConfig = imuConfig();
1243 break;
1244 case PG_RC_CONTROLS_CONFIG:
1245 ret.currentConfig = &rcControlsConfigCopy;
1246 ret.defaultConfig = rcControlsConfig();
1247 break;
1248 case PG_ARMING_CONFIG:
1249 ret.currentConfig = &armingConfigCopy;
1250 ret.defaultConfig = armingConfig();
1251 break;
1252 #ifdef GPS
1253 case PG_GPS_CONFIG:
1254 ret.currentConfig = &gpsConfigCopy;
1255 ret.defaultConfig = gpsConfig();
1256 break;
1257 case PG_NAVIGATION_CONFIG:
1258 ret.currentConfig = &navigationConfigCopy;
1259 ret.defaultConfig = navigationConfig();
1260 break;
1261 #endif
1262 case PG_AIRPLANE_CONFIG:
1263 ret.currentConfig = &airplaneConfigCopy;
1264 ret.defaultConfig = airplaneConfig();
1265 break;
1266 #ifdef TELEMETRY
1267 case PG_TELEMETRY_CONFIG:
1268 ret.currentConfig = &telemetryConfigCopy;
1269 ret.defaultConfig = telemetryConfig();
1270 break;
1271 #endif
1272 #ifdef LED_STRIP
1273 case PG_LED_STRIP_CONFIG:
1274 ret.currentConfig = &ledStripConfigCopy;
1275 ret.defaultConfig = ledStripConfig();
1276 break;
1277 #endif
1278 #ifdef USE_SDCARD
1279 case PG_SDCARD_CONFIG:
1280 ret.currentConfig = &sdcardConfigCopy;
1281 ret.defaultConfig = sdcardConfig();
1282 break;
1283 #endif
1284 #ifdef OSD
1285 case PG_OSD_CONFIG:
1286 ret.currentConfig = &osdConfigCopy;
1287 ret.defaultConfig = osdConfig();
1288 break;
1289 #endif
1290 case PG_SYSTEM_CONFIG:
1291 ret.currentConfig = &systemConfigCopy;
1292 ret.defaultConfig = systemConfig();
1293 break;
1294 case PG_CONTROL_RATE_PROFILES:
1295 ret.currentConfig = &controlRateProfilesCopy[0];
1296 ret.defaultConfig = controlRateProfiles(0);
1297 break;
1298 case PG_PID_PROFILE:
1299 ret.currentConfig = &pidProfileCopy[0];
1300 ret.defaultConfig = pidProfiles(0);
1301 break;
1302 case PG_RX_FAILSAFE_CHANNEL_CONFIG:
1303 ret.currentConfig = &rxFailsafeChannelConfigsCopy[0];
1304 ret.defaultConfig = rxFailsafeChannelConfigs(0);
1305 break;
1306 case PG_RX_CHANNEL_RANGE_CONFIG:
1307 ret.currentConfig = &rxChannelRangeConfigsCopy[0];
1308 ret.defaultConfig = rxChannelRangeConfigs(0);
1309 break;
1310 #ifdef USE_SERVOS
1311 case PG_SERVO_MIXER:
1312 ret.currentConfig = &customServoMixersCopy[0];
1313 ret.defaultConfig = customServoMixers(0);
1314 break;
1315 case PG_SERVO_PARAMS:
1316 ret.currentConfig = &servoParamsCopy[0];
1317 ret.defaultConfig = servoParams(0);
1318 break;
1319 #endif
1320 case PG_MOTOR_MIXER:
1321 ret.currentConfig = &customMotorMixerCopy[0];
1322 ret.defaultConfig = customMotorMixer(0);
1323 break;
1324 case PG_MODE_ACTIVATION_PROFILE:
1325 ret.currentConfig = &modeActivationConditionsCopy[0];
1326 ret.defaultConfig = modeActivationConditions(0);
1327 break;
1328 case PG_ADJUSTMENT_RANGE_CONFIG:
1329 ret.currentConfig = &adjustmentRangesCopy[0];
1330 ret.defaultConfig = adjustmentRanges(0);
1331 break;
1332 #ifdef BEEPER
1333 case PG_BEEPER_CONFIG:
1334 ret.currentConfig = &beeperConfigCopy;
1335 ret.defaultConfig = beeperConfig();
1336 break;
1337 case PG_BEEPER_DEV_CONFIG:
1338 ret.currentConfig = &beeperDevConfigCopy;
1339 ret.defaultConfig = beeperDevConfig();
1340 break;
1341 #endif
1342 #ifdef VTX_RTC6705
1343 case PG_VTX_RTC6705_CONFIG:
1344 ret.currentConfig = &vtxRTC6705ConfigCopy;
1345 ret.defaultConfig = vtxRTC6705Config();
1346 break;
1347 #endif
1348 #ifdef VTX_CONTROL
1349 case PG_VTX_CONFIG:
1350 ret.currentConfig = &vtxConfigCopy;
1351 ret.defaultConfig = vtxConfig();
1352 break;
1353 #endif
1354 #ifdef USE_MAX7456
1355 case PG_VCD_CONFIG:
1356 ret.currentConfig = &vcdProfileCopy;
1357 ret.defaultConfig = vcdProfile();
1358 break;
1359 #endif
1360 #ifdef USE_MSP_DISPLAYPORT
1361 case PG_DISPLAY_PORT_MSP_CONFIG:
1362 ret.currentConfig = &displayPortProfileMspCopy;
1363 ret.defaultConfig = displayPortProfileMsp();
1364 break;
1365 #endif
1366 #ifdef USE_MAX7456
1367 case PG_DISPLAY_PORT_MAX7456_CONFIG:
1368 ret.currentConfig = &displayPortProfileMax7456Copy;
1369 ret.defaultConfig = displayPortProfileMax7456();
1370 break;
1371 #endif
1372 case PG_PID_CONFIG:
1373 ret.currentConfig = &pidConfigCopy;
1374 ret.defaultConfig = pidConfig();
1375 break;
1376 default:
1377 ret.currentConfig = NULL;
1378 ret.defaultConfig = NULL;
1379 break;
1381 return &ret;
1384 static uint16_t getValueOffset(const clivalue_t *value)
1386 switch (value->type & VALUE_SECTION_MASK) {
1387 case MASTER_VALUE:
1388 return value->offset;
1389 case PROFILE_VALUE:
1390 return value->offset + sizeof(pidProfile_t) * getCurrentPidProfileIndex();
1391 case PROFILE_RATE_VALUE:
1392 return value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
1394 return 0;
1397 static void *getValuePointer(const clivalue_t *value)
1399 const pgRegistry_t* rec = pgFind(value->pgn);
1400 return CONST_CAST(void *, rec->address + getValueOffset(value));
1403 static void dumpPgValue(const clivalue_t *value, uint8_t dumpMask)
1405 const cliCurrentAndDefaultConfig_t *config = getCurrentAndDefaultConfigs(value->pgn);
1406 if (config->currentConfig == NULL || config->defaultConfig == NULL) {
1407 // has not been set up properly
1408 cliPrintf("VALUE %s ERROR\r\n", value->name);
1409 return;
1412 const char *format = "set %s = ";
1413 const char *defaultFormat = "#set %s = ";
1414 const int valueOffset = getValueOffset(value);
1415 const bool equalsDefault = valuePtrEqualsDefault(value->type, (uint8_t*)config->currentConfig + valueOffset, (uint8_t*)config->defaultConfig + valueOffset);
1416 if (((dumpMask & DO_DIFF) == 0) || !equalsDefault) {
1417 if (dumpMask & SHOW_DEFAULTS && !equalsDefault) {
1418 cliPrintf(defaultFormat, value->name);
1419 printValuePointer(value, (uint8_t*)config->defaultConfig + valueOffset, 0);
1420 cliPrint("\r\n");
1422 cliPrintf(format, value->name);
1423 printValuePointer(value, (uint8_t*)config->currentConfig + valueOffset, 0);
1424 cliPrint("\r\n");
1428 static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
1430 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
1431 const clivalue_t *value = &valueTable[i];
1432 bufWriterFlush(cliWriter);
1433 if ((value->type & VALUE_SECTION_MASK) == valueSection) {
1434 dumpPgValue(value, dumpMask);
1439 static void cliPrintVar(const clivalue_t *var, bool full)
1441 const void *ptr = getValuePointer(var);
1443 printValuePointer(var, ptr, full);
1446 static void cliPrintVarRange(const clivalue_t *var)
1448 switch (var->type & VALUE_MODE_MASK) {
1449 case (MODE_DIRECT): {
1450 cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
1452 break;
1453 case (MODE_LOOKUP): {
1454 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
1455 cliPrint("Allowed values:");
1456 for (uint32_t i = 0; i < tableEntry->valueCount ; i++) {
1457 if (i > 0)
1458 cliPrint(",");
1459 cliPrintf(" %s", tableEntry->values[i]);
1461 cliPrint("\r\n");
1463 break;
1467 static void cliSetVar(const clivalue_t *var, const cliVar_t value)
1469 void *ptr = getValuePointer(var);
1471 switch (var->type & VALUE_TYPE_MASK) {
1472 case VAR_UINT8:
1473 *(uint8_t *)ptr = value.uint8;
1474 break;
1476 case VAR_INT8:
1477 *(int8_t *)ptr = value.int8;
1478 break;
1480 case VAR_UINT16:
1481 *(uint16_t *)ptr = value.uint16;
1482 break;
1484 case VAR_INT16:
1485 *(int16_t *)ptr = value.int16;
1486 break;
1490 #ifndef MINIMAL_CLI
1491 static void cliRepeat(char ch, uint8_t len)
1493 for (int i = 0; i < len; i++) {
1494 bufWriterAppend(cliWriter, ch);
1496 cliPrint("\r\n");
1498 #endif
1500 static void cliPrompt(void)
1502 cliPrint("\r\n# ");
1505 static void cliShowParseError(void)
1507 cliPrint("Parse error\r\n");
1510 static void cliShowArgumentRangeError(char *name, int min, int max)
1512 cliPrintf("%s not between %d and %d\r\n", name, min, max);
1515 static const char *nextArg(const char *currentArg)
1517 const char *ptr = strchr(currentArg, ' ');
1518 while (ptr && *ptr == ' ') {
1519 ptr++;
1522 return ptr;
1525 static const char *processChannelRangeArgs(const char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
1527 for (uint32_t argIndex = 0; argIndex < 2; argIndex++) {
1528 ptr = nextArg(ptr);
1529 if (ptr) {
1530 int val = atoi(ptr);
1531 val = CHANNEL_VALUE_TO_STEP(val);
1532 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
1533 if (argIndex == 0) {
1534 range->startStep = val;
1535 } else {
1536 range->endStep = val;
1538 (*validArgumentCount)++;
1543 return ptr;
1546 // Check if a string's length is zero
1547 static bool isEmpty(const char *string)
1549 return (string == NULL || *string == '\0') ? true : false;
1552 static void printRxFailsafe(uint8_t dumpMask, const rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs, const rxFailsafeChannelConfig_t *defaultRxFailsafeChannelConfigs)
1554 // print out rxConfig failsafe settings
1555 for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
1556 const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxFailsafeChannelConfigs[channel];
1557 const rxFailsafeChannelConfig_t *defaultChannelFailsafeConfig = &defaultRxFailsafeChannelConfigs[channel];
1558 const bool equalsDefault = channelFailsafeConfig->mode == defaultChannelFailsafeConfig->mode
1559 && channelFailsafeConfig->step == defaultChannelFailsafeConfig->step;
1560 const bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
1561 if (requireValue) {
1562 const char *format = "rxfail %u %c %d\r\n";
1563 cliDefaultPrintf(dumpMask, equalsDefault, format,
1564 channel,
1565 rxFailsafeModeCharacters[defaultChannelFailsafeConfig->mode],
1566 RXFAIL_STEP_TO_CHANNEL_VALUE(defaultChannelFailsafeConfig->step)
1568 cliDumpPrintf(dumpMask, equalsDefault, format,
1569 channel,
1570 rxFailsafeModeCharacters[channelFailsafeConfig->mode],
1571 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
1573 } else {
1574 const char *format = "rxfail %u %c\r\n";
1575 cliDefaultPrintf(dumpMask, equalsDefault, format,
1576 channel,
1577 rxFailsafeModeCharacters[defaultChannelFailsafeConfig->mode]
1579 cliDumpPrintf(dumpMask, equalsDefault, format,
1580 channel,
1581 rxFailsafeModeCharacters[channelFailsafeConfig->mode]
1587 static void cliRxFailsafe(char *cmdline)
1589 uint8_t channel;
1590 char buf[3];
1592 if (isEmpty(cmdline)) {
1593 // print out rxConfig failsafe settings
1594 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
1595 cliRxFailsafe(itoa(channel, buf, 10));
1597 } else {
1598 const char *ptr = cmdline;
1599 channel = atoi(ptr++);
1600 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
1602 rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigsMutable(channel);
1604 const rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
1605 rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
1606 bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
1608 ptr = nextArg(ptr);
1609 if (ptr) {
1610 const char *p = strchr(rxFailsafeModeCharacters, *(ptr));
1611 if (p) {
1612 const uint8_t requestedMode = p - rxFailsafeModeCharacters;
1613 mode = rxFailsafeModesTable[type][requestedMode];
1614 } else {
1615 mode = RX_FAILSAFE_MODE_INVALID;
1617 if (mode == RX_FAILSAFE_MODE_INVALID) {
1618 cliShowParseError();
1619 return;
1622 requireValue = mode == RX_FAILSAFE_MODE_SET;
1624 ptr = nextArg(ptr);
1625 if (ptr) {
1626 if (!requireValue) {
1627 cliShowParseError();
1628 return;
1630 uint16_t value = atoi(ptr);
1631 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
1632 if (value > MAX_RXFAIL_RANGE_STEP) {
1633 cliPrint("Value out of range\r\n");
1634 return;
1637 channelFailsafeConfig->step = value;
1638 } else if (requireValue) {
1639 cliShowParseError();
1640 return;
1642 channelFailsafeConfig->mode = mode;
1645 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfig->mode];
1647 // double use of cliPrintf below
1648 // 1. acknowledge interpretation on command,
1649 // 2. query current setting on single item,
1651 if (requireValue) {
1652 cliPrintf("rxfail %u %c %d\r\n",
1653 channel,
1654 modeCharacter,
1655 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
1657 } else {
1658 cliPrintf("rxfail %u %c\r\n",
1659 channel,
1660 modeCharacter
1663 } else {
1664 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
1669 static void printAux(uint8_t dumpMask, const modeActivationCondition_t *modeActivationConditions, const modeActivationCondition_t *defaultModeActivationConditions)
1671 const char *format = "aux %u %u %u %u %u\r\n";
1672 // print out aux channel settings
1673 for (uint32_t i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
1674 const modeActivationCondition_t *mac = &modeActivationConditions[i];
1675 bool equalsDefault = false;
1676 if (defaultModeActivationConditions) {
1677 const modeActivationCondition_t *macDefault = &defaultModeActivationConditions[i];
1678 equalsDefault = mac->modeId == macDefault->modeId
1679 && mac->auxChannelIndex == macDefault->auxChannelIndex
1680 && mac->range.startStep == macDefault->range.startStep
1681 && mac->range.endStep == macDefault->range.endStep;
1682 const box_t *box = findBoxByBoxId(macDefault->modeId);
1683 if (box) {
1684 cliDefaultPrintf(dumpMask, equalsDefault, format,
1686 box->permanentId,
1687 macDefault->auxChannelIndex,
1688 MODE_STEP_TO_CHANNEL_VALUE(macDefault->range.startStep),
1689 MODE_STEP_TO_CHANNEL_VALUE(macDefault->range.endStep)
1693 const box_t *box = findBoxByBoxId(mac->modeId);
1694 if (box) {
1695 cliDumpPrintf(dumpMask, equalsDefault, format,
1697 box->permanentId,
1698 mac->auxChannelIndex,
1699 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
1700 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
1706 static void cliAux(char *cmdline)
1708 int i, val = 0;
1709 const char *ptr;
1711 if (isEmpty(cmdline)) {
1712 printAux(DUMP_MASTER, modeActivationConditions(0), NULL);
1713 } else {
1714 ptr = cmdline;
1715 i = atoi(ptr++);
1716 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
1717 modeActivationCondition_t *mac = modeActivationConditionsMutable(i);
1718 uint8_t validArgumentCount = 0;
1719 ptr = nextArg(ptr);
1720 if (ptr) {
1721 val = atoi(ptr);
1722 const box_t *box = findBoxByPermanentId(val);
1723 if (box) {
1724 mac->modeId = box->boxId;
1725 validArgumentCount++;
1728 ptr = nextArg(ptr);
1729 if (ptr) {
1730 val = atoi(ptr);
1731 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1732 mac->auxChannelIndex = val;
1733 validArgumentCount++;
1736 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
1738 if (validArgumentCount != 4) {
1739 memset(mac, 0, sizeof(modeActivationCondition_t));
1741 } else {
1742 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
1747 static void printSerial(uint8_t dumpMask, const serialConfig_t *serialConfig, const serialConfig_t *serialConfigDefault)
1749 const char *format = "serial %d %d %ld %ld %ld %ld\r\n";
1750 for (uint32_t i = 0; i < SERIAL_PORT_COUNT; i++) {
1751 if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
1752 continue;
1754 bool equalsDefault = false;
1755 if (serialConfigDefault) {
1756 equalsDefault = serialConfig->portConfigs[i].identifier == serialConfigDefault->portConfigs[i].identifier
1757 && serialConfig->portConfigs[i].functionMask == serialConfigDefault->portConfigs[i].functionMask
1758 && serialConfig->portConfigs[i].msp_baudrateIndex == serialConfigDefault->portConfigs[i].msp_baudrateIndex
1759 && serialConfig->portConfigs[i].gps_baudrateIndex == serialConfigDefault->portConfigs[i].gps_baudrateIndex
1760 && serialConfig->portConfigs[i].telemetry_baudrateIndex == serialConfigDefault->portConfigs[i].telemetry_baudrateIndex
1761 && serialConfig->portConfigs[i].blackbox_baudrateIndex == serialConfigDefault->portConfigs[i].blackbox_baudrateIndex;
1762 cliDefaultPrintf(dumpMask, equalsDefault, format,
1763 serialConfigDefault->portConfigs[i].identifier,
1764 serialConfigDefault->portConfigs[i].functionMask,
1765 baudRates[serialConfigDefault->portConfigs[i].msp_baudrateIndex],
1766 baudRates[serialConfigDefault->portConfigs[i].gps_baudrateIndex],
1767 baudRates[serialConfigDefault->portConfigs[i].telemetry_baudrateIndex],
1768 baudRates[serialConfigDefault->portConfigs[i].blackbox_baudrateIndex]
1771 cliDumpPrintf(dumpMask, equalsDefault, format,
1772 serialConfig->portConfigs[i].identifier,
1773 serialConfig->portConfigs[i].functionMask,
1774 baudRates[serialConfig->portConfigs[i].msp_baudrateIndex],
1775 baudRates[serialConfig->portConfigs[i].gps_baudrateIndex],
1776 baudRates[serialConfig->portConfigs[i].telemetry_baudrateIndex],
1777 baudRates[serialConfig->portConfigs[i].blackbox_baudrateIndex]
1782 static void cliSerial(char *cmdline)
1784 if (isEmpty(cmdline)) {
1785 printSerial(DUMP_MASTER, serialConfig(), NULL);
1786 return;
1788 serialPortConfig_t portConfig;
1789 memset(&portConfig, 0 , sizeof(portConfig));
1791 serialPortConfig_t *currentConfig;
1793 uint8_t validArgumentCount = 0;
1795 const char *ptr = cmdline;
1797 int val = atoi(ptr++);
1798 currentConfig = serialFindPortConfiguration(val);
1799 if (currentConfig) {
1800 portConfig.identifier = val;
1801 validArgumentCount++;
1804 ptr = nextArg(ptr);
1805 if (ptr) {
1806 val = atoi(ptr);
1807 portConfig.functionMask = val & 0xFFFF;
1808 validArgumentCount++;
1811 for (int i = 0; i < 4; i ++) {
1812 ptr = nextArg(ptr);
1813 if (!ptr) {
1814 break;
1817 val = atoi(ptr);
1819 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1820 if (baudRates[baudRateIndex] != (uint32_t) val) {
1821 break;
1824 switch(i) {
1825 case 0:
1826 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_1000000) {
1827 continue;
1829 portConfig.msp_baudrateIndex = baudRateIndex;
1830 break;
1831 case 1:
1832 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1833 continue;
1835 portConfig.gps_baudrateIndex = baudRateIndex;
1836 break;
1837 case 2:
1838 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1839 continue;
1841 portConfig.telemetry_baudrateIndex = baudRateIndex;
1842 break;
1843 case 3:
1844 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1845 continue;
1847 portConfig.blackbox_baudrateIndex = baudRateIndex;
1848 break;
1851 validArgumentCount++;
1854 if (validArgumentCount < 6) {
1855 cliShowParseError();
1856 return;
1859 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1862 #ifndef SKIP_SERIAL_PASSTHROUGH
1863 static void cliSerialPassthrough(char *cmdline)
1865 if (isEmpty(cmdline)) {
1866 cliShowParseError();
1867 return;
1870 int id = -1;
1871 uint32_t baud = 0;
1872 unsigned mode = 0;
1873 char *saveptr;
1874 char* tok = strtok_r(cmdline, " ", &saveptr);
1875 int index = 0;
1877 while (tok != NULL) {
1878 switch(index) {
1879 case 0:
1880 id = atoi(tok);
1881 break;
1882 case 1:
1883 baud = atoi(tok);
1884 break;
1885 case 2:
1886 if (strstr(tok, "rx") || strstr(tok, "RX"))
1887 mode |= MODE_RX;
1888 if (strstr(tok, "tx") || strstr(tok, "TX"))
1889 mode |= MODE_TX;
1890 break;
1892 index++;
1893 tok = strtok_r(NULL, " ", &saveptr);
1896 printf("Port %d ", id);
1897 serialPort_t *passThroughPort;
1898 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1899 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1900 if (!baud) {
1901 printf("closed, specify baud.\r\n");
1902 return;
1904 if (!mode)
1905 mode = MODE_RXTX;
1907 passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL,
1908 baud, mode,
1909 SERIAL_NOT_INVERTED);
1910 if (!passThroughPort) {
1911 printf("could not be opened.\r\n");
1912 return;
1914 printf("opened, baud = %d.\r\n", baud);
1915 } else {
1916 passThroughPort = passThroughPortUsage->serialPort;
1917 // If the user supplied a mode, override the port's mode, otherwise
1918 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1919 printf("already open.\r\n");
1920 if (mode && passThroughPort->mode != mode) {
1921 printf("mode changed from %d to %d.\r\n",
1922 passThroughPort->mode, mode);
1923 serialSetMode(passThroughPort, mode);
1925 // If this port has a rx callback associated we need to remove it now.
1926 // Otherwise no data will be pushed in the serial port buffer!
1927 if (passThroughPort->rxCallback) {
1928 passThroughPort->rxCallback = 0;
1932 printf("forwarding, power cycle to exit.\r\n");
1934 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1936 #endif
1938 static void printAdjustmentRange(uint8_t dumpMask, const adjustmentRange_t *adjustmentRanges, const adjustmentRange_t *defaultAdjustmentRanges)
1940 const char *format = "adjrange %u %u %u %u %u %u %u\r\n";
1941 // print out adjustment ranges channel settings
1942 for (uint32_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1943 const adjustmentRange_t *ar = &adjustmentRanges[i];
1944 bool equalsDefault = false;
1945 if (defaultAdjustmentRanges) {
1946 const adjustmentRange_t *arDefault = &defaultAdjustmentRanges[i];
1947 equalsDefault = ar->auxChannelIndex == arDefault->auxChannelIndex
1948 && ar->range.startStep == arDefault->range.startStep
1949 && ar->range.endStep == arDefault->range.endStep
1950 && ar->adjustmentFunction == arDefault->adjustmentFunction
1951 && ar->auxSwitchChannelIndex == arDefault->auxSwitchChannelIndex
1952 && ar->adjustmentIndex == arDefault->adjustmentIndex;
1953 cliDefaultPrintf(dumpMask, equalsDefault, format,
1955 arDefault->adjustmentIndex,
1956 arDefault->auxChannelIndex,
1957 MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.startStep),
1958 MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.endStep),
1959 arDefault->adjustmentFunction,
1960 arDefault->auxSwitchChannelIndex
1963 cliDumpPrintf(dumpMask, equalsDefault, format,
1965 ar->adjustmentIndex,
1966 ar->auxChannelIndex,
1967 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1968 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1969 ar->adjustmentFunction,
1970 ar->auxSwitchChannelIndex
1975 static void cliAdjustmentRange(char *cmdline)
1977 int i, val = 0;
1978 const char *ptr;
1980 if (isEmpty(cmdline)) {
1981 printAdjustmentRange(DUMP_MASTER, adjustmentRanges(0), NULL);
1982 } else {
1983 ptr = cmdline;
1984 i = atoi(ptr++);
1985 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1986 adjustmentRange_t *ar = adjustmentRangesMutable(i);
1987 uint8_t validArgumentCount = 0;
1989 ptr = nextArg(ptr);
1990 if (ptr) {
1991 val = atoi(ptr);
1992 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1993 ar->adjustmentIndex = val;
1994 validArgumentCount++;
1997 ptr = nextArg(ptr);
1998 if (ptr) {
1999 val = atoi(ptr);
2000 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2001 ar->auxChannelIndex = val;
2002 validArgumentCount++;
2006 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
2008 ptr = nextArg(ptr);
2009 if (ptr) {
2010 val = atoi(ptr);
2011 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
2012 ar->adjustmentFunction = val;
2013 validArgumentCount++;
2016 ptr = nextArg(ptr);
2017 if (ptr) {
2018 val = atoi(ptr);
2019 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2020 ar->auxSwitchChannelIndex = val;
2021 validArgumentCount++;
2025 if (validArgumentCount != 6) {
2026 memset(ar, 0, sizeof(adjustmentRange_t));
2027 cliShowParseError();
2029 } else {
2030 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
2035 #ifndef USE_QUAD_MIXER_ONLY
2036 static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer, const motorMixer_t *defaultCustomMotorMixer)
2038 const char *format = "mmix %d %s %s %s %s\r\n";
2039 char buf0[8];
2040 char buf1[FTOA_BUFFER_LENGTH];
2041 char buf2[FTOA_BUFFER_LENGTH];
2042 char buf3[FTOA_BUFFER_LENGTH];
2043 for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2044 if (customMotorMixer[i].throttle == 0.0f)
2045 break;
2046 const float thr = customMotorMixer[i].throttle;
2047 const float roll = customMotorMixer[i].roll;
2048 const float pitch = customMotorMixer[i].pitch;
2049 const float yaw = customMotorMixer[i].yaw;
2050 bool equalsDefault = false;
2051 if (defaultCustomMotorMixer) {
2052 const float thrDefault = defaultCustomMotorMixer[i].throttle;
2053 const float rollDefault = defaultCustomMotorMixer[i].roll;
2054 const float pitchDefault = defaultCustomMotorMixer[i].pitch;
2055 const float yawDefault = defaultCustomMotorMixer[i].yaw;
2056 const bool equalsDefault = thr == thrDefault && roll == rollDefault && pitch == pitchDefault && yaw == yawDefault;
2058 cliDefaultPrintf(dumpMask, equalsDefault, format,
2060 ftoa(thrDefault, buf0),
2061 ftoa(rollDefault, buf1),
2062 ftoa(pitchDefault, buf2),
2063 ftoa(yawDefault, buf3));
2065 cliDumpPrintf(dumpMask, equalsDefault, format,
2067 ftoa(thr, buf0),
2068 ftoa(roll, buf1),
2069 ftoa(pitch, buf2),
2070 ftoa(yaw, buf3));
2073 #endif // USE_QUAD_MIXER_ONLY
2075 static void cliMotorMix(char *cmdline)
2077 #ifdef USE_QUAD_MIXER_ONLY
2078 UNUSED(cmdline);
2079 #else
2080 int check = 0;
2081 uint8_t len;
2082 const char *ptr;
2084 if (isEmpty(cmdline)) {
2085 printMotorMix(DUMP_MASTER, customMotorMixer(0), NULL);
2086 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
2087 // erase custom mixer
2088 for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2089 customMotorMixerMutable(i)->throttle = 0.0f;
2091 } else if (strncasecmp(cmdline, "load", 4) == 0) {
2092 ptr = nextArg(cmdline);
2093 if (ptr) {
2094 len = strlen(ptr);
2095 for (uint32_t i = 0; ; i++) {
2096 if (mixerNames[i] == NULL) {
2097 cliPrint("Invalid name\r\n");
2098 break;
2100 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
2101 mixerLoadMix(i, customMotorMixerMutable(0));
2102 cliPrintf("Loaded %s\r\n", mixerNames[i]);
2103 cliMotorMix("");
2104 break;
2108 } else {
2109 ptr = cmdline;
2110 uint32_t i = atoi(ptr); // get motor number
2111 if (i < MAX_SUPPORTED_MOTORS) {
2112 ptr = nextArg(ptr);
2113 if (ptr) {
2114 customMotorMixerMutable(i)->throttle = fastA2F(ptr);
2115 check++;
2117 ptr = nextArg(ptr);
2118 if (ptr) {
2119 customMotorMixerMutable(i)->roll = fastA2F(ptr);
2120 check++;
2122 ptr = nextArg(ptr);
2123 if (ptr) {
2124 customMotorMixerMutable(i)->pitch = fastA2F(ptr);
2125 check++;
2127 ptr = nextArg(ptr);
2128 if (ptr) {
2129 customMotorMixerMutable(i)->yaw = fastA2F(ptr);
2130 check++;
2132 if (check != 4) {
2133 cliShowParseError();
2134 } else {
2135 printMotorMix(DUMP_MASTER, customMotorMixer(0), NULL);
2137 } else {
2138 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2141 #endif
2144 static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channelRangeConfigs, const rxChannelRangeConfig_t *defaultChannelRangeConfigs)
2146 const char *format = "rxrange %u %u %u\r\n";
2147 for (uint32_t i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
2148 bool equalsDefault = false;
2149 if (defaultChannelRangeConfigs) {
2150 equalsDefault = channelRangeConfigs[i].min == defaultChannelRangeConfigs[i].min
2151 && channelRangeConfigs[i].max == defaultChannelRangeConfigs[i].max;
2152 cliDefaultPrintf(dumpMask, equalsDefault, format,
2154 defaultChannelRangeConfigs[i].min,
2155 defaultChannelRangeConfigs[i].max
2158 cliDumpPrintf(dumpMask, equalsDefault, format,
2160 channelRangeConfigs[i].min,
2161 channelRangeConfigs[i].max
2166 static void cliRxRange(char *cmdline)
2168 int i, validArgumentCount = 0;
2169 const char *ptr;
2171 if (isEmpty(cmdline)) {
2172 printRxRange(DUMP_MASTER, rxChannelRangeConfigs(0), NULL);
2173 } else if (strcasecmp(cmdline, "reset") == 0) {
2174 resetAllRxChannelRangeConfigurations(rxChannelRangeConfigsMutable(0));
2175 } else {
2176 ptr = cmdline;
2177 i = atoi(ptr);
2178 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
2179 int rangeMin, rangeMax;
2181 ptr = nextArg(ptr);
2182 if (ptr) {
2183 rangeMin = atoi(ptr);
2184 validArgumentCount++;
2187 ptr = nextArg(ptr);
2188 if (ptr) {
2189 rangeMax = atoi(ptr);
2190 validArgumentCount++;
2193 if (validArgumentCount != 2) {
2194 cliShowParseError();
2195 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
2196 cliShowParseError();
2197 } else {
2198 rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigsMutable(i);
2199 channelRangeConfig->min = rangeMin;
2200 channelRangeConfig->max = rangeMax;
2202 } else {
2203 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
2208 #ifdef LED_STRIP
2209 static void printLed(uint8_t dumpMask, const ledConfig_t *ledConfigs, const ledConfig_t *defaultLedConfigs)
2211 const char *format = "led %u %s\r\n";
2212 char ledConfigBuffer[20];
2213 char ledConfigDefaultBuffer[20];
2214 for (uint32_t i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
2215 ledConfig_t ledConfig = ledConfigs[i];
2216 generateLedConfig(&ledConfig, ledConfigBuffer, sizeof(ledConfigBuffer));
2217 bool equalsDefault = false;
2218 if (defaultLedConfigs) {
2219 ledConfig_t ledConfigDefault = defaultLedConfigs[i];
2220 equalsDefault = ledConfig == ledConfigDefault;
2221 generateLedConfig(&ledConfigDefault, ledConfigDefaultBuffer, sizeof(ledConfigDefaultBuffer));
2222 cliDefaultPrintf(dumpMask, equalsDefault, format, i, ledConfigDefaultBuffer);
2224 cliDumpPrintf(dumpMask, equalsDefault, format, i, ledConfigBuffer);
2228 static void cliLed(char *cmdline)
2230 int i;
2231 const char *ptr;
2233 if (isEmpty(cmdline)) {
2234 printLed(DUMP_MASTER, ledStripConfig()->ledConfigs, NULL);
2235 } else {
2236 ptr = cmdline;
2237 i = atoi(ptr);
2238 if (i < LED_MAX_STRIP_LENGTH) {
2239 ptr = nextArg(cmdline);
2240 if (!parseLedStripConfig(i, ptr)) {
2241 cliShowParseError();
2243 } else {
2244 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH - 1);
2249 static void printColor(uint8_t dumpMask, const hsvColor_t *colors, const hsvColor_t *defaultColors)
2251 const char *format = "color %u %d,%u,%u\r\n";
2252 for (uint32_t i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
2253 const hsvColor_t *color = &colors[i];
2254 bool equalsDefault = false;
2255 if (defaultColors) {
2256 const hsvColor_t *colorDefault = &defaultColors[i];
2257 equalsDefault = color->h == colorDefault->h
2258 && color->s == colorDefault->s
2259 && color->v == colorDefault->v;
2260 cliDefaultPrintf(dumpMask, equalsDefault, format, i,colorDefault->h, colorDefault->s, colorDefault->v);
2262 cliDumpPrintf(dumpMask, equalsDefault, format, i, color->h, color->s, color->v);
2266 static void cliColor(char *cmdline)
2268 if (isEmpty(cmdline)) {
2269 printColor(DUMP_MASTER, ledStripConfig()->colors, NULL);
2270 } else {
2271 const char *ptr = cmdline;
2272 const int i = atoi(ptr);
2273 if (i < LED_CONFIGURABLE_COLOR_COUNT) {
2274 ptr = nextArg(cmdline);
2275 if (!parseColor(i, ptr)) {
2276 cliShowParseError();
2278 } else {
2279 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT - 1);
2284 static void printModeColor(uint8_t dumpMask, const ledStripConfig_t *ledStripConfig, const ledStripConfig_t *defaultLedStripConfig)
2286 const char *format = "mode_color %u %u %u\r\n";
2287 for (uint32_t i = 0; i < LED_MODE_COUNT; i++) {
2288 for (uint32_t j = 0; j < LED_DIRECTION_COUNT; j++) {
2289 int colorIndex = ledStripConfig->modeColors[i].color[j];
2290 bool equalsDefault = false;
2291 if (defaultLedStripConfig) {
2292 int colorIndexDefault = defaultLedStripConfig->modeColors[i].color[j];
2293 equalsDefault = colorIndex == colorIndexDefault;
2294 cliDefaultPrintf(dumpMask, equalsDefault, format, i, j, colorIndexDefault);
2296 cliDumpPrintf(dumpMask, equalsDefault, format, i, j, colorIndex);
2300 for (uint32_t j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
2301 const int colorIndex = ledStripConfig->specialColors.color[j];
2302 bool equalsDefault = false;
2303 if (defaultLedStripConfig) {
2304 const int colorIndexDefault = defaultLedStripConfig->specialColors.color[j];
2305 equalsDefault = colorIndex == colorIndexDefault;
2306 cliDefaultPrintf(dumpMask, equalsDefault, format, LED_SPECIAL, j, colorIndexDefault);
2308 cliDumpPrintf(dumpMask, equalsDefault, format, LED_SPECIAL, j, colorIndex);
2311 const int ledStripAuxChannel = ledStripConfig->ledstrip_aux_channel;
2312 bool equalsDefault = false;
2313 if (defaultLedStripConfig) {
2314 const int ledStripAuxChannelDefault = defaultLedStripConfig->ledstrip_aux_channel;
2315 equalsDefault = ledStripAuxChannel == ledStripAuxChannelDefault;
2316 cliDefaultPrintf(dumpMask, equalsDefault, format, LED_AUX_CHANNEL, 0, ledStripAuxChannelDefault);
2318 cliDumpPrintf(dumpMask, equalsDefault, format, LED_AUX_CHANNEL, 0, ledStripAuxChannel);
2321 static void cliModeColor(char *cmdline)
2323 if (isEmpty(cmdline)) {
2324 printModeColor(DUMP_MASTER, ledStripConfig(), NULL);
2325 } else {
2326 enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
2327 int args[ARGS_COUNT];
2328 int argNo = 0;
2329 char *saveptr;
2330 const char* ptr = strtok_r(cmdline, " ", &saveptr);
2331 while (ptr && argNo < ARGS_COUNT) {
2332 args[argNo++] = atoi(ptr);
2333 ptr = strtok_r(NULL, " ", &saveptr);
2336 if (ptr != NULL || argNo != ARGS_COUNT) {
2337 cliShowParseError();
2338 return;
2341 int modeIdx = args[MODE];
2342 int funIdx = args[FUNCTION];
2343 int color = args[COLOR];
2344 if(!setModeColor(modeIdx, funIdx, color)) {
2345 cliShowParseError();
2346 return;
2348 // values are validated
2349 cliPrintf("mode_color %u %u %u\r\n", modeIdx, funIdx, color);
2352 #endif
2354 #ifdef USE_SERVOS
2355 static void printServo(uint8_t dumpMask, const servoParam_t *servoParams, const servoParam_t *defaultServoParams)
2357 // print out servo settings
2358 const char *format = "servo %u %d %d %d %d %d\r\n";
2359 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2360 const servoParam_t *servoConf = &servoParams[i];
2361 bool equalsDefault = false;
2362 if (defaultServoParams) {
2363 const servoParam_t *defaultServoConf = &defaultServoParams[i];
2364 equalsDefault = servoConf->min == defaultServoConf->min
2365 && servoConf->max == defaultServoConf->max
2366 && servoConf->middle == defaultServoConf->middle
2367 && servoConf->rate == defaultServoConf->rate
2368 && servoConf->forwardFromChannel == defaultServoConf->forwardFromChannel;
2369 cliDefaultPrintf(dumpMask, equalsDefault, format,
2371 defaultServoConf->min,
2372 defaultServoConf->max,
2373 defaultServoConf->middle,
2374 defaultServoConf->rate,
2375 defaultServoConf->forwardFromChannel
2378 cliDumpPrintf(dumpMask, equalsDefault, format,
2380 servoConf->min,
2381 servoConf->max,
2382 servoConf->middle,
2383 servoConf->rate,
2384 servoConf->forwardFromChannel
2387 // print servo directions
2388 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2389 const char *format = "smix reverse %d %d r\r\n";
2390 const servoParam_t *servoConf = &servoParams[i];
2391 const servoParam_t *servoConfDefault = &defaultServoParams[i];
2392 if (defaultServoParams) {
2393 bool equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources;
2394 for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2395 equalsDefault = ~(servoConf->reversedSources ^ servoConfDefault->reversedSources) & (1 << channel);
2396 if (servoConfDefault->reversedSources & (1 << channel)) {
2397 cliDefaultPrintf(dumpMask, equalsDefault, format, i , channel);
2399 if (servoConf->reversedSources & (1 << channel)) {
2400 cliDumpPrintf(dumpMask, equalsDefault, format, i , channel);
2403 } else {
2404 for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2405 if (servoConf->reversedSources & (1 << channel)) {
2406 cliDumpPrintf(dumpMask, true, format, i , channel);
2413 static void cliServo(char *cmdline)
2415 enum { SERVO_ARGUMENT_COUNT = 6 };
2416 int16_t arguments[SERVO_ARGUMENT_COUNT];
2418 servoParam_t *servo;
2420 int i;
2421 char *ptr;
2423 if (isEmpty(cmdline)) {
2424 printServo(DUMP_MASTER, servoParams(0), NULL);
2425 } else {
2426 int validArgumentCount = 0;
2428 ptr = cmdline;
2430 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
2432 // If command line doesn't fit the format, don't modify the config
2433 while (*ptr) {
2434 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
2435 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
2436 cliShowParseError();
2437 return;
2440 arguments[validArgumentCount++] = atoi(ptr);
2442 do {
2443 ptr++;
2444 } while (*ptr >= '0' && *ptr <= '9');
2445 } else if (*ptr == ' ') {
2446 ptr++;
2447 } else {
2448 cliShowParseError();
2449 return;
2453 enum {INDEX = 0, MIN, MAX, MIDDLE, RATE, FORWARD};
2455 i = arguments[INDEX];
2457 // Check we got the right number of args and the servo index is correct (don't validate the other values)
2458 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
2459 cliShowParseError();
2460 return;
2463 servo = servoParamsMutable(i);
2465 if (
2466 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
2467 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
2468 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
2469 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
2470 arguments[RATE] < -100 || arguments[RATE] > 100 ||
2471 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
2473 cliShowParseError();
2474 return;
2477 servo->min = arguments[MIN];
2478 servo->max = arguments[MAX];
2479 servo->middle = arguments[MIDDLE];
2480 servo->rate = arguments[RATE];
2481 servo->forwardFromChannel = arguments[FORWARD];
2484 #endif
2486 #ifdef USE_SERVOS
2487 static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixers, const servoMixer_t *defaultCustomServoMixers)
2489 const char *format = "smix %d %d %d %d %d %d %d %d\r\n";
2490 for (uint32_t i = 0; i < MAX_SERVO_RULES; i++) {
2491 const servoMixer_t customServoMixer = customServoMixers[i];
2492 if (customServoMixer.rate == 0) {
2493 break;
2496 bool equalsDefault = false;
2497 if (defaultCustomServoMixers) {
2498 servoMixer_t customServoMixerDefault = defaultCustomServoMixers[i];
2499 equalsDefault = customServoMixer.targetChannel == customServoMixerDefault.targetChannel
2500 && customServoMixer.inputSource == customServoMixerDefault.inputSource
2501 && customServoMixer.rate == customServoMixerDefault.rate
2502 && customServoMixer.speed == customServoMixerDefault.speed
2503 && customServoMixer.min == customServoMixerDefault.min
2504 && customServoMixer.max == customServoMixerDefault.max
2505 && customServoMixer.box == customServoMixerDefault.box;
2507 cliDefaultPrintf(dumpMask, equalsDefault, format,
2509 customServoMixerDefault.targetChannel,
2510 customServoMixerDefault.inputSource,
2511 customServoMixerDefault.rate,
2512 customServoMixerDefault.speed,
2513 customServoMixerDefault.min,
2514 customServoMixerDefault.max,
2515 customServoMixerDefault.box
2518 cliDumpPrintf(dumpMask, equalsDefault, format,
2520 customServoMixer.targetChannel,
2521 customServoMixer.inputSource,
2522 customServoMixer.rate,
2523 customServoMixer.speed,
2524 customServoMixer.min,
2525 customServoMixer.max,
2526 customServoMixer.box
2530 cliPrint("\r\n");
2533 static void cliServoMix(char *cmdline)
2535 int args[8], check = 0;
2536 int len = strlen(cmdline);
2538 if (len == 0) {
2539 printServoMix(DUMP_MASTER, customServoMixers(0), NULL);
2540 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
2541 // erase custom mixer
2542 memset(customServoMixers_array(), 0, sizeof(*customServoMixers_array()));
2543 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2544 servoParamsMutable(i)->reversedSources = 0;
2546 } else if (strncasecmp(cmdline, "load", 4) == 0) {
2547 const char *ptr = nextArg(cmdline);
2548 if (ptr) {
2549 len = strlen(ptr);
2550 for (uint32_t i = 0; ; i++) {
2551 if (mixerNames[i] == NULL) {
2552 cliPrintf("Invalid name\r\n");
2553 break;
2555 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
2556 servoMixerLoadMix(i);
2557 cliPrintf("Loaded %s\r\n", mixerNames[i]);
2558 cliServoMix("");
2559 break;
2563 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
2564 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
2565 char *ptr = strchr(cmdline, ' ');
2567 len = strlen(ptr);
2568 if (len == 0) {
2569 cliPrintf("s");
2570 for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
2571 cliPrintf("\ti%d", inputSource);
2572 cliPrintf("\r\n");
2574 for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
2575 cliPrintf("%d", servoIndex);
2576 for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
2577 cliPrintf("\t%s ", (servoParams(servoIndex)->reversedSources & (1 << inputSource)) ? "r" : "n");
2578 cliPrintf("\r\n");
2580 return;
2583 char *saveptr;
2584 ptr = strtok_r(ptr, " ", &saveptr);
2585 while (ptr != NULL && check < ARGS_COUNT - 1) {
2586 args[check++] = atoi(ptr);
2587 ptr = strtok_r(NULL, " ", &saveptr);
2590 if (ptr == NULL || check != ARGS_COUNT - 1) {
2591 cliShowParseError();
2592 return;
2595 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
2596 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
2597 && (*ptr == 'r' || *ptr == 'n')) {
2598 if (*ptr == 'r')
2599 servoParamsMutable(args[SERVO])->reversedSources |= 1 << args[INPUT];
2600 else
2601 servoParamsMutable(args[SERVO])->reversedSources &= ~(1 << args[INPUT]);
2602 } else
2603 cliShowParseError();
2605 cliServoMix("reverse");
2606 } else {
2607 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
2608 char *saveptr;
2609 char *ptr = strtok_r(cmdline, " ", &saveptr);
2610 while (ptr != NULL && check < ARGS_COUNT) {
2611 args[check++] = atoi(ptr);
2612 ptr = strtok_r(NULL, " ", &saveptr);
2615 if (ptr != NULL || check != ARGS_COUNT) {
2616 cliShowParseError();
2617 return;
2620 int32_t i = args[RULE];
2621 if (i >= 0 && i < MAX_SERVO_RULES &&
2622 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
2623 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
2624 args[RATE] >= -100 && args[RATE] <= 100 &&
2625 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
2626 args[MIN] >= 0 && args[MIN] <= 100 &&
2627 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
2628 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
2629 customServoMixersMutable(i)->targetChannel = args[TARGET];
2630 customServoMixersMutable(i)->inputSource = args[INPUT];
2631 customServoMixersMutable(i)->rate = args[RATE];
2632 customServoMixersMutable(i)->speed = args[SPEED];
2633 customServoMixersMutable(i)->min = args[MIN];
2634 customServoMixersMutable(i)->max = args[MAX];
2635 customServoMixersMutable(i)->box = args[BOX];
2636 cliServoMix("");
2637 } else {
2638 cliShowParseError();
2642 #endif
2644 #ifdef USE_SDCARD
2646 static void cliWriteBytes(const uint8_t *buffer, int count)
2648 while (count > 0) {
2649 cliWrite(*buffer);
2650 buffer++;
2651 count--;
2655 static void cliSdInfo(char *cmdline)
2657 UNUSED(cmdline);
2659 cliPrint("SD card: ");
2661 if (!sdcard_isInserted()) {
2662 cliPrint("None inserted\r\n");
2663 return;
2666 if (!sdcard_isInitialized()) {
2667 cliPrint("Startup failed\r\n");
2668 return;
2671 const sdcardMetadata_t *metadata = sdcard_getMetadata();
2673 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
2674 metadata->manufacturerID,
2675 metadata->numBlocks / 2, /* One block is half a kB */
2676 metadata->productionMonth,
2677 metadata->productionYear,
2678 metadata->productRevisionMajor,
2679 metadata->productRevisionMinor
2682 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
2684 cliPrint("'\r\n" "Filesystem: ");
2686 switch (afatfs_getFilesystemState()) {
2687 case AFATFS_FILESYSTEM_STATE_READY:
2688 cliPrint("Ready");
2689 break;
2690 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
2691 cliPrint("Initializing");
2692 break;
2693 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
2694 case AFATFS_FILESYSTEM_STATE_FATAL:
2695 cliPrint("Fatal");
2697 switch (afatfs_getLastError()) {
2698 case AFATFS_ERROR_BAD_MBR:
2699 cliPrint(" - no FAT MBR partitions");
2700 break;
2701 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
2702 cliPrint(" - bad FAT header");
2703 break;
2704 case AFATFS_ERROR_GENERIC:
2705 case AFATFS_ERROR_NONE:
2706 ; // Nothing more detailed to print
2707 break;
2709 break;
2711 cliPrint("\r\n");
2714 #endif
2716 #ifdef USE_FLASHFS
2718 static void cliFlashInfo(char *cmdline)
2720 const flashGeometry_t *layout = flashfsGetGeometry();
2722 UNUSED(cmdline);
2724 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
2725 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
2729 static void cliFlashErase(char *cmdline)
2731 UNUSED(cmdline);
2733 #ifndef MINIMAL_CLI
2734 uint32_t i = 0;
2735 cliPrintf("Erasing, please wait ... \r\n");
2736 #else
2737 cliPrintf("Erasing,\r\n");
2738 #endif
2740 bufWriterFlush(cliWriter);
2741 flashfsEraseCompletely();
2743 while (!flashfsIsReady()) {
2744 #ifndef MINIMAL_CLI
2745 cliPrintf(".");
2746 if (i++ > 120) {
2747 i=0;
2748 cliPrintf("\r\n");
2751 bufWriterFlush(cliWriter);
2752 #endif
2753 delay(100);
2755 beeper(BEEPER_BLACKBOX_ERASE);
2756 cliPrintf("\r\nDone.\r\n");
2759 #ifdef USE_FLASH_TOOLS
2761 static void cliFlashWrite(char *cmdline)
2763 const uint32_t address = atoi(cmdline);
2764 const char *text = strchr(cmdline, ' ');
2766 if (!text) {
2767 cliShowParseError();
2768 } else {
2769 flashfsSeekAbs(address);
2770 flashfsWrite((uint8_t*)text, strlen(text), true);
2771 flashfsFlushSync();
2773 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
2777 static void cliFlashRead(char *cmdline)
2779 uint32_t address = atoi(cmdline);
2781 const char *nextArg = strchr(cmdline, ' ');
2783 if (!nextArg) {
2784 cliShowParseError();
2785 } else {
2786 uint32_t length = atoi(nextArg);
2788 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
2790 uint8_t buffer[32];
2791 while (length > 0) {
2792 int bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
2794 for (int i = 0; i < bytesRead; i++) {
2795 cliWrite(buffer[i]);
2798 length -= bytesRead;
2799 address += bytesRead;
2801 if (bytesRead == 0) {
2802 //Assume we reached the end of the volume or something fatal happened
2803 break;
2806 cliPrintf("\r\n");
2810 #endif
2811 #endif
2813 #ifdef VTX_CONTROL
2814 static void printVtx(uint8_t dumpMask, const vtxConfig_t *vtxConfig, const vtxConfig_t *vtxConfigDefault)
2816 // print out vtx channel settings
2817 const char *format = "vtx %u %u %u %u %u %u\r\n";
2818 bool equalsDefault = false;
2819 for (uint32_t i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
2820 const vtxChannelActivationCondition_t *cac = &vtxConfig->vtxChannelActivationConditions[i];
2821 if (vtxConfigDefault) {
2822 const vtxChannelActivationCondition_t *cacDefault = &vtxConfigDefault->vtxChannelActivationConditions[i];
2823 equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
2824 && cac->band == cacDefault->band
2825 && cac->channel == cacDefault->channel
2826 && cac->range.startStep == cacDefault->range.startStep
2827 && cac->range.endStep == cacDefault->range.endStep;
2828 cliDefaultPrintf(dumpMask, equalsDefault, format,
2830 cacDefault->auxChannelIndex,
2831 cacDefault->band,
2832 cacDefault->channel,
2833 MODE_STEP_TO_CHANNEL_VALUE(cacDefault->range.startStep),
2834 MODE_STEP_TO_CHANNEL_VALUE(cacDefault->range.endStep)
2837 cliDumpPrintf(dumpMask, equalsDefault, format,
2839 cac->auxChannelIndex,
2840 cac->band,
2841 cac->channel,
2842 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
2843 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
2848 // FIXME remove these and use the VTX API
2849 #define VTX_BAND_MIN 1
2850 #define VTX_BAND_MAX 5
2851 #define VTX_CHANNEL_MIN 1
2852 #define VTX_CHANNEL_MAX 8
2854 static void cliVtx(char *cmdline)
2856 int i, val = 0;
2857 const char *ptr;
2859 if (isEmpty(cmdline)) {
2860 printVtx(DUMP_MASTER, vtxConfig(), NULL);
2861 } else {
2862 ptr = cmdline;
2863 i = atoi(ptr++);
2864 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
2865 vtxChannelActivationCondition_t *cac = &vtxConfigMutable()->vtxChannelActivationConditions[i];
2866 uint8_t validArgumentCount = 0;
2867 ptr = nextArg(ptr);
2868 if (ptr) {
2869 val = atoi(ptr);
2870 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2871 cac->auxChannelIndex = val;
2872 validArgumentCount++;
2875 ptr = nextArg(ptr);
2876 if (ptr) {
2877 val = atoi(ptr);
2878 // FIXME Use VTX API to get min/max
2879 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
2880 cac->band = val;
2881 validArgumentCount++;
2884 ptr = nextArg(ptr);
2885 if (ptr) {
2886 val = atoi(ptr);
2887 // FIXME Use VTX API to get min/max
2888 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
2889 cac->channel = val;
2890 validArgumentCount++;
2893 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
2895 if (validArgumentCount != 5) {
2896 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
2898 } else {
2899 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
2904 #endif // VTX_CONTROL
2906 static void printName(uint8_t dumpMask, const systemConfig_t *systemConfig)
2908 const bool equalsDefault = strlen(systemConfig->name) == 0;
2909 cliDumpPrintf(dumpMask, equalsDefault, "name %s\r\n", equalsDefault ? emptyName : systemConfig->name);
2912 static void cliName(char *cmdline)
2914 const uint32_t len = strlen(cmdline);
2915 if (len > 0) {
2916 memset(systemConfigMutable()->name, 0, ARRAYLEN(systemConfig()->name));
2917 if (strncmp(cmdline, emptyName, len)) {
2918 strncpy(systemConfigMutable()->name, cmdline, MIN(len, MAX_NAME_LENGTH));
2921 printName(DUMP_MASTER, systemConfig());
2924 static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig, const featureConfig_t *featureConfigDefault)
2926 const uint32_t mask = featureConfig->enabledFeatures;
2927 const uint32_t defaultMask = featureConfigDefault->enabledFeatures;
2928 for (uint32_t i = 0; featureNames[i]; i++) { // disable all feature first
2929 const char *format = "feature -%s\r\n";
2930 cliDefaultPrintf(dumpMask, (defaultMask | ~mask) & (1 << i), format, featureNames[i]);
2931 cliDumpPrintf(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
2933 for (uint32_t i = 0; featureNames[i]; i++) { // reenable what we want.
2934 const char *format = "feature %s\r\n";
2935 if (defaultMask & (1 << i)) {
2936 cliDefaultPrintf(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
2938 if (mask & (1 << i)) {
2939 cliDumpPrintf(dumpMask, (defaultMask | ~mask) & (1 << i), format, featureNames[i]);
2944 static void cliFeature(char *cmdline)
2946 uint32_t len = strlen(cmdline);
2947 uint32_t mask = featureMask();
2949 if (len == 0) {
2950 cliPrint("Enabled: ");
2951 for (uint32_t i = 0; ; i++) {
2952 if (featureNames[i] == NULL)
2953 break;
2954 if (mask & (1 << i))
2955 cliPrintf("%s ", featureNames[i]);
2957 cliPrint("\r\n");
2958 } else if (strncasecmp(cmdline, "list", len) == 0) {
2959 cliPrint("Available:");
2960 for (uint32_t i = 0; ; i++) {
2961 if (featureNames[i] == NULL)
2962 break;
2963 cliPrintf(" %s", featureNames[i]);
2965 cliPrint("\r\n");
2966 return;
2967 } else {
2968 bool remove = false;
2969 if (cmdline[0] == '-') {
2970 // remove feature
2971 remove = true;
2972 cmdline++; // skip over -
2973 len--;
2976 for (uint32_t i = 0; ; i++) {
2977 if (featureNames[i] == NULL) {
2978 cliPrint("Invalid name\r\n");
2979 break;
2982 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2984 mask = 1 << i;
2985 #ifndef GPS
2986 if (mask & FEATURE_GPS) {
2987 cliPrint("unavailable\r\n");
2988 break;
2990 #endif
2991 #ifndef SONAR
2992 if (mask & FEATURE_SONAR) {
2993 cliPrint("unavailable\r\n");
2994 break;
2996 #endif
2997 if (remove) {
2998 featureClear(mask);
2999 cliPrint("Disabled");
3000 } else {
3001 featureSet(mask);
3002 cliPrint("Enabled");
3004 cliPrintf(" %s\r\n", featureNames[i]);
3005 break;
3011 #ifdef BEEPER
3012 static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
3014 const uint8_t beeperCount = beeperTableEntryCount();
3015 const uint32_t mask = beeperConfig->beeper_off_flags;
3016 const uint32_t defaultMask = beeperConfigDefault->beeper_off_flags;
3017 for (int32_t i = 0; i < beeperCount - 2; i++) {
3018 const char *formatOff = "beeper -%s\r\n";
3019 const char *formatOn = "beeper %s\r\n";
3020 cliDefaultPrintf(dumpMask, ~(mask ^ defaultMask) & (1 << i), mask & (1 << i) ? formatOn : formatOff, beeperNameForTableIndex(i));
3021 cliDumpPrintf(dumpMask, ~(mask ^ defaultMask) & (1 << i), mask & (1 << i) ? formatOff : formatOn, beeperNameForTableIndex(i));
3025 static void cliBeeper(char *cmdline)
3027 uint32_t len = strlen(cmdline);
3028 uint8_t beeperCount = beeperTableEntryCount();
3029 uint32_t mask = getBeeperOffMask();
3031 if (len == 0) {
3032 cliPrintf("Disabled:");
3033 for (int32_t i = 0; ; i++) {
3034 if (i == beeperCount - 2){
3035 if (mask == 0)
3036 cliPrint(" none");
3037 break;
3039 if (mask & (1 << i))
3040 cliPrintf(" %s", beeperNameForTableIndex(i));
3042 cliPrint("\r\n");
3043 } else if (strncasecmp(cmdline, "list", len) == 0) {
3044 cliPrint("Available:");
3045 for (uint32_t i = 0; i < beeperCount; i++)
3046 cliPrintf(" %s", beeperNameForTableIndex(i));
3047 cliPrint("\r\n");
3048 return;
3049 } else {
3050 bool remove = false;
3051 if (cmdline[0] == '-') {
3052 remove = true; // this is for beeper OFF condition
3053 cmdline++;
3054 len--;
3057 for (uint32_t i = 0; ; i++) {
3058 if (i == beeperCount) {
3059 cliPrint("Invalid name\r\n");
3060 break;
3062 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
3063 if (remove) { // beeper off
3064 if (i == BEEPER_ALL-1)
3065 beeperOffSetAll(beeperCount-2);
3066 else
3067 if (i == BEEPER_PREFERENCE-1)
3068 setBeeperOffMask(getPreferredBeeperOffMask());
3069 else {
3070 mask = 1 << i;
3071 beeperOffSet(mask);
3073 cliPrint("Disabled");
3075 else { // beeper on
3076 if (i == BEEPER_ALL-1)
3077 beeperOffClearAll();
3078 else
3079 if (i == BEEPER_PREFERENCE-1)
3080 setPreferredBeeperOffMask(getBeeperOffMask());
3081 else {
3082 mask = 1 << i;
3083 beeperOffClear(mask);
3085 cliPrint("Enabled");
3087 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
3088 break;
3093 #endif
3095 static void printMap(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfig_t *defaultRxConfig)
3097 bool equalsDefault = true;
3098 char buf[16];
3099 char bufDefault[16];
3100 uint32_t i;
3101 for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
3102 buf[rxConfig->rcmap[i]] = rcChannelLetters[i];
3103 if (defaultRxConfig) {
3104 bufDefault[defaultRxConfig->rcmap[i]] = rcChannelLetters[i];
3105 equalsDefault = equalsDefault && (rxConfig->rcmap[i] == defaultRxConfig->rcmap[i]);
3108 buf[i] = '\0';
3110 const char *formatMap = "map %s\r\n";
3111 cliDefaultPrintf(dumpMask, equalsDefault, formatMap, bufDefault);
3112 cliDumpPrintf(dumpMask, equalsDefault, formatMap, buf);
3115 static void cliMap(char *cmdline)
3117 uint32_t len;
3118 char out[9];
3120 len = strlen(cmdline);
3122 if (len == 8) {
3123 // uppercase it
3124 for (uint32_t i = 0; i < 8; i++)
3125 cmdline[i] = toupper((unsigned char)cmdline[i]);
3126 for (uint32_t i = 0; i < 8; i++) {
3127 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
3128 continue;
3129 cliShowParseError();
3130 return;
3132 parseRcChannels(cmdline, rxConfigMutable());
3134 cliPrint("Map: ");
3135 uint32_t i;
3136 for (i = 0; i < 8; i++)
3137 out[rxConfig()->rcmap[i]] = rcChannelLetters[i];
3138 out[i] = '\0';
3139 cliPrintf("%s\r\n", out);
3142 static char *checkCommand(char *cmdLine, const char *command)
3144 if(!strncasecmp(cmdLine, command, strlen(command)) // command names match
3145 && (isspace((unsigned)cmdLine[strlen(command)]) || cmdLine[strlen(command)] == 0)) {
3146 return cmdLine + strlen(command) + 1;
3147 } else {
3148 return 0;
3152 static void cliRebootEx(bool bootLoader)
3154 cliPrint("\r\nRebooting");
3155 bufWriterFlush(cliWriter);
3156 waitForSerialPortToFinishTransmitting(cliPort);
3157 stopPwmAllMotors();
3158 if (bootLoader) {
3159 systemResetToBootloader();
3160 return;
3162 systemReset();
3165 static void cliReboot(void)
3167 cliRebootEx(false);
3170 static void cliBootloader(char *cmdLine)
3172 UNUSED(cmdLine);
3174 cliPrintHashLine("restarting in bootloader mode");
3175 cliRebootEx(true);
3178 static void cliExit(char *cmdline)
3180 UNUSED(cmdline);
3182 cliPrintHashLine("leaving CLI mode, unsaved changes lost");
3183 bufWriterFlush(cliWriter);
3185 *cliBuffer = '\0';
3186 bufferIndex = 0;
3187 cliMode = 0;
3188 // incase a motor was left running during motortest, clear it here
3189 mixerResetDisarmedMotors();
3190 cliReboot();
3192 cliWriter = NULL;
3195 #ifdef GPS
3196 static void cliGpsPassthrough(char *cmdline)
3198 UNUSED(cmdline);
3200 gpsEnablePassthrough(cliPort);
3202 #endif
3204 #if defined(USE_ESCSERIAL) || defined(USE_DSHOT)
3206 #ifndef ALL_ESCS
3207 #define ALL_ESCS 255
3208 #endif
3210 static int parseEscNumber(char *pch, bool allowAllEscs) {
3211 int escNumber = atoi(pch);
3212 if ((escNumber >= 0) && (escNumber < getMotorCount())) {
3213 printf("Programming on ESC %d.\r\n", escNumber);
3214 } else if (allowAllEscs && escNumber == ALL_ESCS) {
3215 printf("Programming on all ESCs.\r\n");
3216 } else {
3217 printf("Invalid ESC number, range: 0 to %d.\r\n", getMotorCount() - 1);
3219 return -1;
3222 return escNumber;
3224 #endif
3226 #ifdef USE_DSHOT
3227 static void cliDshotProg(char *cmdline)
3229 if (isEmpty(cmdline) || motorConfig()->dev.motorPwmProtocol < PWM_TYPE_DSHOT150) {
3230 cliShowParseError();
3232 return;
3235 char *saveptr;
3236 char *pch = strtok_r(cmdline, " ", &saveptr);
3237 int pos = 0;
3238 int escNumber = 0;
3239 while (pch != NULL) {
3240 switch (pos) {
3241 case 0:
3242 escNumber = parseEscNumber(pch, true);
3243 if (escNumber == -1) {
3244 return;
3247 break;
3248 default:
3249 motorControlEnable = false;
3251 int command = atoi(pch);
3252 if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
3253 if (escNumber == ALL_ESCS) {
3254 for (unsigned i = 0; i < getMotorCount(); i++) {
3255 pwmWriteDshotCommand(i, command);
3257 } else {
3258 pwmWriteDshotCommand(escNumber, command);
3261 if (command <= 5) {
3262 delay(10); // wait for sound output to finish
3265 printf("Command %d written.\r\n", command);
3266 } else {
3267 printf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
3270 break;
3273 pos++;
3274 pch = strtok_r(NULL, " ", &saveptr);
3277 motorControlEnable = true;
3279 #endif
3281 #ifdef USE_ESCSERIAL
3282 static void cliEscPassthrough(char *cmdline)
3284 if (isEmpty(cmdline)) {
3285 cliShowParseError();
3287 return;
3290 char *saveptr;
3291 char *pch = strtok_r(cmdline, " ", &saveptr);
3292 int pos = 0;
3293 uint8_t mode = 0;
3294 int escNumber = 0;
3295 while (pch != NULL) {
3296 switch (pos) {
3297 case 0:
3298 if(strncasecmp(pch, "sk", strlen(pch)) == 0) {
3299 mode = PROTOCOL_SIMONK;
3300 } else if(strncasecmp(pch, "bl", strlen(pch)) == 0) {
3301 mode = PROTOCOL_BLHELI;
3302 } else if(strncasecmp(pch, "ki", strlen(pch)) == 0) {
3303 mode = PROTOCOL_KISS;
3304 } else if(strncasecmp(pch, "cc", strlen(pch)) == 0) {
3305 mode = PROTOCOL_KISSALL;
3306 } else {
3307 cliShowParseError();
3309 return;
3311 break;
3312 case 1:
3313 escNumber = parseEscNumber(pch, mode == PROTOCOL_KISS);
3314 if (escNumber == -1) {
3315 return;
3318 break;
3319 default:
3320 cliShowParseError();
3322 return;
3324 break;
3327 pos++;
3328 pch = strtok_r(NULL, " ", &saveptr);
3331 escEnablePassthrough(cliPort, escNumber, mode);
3333 #endif
3335 #ifndef USE_QUAD_MIXER_ONLY
3336 static void cliMixer(char *cmdline)
3338 int len;
3340 len = strlen(cmdline);
3342 if (len == 0) {
3343 cliPrintf("Mixer: %s\r\n", mixerNames[mixerConfig()->mixerMode - 1]);
3344 return;
3345 } else if (strncasecmp(cmdline, "list", len) == 0) {
3346 cliPrint("Available:");
3347 for (uint32_t i = 0; ; i++) {
3348 if (mixerNames[i] == NULL)
3349 break;
3350 cliPrintf(" %s", mixerNames[i]);
3352 cliPrint("\r\n");
3353 return;
3356 for (uint32_t i = 0; ; i++) {
3357 if (mixerNames[i] == NULL) {
3358 cliPrint("Invalid name\r\n");
3359 return;
3361 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
3362 mixerConfigMutable()->mixerMode = i + 1;
3363 break;
3367 cliMixer("");
3369 #endif
3371 static void cliMotor(char *cmdline)
3373 int motor_index = 0;
3374 int motor_value = 0;
3375 int index = 0;
3376 char *pch = NULL;
3377 char *saveptr;
3379 if (isEmpty(cmdline)) {
3380 cliShowParseError();
3381 return;
3384 pch = strtok_r(cmdline, " ", &saveptr);
3385 while (pch != NULL) {
3386 switch (index) {
3387 case 0:
3388 motor_index = atoi(pch);
3389 break;
3390 case 1:
3391 motor_value = atoi(pch);
3392 break;
3394 index++;
3395 pch = strtok_r(NULL, " ", &saveptr);
3398 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
3399 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
3400 return;
3403 if (index == 2) {
3404 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
3405 cliShowArgumentRangeError("value", 1000, 2000);
3406 } else {
3407 motor_disarmed[motor_index] = convertExternalToMotor(motor_value);
3409 cliPrintf("motor %d: %d\r\n", motor_index, convertMotorToExternal(motor_disarmed[motor_index]));
3415 #ifndef MINIMAL_CLI
3416 static void cliPlaySound(char *cmdline)
3418 int i;
3419 const char *name;
3420 static int lastSoundIdx = -1;
3422 if (isEmpty(cmdline)) {
3423 i = lastSoundIdx + 1; //next sound index
3424 if ((name=beeperNameForTableIndex(i)) == NULL) {
3425 while (true) { //no name for index; try next one
3426 if (++i >= beeperTableEntryCount())
3427 i = 0; //if end then wrap around to first entry
3428 if ((name=beeperNameForTableIndex(i)) != NULL)
3429 break; //if name OK then play sound below
3430 if (i == lastSoundIdx + 1) { //prevent infinite loop
3431 cliPrintf("Error playing sound\r\n");
3432 return;
3436 } else { //index value was given
3437 i = atoi(cmdline);
3438 if ((name=beeperNameForTableIndex(i)) == NULL) {
3439 cliPrintf("No sound for index %d\r\n", i);
3440 return;
3443 lastSoundIdx = i;
3444 beeperSilence();
3445 cliPrintf("Playing sound %d: %s\r\n", i, name);
3446 beeper(beeperModeForTableIndex(i));
3448 #endif
3450 static void cliProfile(char *cmdline)
3452 if (isEmpty(cmdline)) {
3453 cliPrintf("profile %d\r\n", getCurrentPidProfileIndex());
3454 return;
3455 } else {
3456 const int i = atoi(cmdline);
3457 if (i >= 0 && i < MAX_PROFILE_COUNT) {
3458 systemConfigMutable()->pidProfileIndex = i;
3459 cliProfile("");
3464 static void cliRateProfile(char *cmdline)
3466 if (isEmpty(cmdline)) {
3467 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfileIndex());
3468 return;
3469 } else {
3470 const int i = atoi(cmdline);
3471 if (i >= 0 && i < CONTROL_RATE_PROFILE_COUNT) {
3472 changeControlRateProfile(i);
3473 cliRateProfile("");
3478 static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask)
3480 if (pidProfileIndex >= MAX_PROFILE_COUNT) {
3481 // Faulty values
3482 return;
3484 changePidProfile(pidProfileIndex);
3485 cliPrintHashLine("profile");
3486 cliProfile("");
3487 cliPrint("\r\n");
3488 dumpAllValues(PROFILE_VALUE, dumpMask);
3491 static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask)
3493 if (rateProfileIndex >= CONTROL_RATE_PROFILE_COUNT) {
3494 // Faulty values
3495 return;
3497 changeControlRateProfile(rateProfileIndex);
3498 cliPrintHashLine("rateprofile");
3499 cliRateProfile("");
3500 cliPrint("\r\n");
3501 dumpAllValues(PROFILE_RATE_VALUE, dumpMask);
3504 static void cliSave(char *cmdline)
3506 UNUSED(cmdline);
3508 cliPrintHashLine("saving");
3509 writeEEPROM();
3510 cliReboot();
3513 static void cliDefaults(char *cmdline)
3515 UNUSED(cmdline);
3517 cliPrintHashLine("resetting to defaults");
3518 resetEEPROM();
3519 cliReboot();
3522 static void cliGet(char *cmdline)
3524 const clivalue_t *val;
3525 int matchedCommands = 0;
3527 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3528 if (strstr(valueTable[i].name, cmdline)) {
3529 val = &valueTable[i];
3530 cliPrintf("%s = ", valueTable[i].name);
3531 cliPrintVar(val, 0);
3532 cliPrint("\r\n");
3533 cliPrintVarRange(val);
3534 cliPrint("\r\n");
3536 matchedCommands++;
3541 if (matchedCommands) {
3542 return;
3545 cliPrint("Invalid name\r\n");
3548 static void cliSet(char *cmdline)
3550 uint32_t len;
3551 const clivalue_t *val;
3552 char *eqptr = NULL;
3554 len = strlen(cmdline);
3556 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
3557 cliPrint("Current settings: \r\n");
3558 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3559 val = &valueTable[i];
3560 cliPrintf("%s = ", valueTable[i].name);
3561 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
3562 cliPrint("\r\n");
3564 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
3565 // has equals
3567 char *lastNonSpaceCharacter = eqptr;
3568 while (*(lastNonSpaceCharacter - 1) == ' ') {
3569 lastNonSpaceCharacter--;
3571 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
3573 // skip the '=' and any ' ' characters
3574 eqptr++;
3575 while (*(eqptr) == ' ') {
3576 eqptr++;
3579 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3580 val = &valueTable[i];
3581 // ensure exact match when setting to prevent setting variables with shorter names
3582 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
3584 bool changeValue = false;
3585 cliVar_t value = { .uint16 = 0 };
3586 switch (valueTable[i].type & VALUE_MODE_MASK) {
3587 case MODE_DIRECT: {
3588 value.uint16 = atoi(eqptr);
3590 if (value.uint16 >= valueTable[i].config.minmax.min && value.uint16 <= valueTable[i].config.minmax.max) {
3591 changeValue = true;
3594 break;
3595 case MODE_LOOKUP: {
3596 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
3597 bool matched = false;
3598 for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
3599 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
3601 if (matched) {
3602 value.uint16 = tableValueIndex;
3603 changeValue = true;
3607 break;
3610 if (changeValue) {
3611 cliSetVar(val, value);
3613 cliPrintf("%s set to ", valueTable[i].name);
3614 cliPrintVar(val, 0);
3615 } else {
3616 cliPrint("Invalid value\r\n");
3617 cliPrintVarRange(val);
3620 return;
3623 cliPrint("Invalid name\r\n");
3624 } else {
3625 // no equals, check for matching variables.
3626 cliGet(cmdline);
3630 static void cliStatus(char *cmdline)
3632 UNUSED(cmdline);
3634 cliPrintf("System Uptime: %d seconds\r\n", millis() / 1000);
3635 cliPrintf("Voltage: %d * 0.1V (%dS battery - %s)\r\n", getBatteryVoltage(), getBatteryCellCount(), getBatteryStateString());
3637 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
3639 #if defined(USE_SENSOR_NAMES)
3640 const uint32_t detectedSensorsMask = sensorsMask();
3641 for (uint32_t i = 0; ; i++) {
3642 if (sensorTypeNames[i] == NULL) {
3643 break;
3645 const uint32_t mask = (1 << i);
3646 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
3647 const uint8_t sensorHardwareIndex = detectedSensors[i];
3648 const char *sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
3649 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
3650 if (mask == SENSOR_ACC && acc.dev.revisionCode) {
3651 cliPrintf(".%c", acc.dev.revisionCode);
3655 #endif /* USE_SENSOR_NAMES */
3656 cliPrint("\r\n");
3658 #ifdef USE_SDCARD
3659 cliSdInfo(NULL);
3660 #endif
3662 #ifdef USE_I2C
3663 const uint16_t i2cErrorCounter = i2cGetErrorCounter();
3664 #else
3665 const uint16_t i2cErrorCounter = 0;
3666 #endif
3668 #ifdef STACK_CHECK
3669 cliPrintf("Stack used: %d, ", stackUsedSize());
3670 #endif
3671 cliPrintf("Stack size: %d, Stack address: 0x%x\r\n", stackTotalSize(), stackHighMem());
3673 cliPrintf("I2C Errors: %d, config size: %d, max available config: %d\r\n", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start);
3675 const int gyroRate = getTaskDeltaTime(TASK_GYROPID) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_GYROPID)));
3676 const int rxRate = getTaskDeltaTime(TASK_RX) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_RX)));
3677 const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM)));
3678 cliPrintf("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d\r\n",
3679 constrain(averageSystemLoadPercent, 0, 100), getTaskDeltaTime(TASK_GYROPID), gyroRate, rxRate, systemRate);
3683 #ifndef SKIP_TASK_STATISTICS
3684 static void cliTasks(char *cmdline)
3686 UNUSED(cmdline);
3687 int maxLoadSum = 0;
3688 int averageLoadSum = 0;
3690 #ifndef MINIMAL_CLI
3691 if (systemConfig()->task_statistics) {
3692 cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
3693 } else {
3694 cliPrintf("Task list\r\n");
3696 #endif
3697 for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; taskId++) {
3698 cfTaskInfo_t taskInfo;
3699 getTaskInfo(taskId, &taskInfo);
3700 if (taskInfo.isEnabled) {
3701 int taskFrequency;
3702 int subTaskFrequency;
3703 if (taskId == TASK_GYROPID) {
3704 subTaskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
3705 taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom;
3706 if (pidConfig()->pid_process_denom > 1) {
3707 cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
3708 } else {
3709 taskFrequency = subTaskFrequency;
3710 cliPrintf("%02d - (%11s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
3712 } else {
3713 taskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
3714 cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
3716 const int maxLoad = taskInfo.maxExecutionTime == 0 ? 0 :(taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
3717 const int averageLoad = taskInfo.averageExecutionTime == 0 ? 0 : (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
3718 if (taskId != TASK_SERIAL) {
3719 maxLoadSum += maxLoad;
3720 averageLoadSum += averageLoad;
3722 if (systemConfig()->task_statistics) {
3723 cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n",
3724 taskFrequency, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime,
3725 maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
3726 } else {
3727 cliPrintf("%6d\r\n", taskFrequency);
3729 if (taskId == TASK_GYROPID && pidConfig()->pid_process_denom > 1) {
3730 cliPrintf(" - (%15s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency);
3734 if (systemConfig()->task_statistics) {
3735 cfCheckFuncInfo_t checkFuncInfo;
3736 getCheckFuncInfo(&checkFuncInfo);
3737 cliPrintf("RX Check Function %17d %7d %25d\r\n", checkFuncInfo.maxExecutionTime, checkFuncInfo.averageExecutionTime, checkFuncInfo.totalExecutionTime / 1000);
3738 cliPrintf("Total (excluding SERIAL) %23d.%1d%% %4d.%1d%%\r\n", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
3741 #endif
3743 static void cliVersion(char *cmdline)
3745 UNUSED(cmdline);
3747 cliPrintf("# %s / %s %s %s / %s (%s)\r\n",
3748 FC_FIRMWARE_NAME,
3749 targetName,
3750 FC_VERSION_STRING,
3751 buildDate,
3752 buildTime,
3753 shortGitRevision
3757 #if defined(USE_RESOURCE_MGMT)
3759 #define MAX_RESOURCE_INDEX(x) ((x) == 0 ? 1 : (x))
3761 typedef struct {
3762 const uint8_t owner;
3763 pgn_t pgn;
3764 uint16_t offset;
3765 const uint8_t maxIndex;
3766 } cliResourceValue_t;
3768 const cliResourceValue_t resourceTable[] = {
3769 #ifdef BEEPER
3770 { OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, ioTag), 0 },
3771 #endif
3772 { OWNER_MOTOR, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.ioTags[0]), MAX_SUPPORTED_MOTORS },
3773 #ifdef USE_SERVOS
3774 { OWNER_SERVO, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.ioTags[0]), MAX_SUPPORTED_SERVOS },
3775 #endif
3776 #if defined(USE_PWM) || defined(USE_PPM)
3777 { OWNER_PPMINPUT, PG_PPM_CONFIG, offsetof(ppmConfig_t, ioTag), 0 },
3778 { OWNER_PWMINPUT, PG_PWM_CONFIG, offsetof(pwmConfig_t, ioTags[0]), PWM_INPUT_PORT_COUNT },
3779 #endif
3780 #ifdef SONAR
3781 { OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 },
3782 { OWNER_SONAR_ECHO, PG_SONAR_CONFIG, offsetof(sonarConfig_t, echoTag), 0 },
3783 #endif
3784 #ifdef LED_STRIP
3785 { OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ioTag), 0 },
3786 #endif
3787 { OWNER_SERIAL_TX, PG_SERIAL_PIN_CONFIG, offsetof(serialPinConfig_t, ioTagTx[0]), SERIAL_PORT_MAX_INDEX },
3788 { OWNER_SERIAL_RX, PG_SERIAL_PIN_CONFIG, offsetof(serialPinConfig_t, ioTagRx[0]), SERIAL_PORT_MAX_INDEX },
3791 static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
3793 const pgRegistry_t* rec = pgFind(value.pgn);
3794 return CONST_CAST(ioTag_t *, rec->address + value.offset + index);
3797 static void printResource(uint8_t dumpMask)
3799 for (unsigned int i = 0; i < ARRAYLEN(resourceTable); i++) {
3800 const char* owner = ownerNames[resourceTable[i].owner];
3801 const void *currentConfig;
3802 const void *defaultConfig;
3803 if (dumpMask & DO_DIFF || dumpMask & SHOW_DEFAULTS) {
3804 const cliCurrentAndDefaultConfig_t *config = getCurrentAndDefaultConfigs(resourceTable[i].pgn);
3805 currentConfig = config->currentConfig;
3806 defaultConfig = config->defaultConfig;
3807 } else { // Not guaranteed to have initialised default configs in this case
3808 currentConfig = pgFind(resourceTable[i].pgn)->address;
3809 defaultConfig = currentConfig;
3812 for (int index = 0; index < MAX_RESOURCE_INDEX(resourceTable[i].maxIndex); index++) {
3813 const ioTag_t ioTag = *((const ioTag_t *)currentConfig + resourceTable[i].offset + index);
3814 const ioTag_t ioTagDefault = *((const ioTag_t *)defaultConfig + resourceTable[i].offset + index);
3816 bool equalsDefault = ioTag == ioTagDefault;
3817 const char *format = "resource %s %d %c%02d\r\n";
3818 const char *formatUnassigned = "resource %s %d NONE\r\n";
3819 if (!ioTagDefault) {
3820 cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
3821 } else {
3822 cliDefaultPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdxByTag(ioTagDefault) + 'A', IO_GPIOPinIdxByTag(ioTagDefault));
3824 if (!ioTag) {
3825 if (!(dumpMask & HIDE_UNUSED)) {
3826 cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
3828 } else {
3829 cliDumpPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag));
3835 static void printResourceOwner(uint8_t owner, uint8_t index)
3837 cliPrintf("%s", ownerNames[resourceTable[owner].owner]);
3839 if (resourceTable[owner].maxIndex > 0) {
3840 cliPrintf(" %d", RESOURCE_INDEX(index));
3844 static void resourceCheck(uint8_t resourceIndex, uint8_t index, ioTag_t newTag)
3846 if (!newTag) {
3847 return;
3850 const char * format = "\r\nNOTE: %c%02d already assigned to ";
3851 for (int r = 0; r < (int)ARRAYLEN(resourceTable); r++) {
3852 for (int i = 0; i < MAX_RESOURCE_INDEX(resourceTable[r].maxIndex); i++) {
3853 ioTag_t *tag = getIoTag(resourceTable[r], i);
3854 if (*tag == newTag) {
3855 bool cleared = false;
3856 if (r == resourceIndex) {
3857 if (i == index) {
3858 continue;
3860 *tag = IO_TAG_NONE;
3861 cleared = true;
3864 cliPrintf(format, DEFIO_TAG_GPIOID(newTag) + 'A', DEFIO_TAG_PIN(newTag));
3866 printResourceOwner(r, i);
3868 if (cleared) {
3869 cliPrintf(". ");
3870 printResourceOwner(r, i);
3871 cliPrintf(" disabled");
3874 cliPrint(".\r\n");
3880 static void cliResource(char *cmdline)
3882 int len = strlen(cmdline);
3884 if (len == 0) {
3885 printResource(DUMP_MASTER | HIDE_UNUSED);
3887 return;
3888 } else if (strncasecmp(cmdline, "list", len) == 0) {
3889 #ifdef MINIMAL_CLI
3890 cliPrintf("IO\r\n");
3891 #else
3892 cliPrintf("Currently active IO resource assignments:\r\n(reboot to update)\r\n");
3893 cliRepeat('-', 20);
3894 #endif
3895 for (int i = 0; i < DEFIO_IO_USED_COUNT; i++) {
3896 const char* owner;
3897 owner = ownerNames[ioRecs[i].owner];
3899 cliPrintf("%c%02d: %s ", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner);
3900 if (ioRecs[i].index > 0) {
3901 cliPrintf("%d", ioRecs[i].index);
3903 cliPrintf("\r\n");
3906 cliPrintf("\r\n\r\n");
3907 #ifdef MINIMAL_CLI
3908 cliPrintf("DMA:\r\n");
3909 #else
3910 cliPrintf("Currently active DMA:\r\n");
3911 cliRepeat('-', 20);
3912 #endif
3913 for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
3914 const char* owner;
3915 owner = ownerNames[dmaGetOwner(i)];
3917 cliPrintf(DMA_OUTPUT_STRING, i / DMA_MOD_VALUE + 1, (i % DMA_MOD_VALUE) + DMA_MOD_OFFSET);
3918 uint8_t resourceIndex = dmaGetResourceIndex(i);
3919 if (resourceIndex > 0) {
3920 cliPrintf(" %s %d\r\n", owner, resourceIndex);
3921 } else {
3922 cliPrintf(" %s\r\n", owner);
3926 #ifndef MINIMAL_CLI
3927 cliPrintf("\r\nUse: 'resource' to see how to change resources.\r\n");
3928 #endif
3930 return;
3933 uint8_t resourceIndex = 0;
3934 int index = 0;
3935 char *pch = NULL;
3936 char *saveptr;
3938 pch = strtok_r(cmdline, " ", &saveptr);
3939 for (resourceIndex = 0; ; resourceIndex++) {
3940 if (resourceIndex >= ARRAYLEN(resourceTable)) {
3941 cliPrint("Invalid\r\n");
3942 return;
3945 if (strncasecmp(pch, ownerNames[resourceTable[resourceIndex].owner], len) == 0) {
3946 break;
3950 pch = strtok_r(NULL, " ", &saveptr);
3951 index = atoi(pch);
3953 if (resourceTable[resourceIndex].maxIndex > 0 || index > 0) {
3954 if (index <= 0 || index > MAX_RESOURCE_INDEX(resourceTable[resourceIndex].maxIndex)) {
3955 cliShowArgumentRangeError("index", 1, MAX_RESOURCE_INDEX(resourceTable[resourceIndex].maxIndex));
3956 return;
3958 index -= 1;
3960 pch = strtok_r(NULL, " ", &saveptr);
3963 ioTag_t *tag = getIoTag(resourceTable[resourceIndex], index);
3965 uint8_t pin = 0;
3966 if (strlen(pch) > 0) {
3967 if (strcasecmp(pch, "NONE") == 0) {
3968 *tag = IO_TAG_NONE;
3969 #ifdef MINIMAL_CLI
3970 cliPrintf("Freed\r\n");
3971 #else
3972 cliPrintf("Resource is freed\r\n");
3973 #endif
3974 return;
3975 } else {
3976 uint8_t port = (*pch) - 'A';
3977 if (port >= 8) {
3978 port = (*pch) - 'a';
3981 if (port < 8) {
3982 pch++;
3983 pin = atoi(pch);
3984 if (pin < 16) {
3985 ioRec_t *rec = IO_Rec(IOGetByTag(DEFIO_TAG_MAKE(port, pin)));
3986 if (rec) {
3987 resourceCheck(resourceIndex, index, DEFIO_TAG_MAKE(port, pin));
3988 #ifdef MINIMAL_CLI
3989 cliPrintf(" %c%02d set\r\n", port + 'A', pin);
3990 #else
3991 cliPrintf("\r\nResource is set to %c%02d!\r\n", port + 'A', pin);
3992 #endif
3993 *tag = DEFIO_TAG_MAKE(port, pin);
3994 } else {
3995 cliShowParseError();
3997 return;
4003 cliShowParseError();
4005 #endif /* USE_RESOURCE_MGMT */
4007 static void backupConfigs(void)
4009 // make copies of configs to do differencing
4010 PG_FOREACH(reg) {
4011 // currentConfig is the copy
4012 const cliCurrentAndDefaultConfig_t *cliCurrentAndDefaultConfig = getCurrentAndDefaultConfigs(pgN(reg));
4013 if (cliCurrentAndDefaultConfig->currentConfig) {
4014 if (pgIsProfile(reg)) {
4015 //memcpy((uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->address, reg->size * MAX_PROFILE_COUNT);
4016 } else {
4017 memcpy((uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->address, reg->size);
4019 #ifdef SERIAL_CLI_DEBUG
4020 } else {
4021 cliPrintf("BACKUP %d SET UP INCORRECTLY\r\n", pgN(reg));
4022 #endif
4027 static void restoreConfigs(void)
4029 PG_FOREACH(reg) {
4030 // currentConfig is the copy
4031 const cliCurrentAndDefaultConfig_t *cliCurrentAndDefaultConfig = getCurrentAndDefaultConfigs(pgN(reg));
4032 if (cliCurrentAndDefaultConfig->currentConfig) {
4033 if (pgIsProfile(reg)) {
4034 //memcpy(reg->address, (uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->size * MAX_PROFILE_COUNT);
4035 } else {
4036 memcpy(reg->address, (uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->size);
4038 #ifdef SERIAL_CLI_DEBUG
4039 } else {
4040 cliPrintf("RESTORE %d SET UP INCORRECTLY\r\n", pgN(reg));
4041 #endif
4046 static void printConfig(char *cmdline, bool doDiff)
4048 uint8_t dumpMask = DUMP_MASTER;
4049 char *options;
4050 if ((options = checkCommand(cmdline, "master"))) {
4051 dumpMask = DUMP_MASTER; // only
4052 } else if ((options = checkCommand(cmdline, "profile"))) {
4053 dumpMask = DUMP_PROFILE; // only
4054 } else if ((options = checkCommand(cmdline, "rates"))) {
4055 dumpMask = DUMP_RATES; // only
4056 } else if ((options = checkCommand(cmdline, "all"))) {
4057 dumpMask = DUMP_ALL; // all profiles and rates
4058 } else {
4059 options = cmdline;
4062 if (doDiff) {
4063 dumpMask = dumpMask | DO_DIFF;
4066 backupConfigs();
4067 // reset all configs to defaults to do differencing
4068 resetConfigs();
4070 #if defined(TARGET_CONFIG)
4071 targetConfiguration();
4072 #endif
4073 if (checkCommand(options, "showdefaults")) {
4074 dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
4077 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
4078 cliPrintHashLine("version");
4079 cliVersion(NULL);
4081 if ((dumpMask & (DUMP_ALL | DO_DIFF)) == (DUMP_ALL | DO_DIFF)) {
4082 cliPrintHashLine("reset configuration to default settings");
4083 cliPrint("defaults\r\n");
4086 cliPrintHashLine("name");
4087 printName(dumpMask, &systemConfigCopy);
4089 #ifdef USE_RESOURCE_MGMT
4090 cliPrintHashLine("resources");
4091 printResource(dumpMask);
4092 #endif
4094 #ifndef USE_QUAD_MIXER_ONLY
4095 cliPrintHashLine("mixer");
4096 const bool equalsDefault = mixerConfigCopy.mixerMode == mixerConfig()->mixerMode;
4097 const char *formatMixer = "mixer %s\r\n";
4098 cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig()->mixerMode - 1]);
4099 cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfigCopy.mixerMode - 1]);
4101 cliDumpPrintf(dumpMask, customMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n\r\n");
4103 printMotorMix(dumpMask, customMotorMixerCopy, customMotorMixer(0));
4105 #ifdef USE_SERVOS
4106 cliPrintHashLine("servo");
4107 printServo(dumpMask, servoParamsCopy, servoParams(0));
4109 cliPrintHashLine("servo mix");
4110 // print custom servo mixer if exists
4111 cliDumpPrintf(dumpMask, customServoMixers(0)->rate == 0, "smix reset\r\n\r\n");
4112 printServoMix(dumpMask, customServoMixersCopy, customServoMixers(0));
4113 #endif
4114 #endif
4116 cliPrintHashLine("feature");
4117 printFeature(dumpMask, &featureConfigCopy, featureConfig());
4119 #ifdef BEEPER
4120 cliPrintHashLine("beeper");
4121 printBeeper(dumpMask, &beeperConfigCopy, beeperConfig());
4122 #endif
4124 cliPrintHashLine("map");
4125 printMap(dumpMask, &rxConfigCopy, rxConfig());
4127 cliPrintHashLine("serial");
4128 printSerial(dumpMask, &serialConfigCopy, serialConfig());
4130 #ifdef LED_STRIP
4131 cliPrintHashLine("led");
4132 printLed(dumpMask, ledStripConfigCopy.ledConfigs, ledStripConfig()->ledConfigs);
4134 cliPrintHashLine("color");
4135 printColor(dumpMask, ledStripConfigCopy.colors, ledStripConfig()->colors);
4137 cliPrintHashLine("mode_color");
4138 printModeColor(dumpMask, &ledStripConfigCopy, ledStripConfig());
4139 #endif
4141 cliPrintHashLine("aux");
4142 printAux(dumpMask, modeActivationConditionsCopy, modeActivationConditions(0));
4144 cliPrintHashLine("adjrange");
4145 printAdjustmentRange(dumpMask, adjustmentRangesCopy, adjustmentRanges(0));
4147 cliPrintHashLine("rxrange");
4148 printRxRange(dumpMask, rxChannelRangeConfigsCopy, rxChannelRangeConfigs(0));
4150 #ifdef VTX_CONTROL
4151 cliPrintHashLine("vtx");
4152 printVtx(dumpMask, &vtxConfigCopy, vtxConfig());
4153 #endif
4155 cliPrintHashLine("rxfail");
4156 printRxFailsafe(dumpMask, rxFailsafeChannelConfigsCopy, rxFailsafeChannelConfigs(0));
4158 cliPrintHashLine("master");
4159 dumpAllValues(MASTER_VALUE, dumpMask);
4161 if (dumpMask & DUMP_ALL) {
4162 const uint8_t pidProfileIndexSave = systemConfigCopy.pidProfileIndex;
4163 for (uint32_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
4164 cliDumpPidProfile(pidProfileIndex, dumpMask);
4166 changePidProfile(pidProfileIndexSave);
4167 cliPrintHashLine("restore original profile selection");
4168 cliProfile("");
4170 const uint8_t controlRateProfileIndexSave = systemConfigCopy.activeRateProfile;
4171 for (uint32_t rateIndex = 0; rateIndex < CONTROL_RATE_PROFILE_COUNT; rateIndex++) {
4172 cliDumpRateProfile(rateIndex, dumpMask);
4174 changeControlRateProfile(controlRateProfileIndexSave);
4175 cliPrintHashLine("restore original rateprofile selection");
4176 cliRateProfile("");
4178 cliPrintHashLine("save configuration");
4179 cliPrint("save");
4180 } else {
4181 cliDumpPidProfile(systemConfigCopy.pidProfileIndex, dumpMask);
4183 cliDumpRateProfile(systemConfigCopy.activeRateProfile, dumpMask);
4187 if (dumpMask & DUMP_PROFILE) {
4188 cliDumpPidProfile(systemConfigCopy.pidProfileIndex, dumpMask);
4191 if (dumpMask & DUMP_RATES) {
4192 cliDumpRateProfile(systemConfigCopy.activeRateProfile, dumpMask);
4194 // restore configs from copies
4195 restoreConfigs();
4198 static void cliDump(char *cmdline)
4200 printConfig(cmdline, false);
4203 static void cliDiff(char *cmdline)
4205 printConfig(cmdline, true);
4208 typedef struct {
4209 const char *name;
4210 #ifndef MINIMAL_CLI
4211 const char *description;
4212 const char *args;
4213 #endif
4214 void (*func)(char *cmdline);
4215 } clicmd_t;
4217 #ifndef MINIMAL_CLI
4218 #define CLI_COMMAND_DEF(name, description, args, method) \
4220 name , \
4221 description , \
4222 args , \
4223 method \
4225 #else
4226 #define CLI_COMMAND_DEF(name, description, args, method) \
4228 name, \
4229 method \
4231 #endif
4233 static void cliHelp(char *cmdline);
4235 // should be sorted a..z for bsearch()
4236 const clicmd_t cmdTable[] = {
4237 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
4238 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
4239 #ifdef BEEPER
4240 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
4241 "\t<+|->[name]", cliBeeper),
4242 #endif
4243 #ifdef LED_STRIP
4244 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
4245 #endif
4246 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
4247 CLI_COMMAND_DEF("bl", "reboot into bootloader", NULL, cliBootloader),
4248 CLI_COMMAND_DEF("diff", "list configuration changes from default",
4249 "[master|profile|rates|all] {showdefaults}", cliDiff),
4250 #ifdef USE_DSHOT
4251 CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
4252 #endif
4253 CLI_COMMAND_DEF("dump", "dump configuration",
4254 "[master|profile|rates|all] {showdefaults}", cliDump),
4255 #ifdef USE_ESCSERIAL
4256 CLI_COMMAND_DEF("escprog", "passthrough esc to serial", "<mode [sk/bl/ki/cc]> <index>", cliEscPassthrough),
4257 #endif
4258 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
4259 CLI_COMMAND_DEF("feature", "configure features",
4260 "list\r\n"
4261 "\t<+|->[name]", cliFeature),
4262 #ifdef USE_FLASHFS
4263 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
4264 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
4265 #ifdef USE_FLASH_TOOLS
4266 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
4267 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
4268 #endif
4269 #endif
4270 CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet),
4271 #ifdef GPS
4272 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
4273 #endif
4274 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
4275 #ifdef LED_STRIP
4276 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
4277 #endif
4278 CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap),
4279 #ifndef USE_QUAD_MIXER_ONLY
4280 CLI_COMMAND_DEF("mixer", "configure mixer", "list\r\n\t<name>", cliMixer),
4281 #endif
4282 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
4283 #ifdef LED_STRIP
4284 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
4285 #endif
4286 CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor),
4287 CLI_COMMAND_DEF("name", "name of craft", NULL, cliName),
4288 #ifndef MINIMAL_CLI
4289 CLI_COMMAND_DEF("play_sound", NULL, "[<index>]", cliPlaySound),
4290 #endif
4291 CLI_COMMAND_DEF("profile", "change profile", "[<index>]", cliProfile),
4292 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
4293 #if defined(USE_RESOURCE_MGMT)
4294 CLI_COMMAND_DEF("resource", "show/set resources", NULL, cliResource),
4295 #endif
4296 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFailsafe),
4297 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
4298 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
4299 #ifdef USE_SDCARD
4300 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
4301 #endif
4302 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
4303 #ifndef SKIP_SERIAL_PASSTHROUGH
4304 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
4305 #endif
4306 #ifdef USE_SERVOS
4307 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
4308 #endif
4309 CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet),
4310 #ifdef USE_SERVOS
4311 CLI_COMMAND_DEF("smix", "servo mixer", "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
4312 "\treset\r\n"
4313 "\tload <mixer>\r\n"
4314 "\treverse <servo> <source> r|n", cliServoMix),
4315 #endif
4316 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
4317 #ifndef SKIP_TASK_STATISTICS
4318 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
4319 #endif
4320 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
4321 #ifdef VTX_CONTROL
4322 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
4323 #endif
4325 static void cliHelp(char *cmdline)
4327 UNUSED(cmdline);
4329 for (uint32_t i = 0; i < ARRAYLEN(cmdTable); i++) {
4330 cliPrint(cmdTable[i].name);
4331 #ifndef MINIMAL_CLI
4332 if (cmdTable[i].description) {
4333 cliPrintf(" - %s", cmdTable[i].description);
4335 if (cmdTable[i].args) {
4336 cliPrintf("\r\n\t%s", cmdTable[i].args);
4338 #endif
4339 cliPrint("\r\n");
4343 void cliProcess(void)
4345 if (!cliWriter) {
4346 return;
4349 // Be a little bit tricky. Flush the last inputs buffer, if any.
4350 bufWriterFlush(cliWriter);
4352 while (serialRxBytesWaiting(cliPort)) {
4353 uint8_t c = serialRead(cliPort);
4354 if (c == '\t' || c == '?') {
4355 // do tab completion
4356 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
4357 uint32_t i = bufferIndex;
4358 for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
4359 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
4360 continue;
4361 if (!pstart)
4362 pstart = cmd;
4363 pend = cmd;
4365 if (pstart) { /* Buffer matches one or more commands */
4366 for (; ; bufferIndex++) {
4367 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
4368 break;
4369 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
4370 /* Unambiguous -- append a space */
4371 cliBuffer[bufferIndex++] = ' ';
4372 cliBuffer[bufferIndex] = '\0';
4373 break;
4375 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
4378 if (!bufferIndex || pstart != pend) {
4379 /* Print list of ambiguous matches */
4380 cliPrint("\r\033[K");
4381 for (cmd = pstart; cmd <= pend; cmd++) {
4382 cliPrint(cmd->name);
4383 cliWrite('\t');
4385 cliPrompt();
4386 i = 0; /* Redraw prompt */
4388 for (; i < bufferIndex; i++)
4389 cliWrite(cliBuffer[i]);
4390 } else if (!bufferIndex && c == 4) { // CTRL-D
4391 cliExit(cliBuffer);
4392 return;
4393 } else if (c == 12) { // NewPage / CTRL-L
4394 // clear screen
4395 cliPrint("\033[2J\033[1;1H");
4396 cliPrompt();
4397 } else if (bufferIndex && (c == '\n' || c == '\r')) {
4398 // enter pressed
4399 cliPrint("\r\n");
4401 // Strip comment starting with # from line
4402 char *p = cliBuffer;
4403 p = strchr(p, '#');
4404 if (NULL != p) {
4405 bufferIndex = (uint32_t)(p - cliBuffer);
4408 // Strip trailing whitespace
4409 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
4410 bufferIndex--;
4413 // Process non-empty lines
4414 if (bufferIndex > 0) {
4415 cliBuffer[bufferIndex] = 0; // null terminate
4417 const clicmd_t *cmd;
4418 char *options;
4419 for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
4420 if ((options = checkCommand(cliBuffer, cmd->name))) {
4421 break;
4424 if(cmd < cmdTable + ARRAYLEN(cmdTable))
4425 cmd->func(options);
4426 else
4427 cliPrint("Unknown command, try 'help'");
4428 bufferIndex = 0;
4431 memset(cliBuffer, 0, sizeof(cliBuffer));
4433 // 'exit' will reset this flag, so we don't need to print prompt again
4434 if (!cliMode)
4435 return;
4437 cliPrompt();
4438 } else if (c == 127) {
4439 // backspace
4440 if (bufferIndex) {
4441 cliBuffer[--bufferIndex] = 0;
4442 cliPrint("\010 \010");
4444 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
4445 if (!bufferIndex && c == ' ')
4446 continue; // Ignore leading spaces
4447 cliBuffer[bufferIndex++] = c;
4448 cliWrite(c);
4453 void cliEnter(serialPort_t *serialPort)
4455 cliMode = 1;
4456 cliPort = serialPort;
4457 setPrintfSerialPort(cliPort);
4458 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufShim, serialPort);
4460 schedulerSetCalulateTaskStatistics(systemConfig()->task_statistics);
4462 #ifndef MINIMAL_CLI
4463 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
4464 #else
4465 cliPrint("\r\nCLI\r\n");
4466 #endif
4467 cliPrompt();
4469 ENABLE_ARMING_FLAG(PREVENT_ARMING);
4472 void cliInit(const serialConfig_t *serialConfig)
4474 UNUSED(serialConfig);
4475 BUILD_BUG_ON(LOOKUP_TABLE_COUNT != ARRAYLEN(lookupTables));
4477 #endif // USE_CLI