CF/BF - add cli diff support for voltage and current sensors.
[betaflight.git] / src / main / fc / cli.c
blob5f6d4337605c2492fabcf1c70dd35e180eb07070
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/config_profile.h"
53 #include "config/feature.h"
54 #include "config/parameter_group.h"
55 #include "config/parameter_group_ids.h"
57 #include "drivers/accgyro.h"
58 #include "drivers/buf_writer.h"
59 #include "drivers/bus_i2c.h"
60 #include "drivers/compass.h"
61 #include "drivers/display.h"
62 #include "drivers/dma.h"
63 #include "drivers/flash.h"
64 #include "drivers/io.h"
65 #include "drivers/io_impl.h"
66 #include "drivers/rx_pwm.h"
67 #include "drivers/sdcard.h"
68 #include "drivers/sensor.h"
69 #include "drivers/serial.h"
70 #include "drivers/serial_escserial.h"
71 #include "drivers/sonar_hcsr04.h"
72 #include "drivers/stack_check.h"
73 #include "drivers/system.h"
74 #include "drivers/timer.h"
75 #include "drivers/vcd.h"
77 #include "fc/cli.h"
78 #include "fc/config.h"
79 #include "fc/controlrate_profile.h"
80 #include "fc/fc_core.h"
81 #include "fc/rc_adjustments.h"
82 #include "fc/rc_controls.h"
83 #include "fc/runtime_config.h"
85 #include "flight/altitudehold.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.h"
105 #include "rx/rx.h"
106 #include "rx/spektrum.h"
108 #include "scheduler/scheduler.h"
110 #include "sensors/acceleration.h"
111 #include "sensors/barometer.h"
112 #include "sensors/battery.h"
113 #include "sensors/boardalignment.h"
114 #include "sensors/compass.h"
115 #include "sensors/gyro.h"
116 #include "sensors/sensors.h"
118 #include "telemetry/frsky.h"
119 #include "telemetry/telemetry.h"
122 static serialPort_t *cliPort;
123 static bufWriter_t *cliWriter;
124 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 128];
126 static char cliBuffer[64];
127 static uint32_t bufferIndex = 0;
129 static const char* const emptyName = "-";
131 #ifndef USE_QUAD_MIXER_ONLY
132 // sync this with mixerMode_e
133 static const char * const mixerNames[] = {
134 "TRI", "QUADP", "QUADX", "BI",
135 "GIMBAL", "Y6", "HEX6",
136 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
137 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
138 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
139 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
141 #endif
143 // sync this with features_e
144 static const char * const featureNames[] = {
145 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
146 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
147 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
148 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
149 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
150 "SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_SENSOR", NULL
153 // sync this with rxFailsafeChannelMode_e
154 static const char rxFailsafeModeCharacters[] = "ahs";
156 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
157 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
158 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
161 // sync this with accelerationSensor_e
162 static const char * const lookupTableAccHardware[] = {
163 "AUTO",
164 "NONE",
165 "ADXL345",
166 "MPU6050",
167 "MMA8452",
168 "BMA280",
169 "LSM303DLHC",
170 "MPU6000",
171 "MPU6500",
172 "MPU9250",
173 "ICM20689",
174 "ICM20602",
175 "BMI160",
176 "FAKE"
179 #ifdef BARO
180 // sync this with baroSensor_e
181 static const char * const lookupTableBaroHardware[] = {
182 "AUTO",
183 "NONE",
184 "BMP085",
185 "MS5611",
186 "BMP280"
188 #endif
190 #ifdef MAG
191 // sync this with magSensor_e
192 static const char * const lookupTableMagHardware[] = {
193 "AUTO",
194 "NONE",
195 "HMC5883",
196 "AK8975",
197 "AK8963"
199 #endif
201 #if defined(USE_SENSOR_NAMES)
202 // sync this with sensors_e
203 static const char * const sensorTypeNames[] = {
204 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
207 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
209 static const char * const sensorHardwareNames[4][16] = {
210 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "ICM20689", "ICM20608G", "ICM20602", "BMI160", "FAKE", NULL },
211 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "ICM20689", "MPU9250", "ICM20608G", "ICM20602", "BMI160", "FAKE", NULL },
212 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
213 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
215 #endif /* USE_SENSOR_NAMES */
217 static const char * const lookupTableOffOn[] = {
218 "OFF", "ON"
221 static const char * const lookupTableUnit[] = {
222 "IMPERIAL", "METRIC"
225 static const char * const lookupTableAlignment[] = {
226 "DEFAULT",
227 "CW0",
228 "CW90",
229 "CW180",
230 "CW270",
231 "CW0FLIP",
232 "CW90FLIP",
233 "CW180FLIP",
234 "CW270FLIP"
237 #ifdef GPS
238 static const char * const lookupTableGPSProvider[] = {
239 "NMEA", "UBLOX"
242 static const char * const lookupTableGPSSBASMode[] = {
243 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
245 #endif
247 static const char * const lookupTableCurrentSensor[] = {
248 "NONE", "ADC", "VIRTUAL", "ESC"
251 static const char * const lookupTableBatterySensor[] = {
252 "NONE", "ADC", "ESC"
255 #ifdef USE_SERVOS
256 static const char * const lookupTableGimbalMode[] = {
257 "NORMAL", "MIXTILT"
259 #endif
261 #ifdef BLACKBOX
262 static const char * const lookupTableBlackboxDevice[] = {
263 "SERIAL", "SPIFLASH", "SDCARD"
265 #endif
267 #ifdef SERIAL_RX
268 static const char * const lookupTableSerialRX[] = {
269 "SPEK1024",
270 "SPEK2048",
271 "SBUS",
272 "SUMD",
273 "SUMH",
274 "XB-B",
275 "XB-B-RJ01",
276 "IBUS",
277 "JETIEXBUS",
278 "CRSF",
279 "SRXL"
281 #endif
283 #ifdef USE_RX_SPI
284 // sync with rx_spi_protocol_e
285 static const char * const lookupTableRxSpi[] = {
286 "V202_250K",
287 "V202_1M",
288 "SYMA_X",
289 "SYMA_X5C",
290 "CX10",
291 "CX10A",
292 "H8_3D",
293 "INAV"
295 #endif
297 static const char * const lookupTableGyroLpf[] = {
298 "OFF",
299 "188HZ",
300 "98HZ",
301 "42HZ",
302 "20HZ",
303 "10HZ",
304 "5HZ",
305 "EXPERIMENTAL"
308 static const char * const lookupTableDebug[DEBUG_COUNT] = {
309 "NONE",
310 "CYCLETIME",
311 "BATTERY",
312 "GYRO",
313 "ACCELEROMETER",
314 "MIXER",
315 "AIRMODE",
316 "PIDLOOP",
317 "NOTCH",
318 "RC_INTERPOLATION",
319 "VELOCITY",
320 "DFILTER",
321 "ANGLERATE",
322 "ESC_SENSOR",
323 "SCHEDULER",
324 "STACK"
327 #ifdef OSD
328 static const char * const lookupTableOsdType[] = {
329 "AUTO",
330 "PAL",
331 "NTSC"
333 #endif
335 static const char * const lookupTableSuperExpoYaw[] = {
336 "OFF", "ON", "ALWAYS"
339 static const char * const lookupTablePwmProtocol[] = {
340 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
341 #ifdef USE_DSHOT
342 "DSHOT150", "DSHOT300", "DSHOT600", "DSHOT1200"
343 #endif
346 static const char * const lookupTableRcInterpolation[] = {
347 "OFF", "PRESET", "AUTO", "MANUAL"
350 static const char * const lookupTableRcInterpolationChannels[] = {
351 "RP", "RPY", "RPYT"
354 static const char * const lookupTableLowpassType[] = {
355 "PT1", "BIQUAD", "FIR"
358 static const char * const lookupTableFailsafe[] = {
359 "AUTO-LAND", "DROP"
362 typedef struct lookupTableEntry_s {
363 const char * const *values;
364 const uint8_t valueCount;
365 } lookupTableEntry_t;
367 typedef enum {
368 TABLE_OFF_ON = 0,
369 TABLE_UNIT,
370 TABLE_ALIGNMENT,
371 #ifdef GPS
372 TABLE_GPS_PROVIDER,
373 TABLE_GPS_SBAS_MODE,
374 #endif
375 #ifdef BLACKBOX
376 TABLE_BLACKBOX_DEVICE,
377 #endif
378 TABLE_CURRENT_METER,
379 TABLE_VOLTAGE_METER,
380 #ifdef USE_SERVOS
381 TABLE_GIMBAL_MODE,
382 #endif
383 #ifdef SERIAL_RX
384 TABLE_SERIAL_RX,
385 #endif
386 #ifdef USE_RX_SPI
387 TABLE_RX_SPI,
388 #endif
389 TABLE_GYRO_LPF,
390 TABLE_ACC_HARDWARE,
391 #ifdef BARO
392 TABLE_BARO_HARDWARE,
393 #endif
394 #ifdef MAG
395 TABLE_MAG_HARDWARE,
396 #endif
397 TABLE_DEBUG,
398 TABLE_SUPEREXPO_YAW,
399 TABLE_MOTOR_PWM_PROTOCOL,
400 TABLE_RC_INTERPOLATION,
401 TABLE_RC_INTERPOLATION_CHANNELS,
402 TABLE_LOWPASS_TYPE,
403 TABLE_FAILSAFE,
404 #ifdef OSD
405 TABLE_OSD,
406 #endif
407 LOOKUP_TABLE_COUNT
408 } lookupTableIndex_e;
410 static const lookupTableEntry_t lookupTables[] = {
411 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
412 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
413 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
414 #ifdef GPS
415 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
416 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
417 #endif
418 #ifdef BLACKBOX
419 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
420 #endif
421 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
422 { lookupTableBatterySensor, sizeof(lookupTableBatterySensor) / sizeof(char *) },
423 #ifdef USE_SERVOS
424 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
425 #endif
426 #ifdef SERIAL_RX
427 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
428 #endif
429 #ifdef USE_RX_SPI
430 { lookupTableRxSpi, sizeof(lookupTableRxSpi) / sizeof(char *) },
431 #endif
432 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
433 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
434 #ifdef BARO
435 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
436 #endif
437 #ifdef MAG
438 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
439 #endif
440 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
441 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
442 { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
443 { lookupTableRcInterpolation, sizeof(lookupTableRcInterpolation) / sizeof(char *) },
444 { lookupTableRcInterpolationChannels, sizeof(lookupTableRcInterpolationChannels) / sizeof(char *) },
445 { lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
446 { lookupTableFailsafe, sizeof(lookupTableFailsafe) / sizeof(char *) },
447 #ifdef OSD
448 { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
449 #endif
452 #define VALUE_TYPE_OFFSET 0
453 #define VALUE_SECTION_OFFSET 4
454 #define VALUE_MODE_OFFSET 6
456 typedef enum {
457 // value type, bits 0-3
458 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
459 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
460 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
461 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
462 //VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
463 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET), // 0x05
465 // value section, bits 4-5
466 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
467 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
468 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET), // 0x20
469 // value mode
470 MODE_DIRECT = (0 << VALUE_MODE_OFFSET), // 0x40
471 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET) // 0x80
472 } cliValueFlag_e;
474 #define VALUE_TYPE_MASK (0x0F)
475 #define VALUE_SECTION_MASK (0x30)
476 #define VALUE_MODE_MASK (0xC0)
478 typedef struct cliMinMaxConfig_s {
479 const int16_t min;
480 const int16_t max;
481 } cliMinMaxConfig_t;
483 typedef struct cliLookupTableConfig_s {
484 const lookupTableIndex_e tableIndex;
485 } cliLookupTableConfig_t;
487 typedef union {
488 cliLookupTableConfig_t lookup;
489 cliMinMaxConfig_t minmax;
490 } cliValueConfig_t;
492 #ifdef USE_PARAMETER_GROUPS
493 typedef struct {
494 const char *name;
495 const uint8_t type; // see cliValueFlag_e
496 const cliValueConfig_t config;
498 pgn_t pgn;
499 uint16_t offset;
500 } __attribute__((packed)) clivalue_t;
502 static const clivalue_t valueTable[] = {
503 // PG_GYRO_CONFIG
504 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_align) },
505 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GYRO_LPF }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_lpf) },
506 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_sync_denom) },
507 { "gyro_lowpass_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_type) },
508 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 255 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_lpf_hz) },
509 { "gyro_notch1_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_1) },
510 { "gyro_notch1_cutoff", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_cutoff_1) },
511 { "gyro_notch2_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_hz_2) },
512 { "gyro_notch2_cutoff", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 16000 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_soft_notch_cutoff_2) },
513 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyroMovementCalibrationThreshold) },
514 #if defined(GYRO_USES_SPI)
515 #if defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689)
516 { "gyro_use_32khz", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_use_32khz) },
517 #endif
518 #if defined(USE_MPU_DATA_READY_SIGNAL)
519 { "gyro_isr_update", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GYRO_CONFIG, offsetof(gyroConfig_t, gyro_isr_update) },
520 #endif
521 #endif
523 // PG_ACCELEROMETER_CONFIG
524 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_align) },
525 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ACC_HARDWARE }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_hardware) },
526 { "acc_lpf_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 400 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, acc_lpf_hz) },
527 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.pitch) },
528 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -300, 300 }, PG_ACCELEROMETER_CONFIG, offsetof(accelerometerConfig_t, accelerometerTrims.values.roll) },
530 // PG_COMPASS_CONFIG
531 #ifdef MAG
532 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_ALIGNMENT }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_align) },
533 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MAG_HARDWARE }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_hardware) },
534 { "mag_declination", VAR_INT16 | MASTER_VALUE, .config.minmax = { -18000, 18000 }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, mag_declination) },
535 { "magzero_x", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[X]) },
536 { "magzero_y", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[Y]) },
537 { "magzero_z", VAR_INT16 | MASTER_VALUE, .config.minmax = { INT16_MIN, INT16_MAX }, PG_COMPASS_CONFIG, offsetof(compassConfig_t, magZero.raw[Z]) },
538 #endif
540 // PG_BAROMETER_CONFIG
541 #ifdef BARO
542 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BARO_HARDWARE }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_hardware) },
543 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_sample_count) },
544 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, .config.minmax = { 0 , 1 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_noise_lpf) },
545 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, .config.minmax = { 0 , 1 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_cf_vel) },
546 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, .config.minmax = { 0 , 1 }, PG_BAROMETER_CONFIG, offsetof(barometerConfig_t, baro_cf_alt) },
547 #endif
549 // PG_RX_CONFIG
550 { "mid_rc", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1200, 1700 }, PG_RX_CONFIG, offsetof(rxConfig_t, midrc) },
551 { "min_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, mincheck) },
552 { "max_check", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, maxcheck) },
553 { "rssi_channel", VAR_INT8 | MASTER_VALUE, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_channel) },
554 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_scale) },
555 { "rssi_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, rssi_invert) },
556 { "rc_interp", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RC_INTERPOLATION }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolation) },
557 { "rc_interp_ch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_RC_INTERPOLATION_CHANNELS }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolationChannels) },
558 { "rc_interp_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, rcInterpolationInterval) },
559 { "fpv_mix_degrees", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 50 }, PG_RX_CONFIG, offsetof(rxConfig_t, fpvCamAngleDegrees) },
560 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, MAX_AUX_CHANNEL_COUNT }, PG_RX_CONFIG, offsetof(rxConfig_t, max_aux_channel) },
561 #ifdef SERIAL_RX
562 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_SERIAL_RX }, PG_RX_CONFIG, offsetof(rxConfig_t, serialrx_provider) },
563 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, sbus_inversion) },
564 #endif
565 #ifdef SPEKTRUM_BIND
566 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind) },
567 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_RX_CONFIG, offsetof(rxConfig_t, spektrum_sat_bind_autoreset) },
568 #endif
569 { "airmode_start_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1000, 2000 }, PG_RX_CONFIG, offsetof(rxConfig_t, airModeActivateThreshold) },
570 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_min_usec) },
571 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, PG_RX_CONFIG, offsetof(rxConfig_t, rx_max_usec) },
572 #ifdef STM32F4
573 { "serialrx_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_RX_CONFIG, offsetof(rxConfig_t, halfDuplex) },
574 #endif
576 // PG_PWM_CONFIG
577 #if defined(USE_PWM)
578 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PWM_CONFIG, offsetof(pwmConfig_t, inputFilteringMode) },
579 #endif
581 // PG_BLACKBOX_CONFIG
582 #ifdef BLACKBOX
583 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, rate_num) },
584 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 32 }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, rate_denom) },
585 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_BLACKBOX_DEVICE }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, device) },
586 { "blackbox_on_motor_test", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BLACKBOX_CONFIG, offsetof(blackboxConfig_t, on_motor_test) },
587 #endif
589 // PG_MOTOR_CONFIG
590 { "min_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, minthrottle) },
591 { "max_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, maxthrottle) },
592 { "min_command", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, mincommand) },
593 #ifdef USE_DSHOT
594 { "digital_idle_percent", VAR_FLOAT | MASTER_VALUE, .config.minmax = { 0, 20 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, digitalIdleOffsetPercent) },
595 #endif
596 { "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.useUnsyncedPwm) },
597 { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmProtocol) },
598 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 200, 32000 }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmRate) },
599 { "motor_pwm_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.motorPwmInversion) },
601 // PG_THROTTLE_CORRECTION_CONFIG
602 { "thr_corr_value", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 150 }, PG_THROTTLE_CORRECTION_CONFIG, offsetof(throttleCorrectionConfig_t, throttle_correction_value) },
603 { "thr_corr_angle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 1, 900 }, PG_THROTTLE_CORRECTION_CONFIG, offsetof(throttleCorrectionConfig_t, throttle_correction_angle) },
605 // PG_FAILSAFE_CONFIG
606 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_delay) },
607 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_off_delay) },
608 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle) },
609 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_kill_switch) },
610 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 300 }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_throttle_low_delay) },
611 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FAILSAFE }, PG_FAILSAFE_CONFIG, offsetof(failsafeConfig_t, failsafe_procedure) },
613 // PG_BOARDALIGNMENT_CONFIG
614 { "align_board_roll", VAR_INT16 | MASTER_VALUE, .config.minmax = { -180, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, rollDegrees) },
615 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, .config.minmax = { -180, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, pitchDegrees) },
616 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, .config.minmax = { -180, 360 }, PG_BOARD_ALIGNMENT, offsetof(boardAlignment_t, yawDegrees) },
618 // PG_GIMBAL_CONFIG
619 #ifdef USE_SERVOS
620 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GIMBAL_MODE }, PG_GIMBAL_CONFIG, offsetof(gimbalConfig_t, mode) },
621 #endif
623 // PG_BATTERY_CONFIG
624 { "bat_capacity", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryCapacity) },
625 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmaxcellvoltage) },
626 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatmincellvoltage) },
627 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 10, 50 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbatwarningcellvoltage) },
628 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 250 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, vbathysteresis) },
629 { "current_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_CURRENT_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, currentMeterSource) },
630 { "battery_meter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_VOLTAGE_METER }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, voltageMeterSource) },
631 { "bat_detect_thresh", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 200 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, batteryNotPresentLevel) },
632 { "use_vbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useVBatAlerts) },
633 { "use_cbat_alerts", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, useConsumptionAlerts) },
634 { "cbat_alert_percent", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_BATTERY_CONFIG, offsetof(batteryConfig_t, consumptionWarningPercentage) },
636 // PG_VOLTAGE_SENSOR_ADC_CONFIG
637 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, PG_VOLTAGE_SENSOR_ADC_CONFIG, offsetof(voltageSensorADCConfig_t, vbatscale) },
639 // PG_CURRENT_SENSOR_ADC_CONFIG
640 { "ibata_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, scale) },
641 { "ibata_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_ADC_CONFIG, offsetof(currentSensorADCConfig_t, offset) },
642 // PG_CURRENT_SENSOR_ADC_CONFIG
643 { "ibatv_scale", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, scale) },
644 { "ibatv_offset", VAR_INT16 | MASTER_VALUE, .config.minmax = { -16000, 16000 }, PG_CURRENT_SENSOR_VIRTUAL_CONFIG, offsetof(currentSensorVirtualConfig_t, offset) },
646 // PG_BEEPER_DEV_CONFIG
647 #ifdef BEEPER
648 { "beeper_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isInverted) },
649 { "beeper_od", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, isOpenDrain) },
650 #endif
652 // PG_MIXER_CONFIG
653 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, .config.minmax = { -1, 1 }, PG_MIXER_CONFIG, offsetof(mixerConfig_t, yaw_motor_direction) },
655 // PG_MOTOR_3D_CONFIG
656 { "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
657 { "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,
658 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, neutral3d) },
659 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_MOTOR_3D_CONFIG, offsetof(flight3DConfig_t, deadband3d_throttle) },
661 // PG_SERVO_CONFIG
662 #ifdef USE_SERVOS
663 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.servoCenterPulse) },
664 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 50, 498 }, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.servoPwmRate) },
665 { "servo_lowpass_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 400}, PG_SERVO_CONFIG, offsetof(servoConfig_t, servo_lowpass_freq) },
666 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SERVO_CONFIG, offsetof(servoConfig_t, tri_unarmed_servo) },
667 { "channel_forwarding_start", VAR_UINT8 | MASTER_VALUE, .config.minmax = { AUX1, MAX_SUPPORTED_RC_CHANNEL_COUNT }, PG_SERVO_CONFIG, offsetof(servoConfig_t, channelForwardingStartChannel) },
668 #endif
670 // PG_CONTROLRATE_PROFILES
671 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcRate8) },
672 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 255 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawRate8) },
673 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcExpo8) },
674 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, rcYawExpo8) },
675 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrMid8) },
676 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, 100 }, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, thrExpo8) },
677 { "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]) },
678 { "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]) },
679 { "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]) },
680 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, dynThrPID) },
681 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX}, PG_CONTROL_RATE_PROFILES, offsetof(controlRateConfig_t, tpa_breakpoint) },
683 // PG_SERIAL_CONFIG
684 { "reboot_character", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 48, 126 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, reboot_character) },
685 { "serial_update_rate_hz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 100, 2000 }, PG_SERIAL_CONFIG, offsetof(serialConfig_t, serial_update_rate_hz) },
687 // PG_IMU_CONFIG
688 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.xy) },
689 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_IMU_CONFIG, offsetof(imuConfig_t, accDeadband.z) },
690 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_IMU_CONFIG, offsetof(imuConfig_t, acc_unarmedcal) },
691 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_kp) },
692 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 32000 }, PG_IMU_CONFIG, offsetof(imuConfig_t, dcm_ki) },
693 { "small_angle", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 180 }, PG_IMU_CONFIG, offsetof(imuConfig_t, small_angle) },
695 // PG_ARMING_CONFIG
696 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_ARMING_CONFIG, offsetof(armingConfig_t, auto_disarm_delay) },
697 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_ARMING_CONFIG, offsetof(armingConfig_t, disarm_kill_switch) },
698 { "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) },
701 // PG_GPS_CONFIG
702 #ifdef GPS
703 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_PROVIDER }, PG_GPS_CONFIG, offsetof(gpsConfig_t, provider) },
704 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_SBAS_MODE }, PG_GPS_CONFIG, offsetof(gpsConfig_t, sbasMode) },
705 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoConfig) },
706 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_CONFIG, offsetof(gpsConfig_t, autoBaud) },
707 #endif
709 // PG_NAVIGATION_CONFIG
710 #ifdef GPS
711 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, gps_wp_radius) },
712 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_controls_heading) },
713 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_min) },
714 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 10, 2000 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_speed_max) },
715 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_NAVIGATION_CONFIG, offsetof(navigationConfig_t, nav_slew_rate) },
716 #endif
718 // PG_AIRPLANE_CONFIG
719 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, .config.minmax = { -1, 1 }, PG_AIRPLANE_CONFIG, offsetof(airplaneConfig_t, fixedwing_althold_dir) },
721 // PG_RC_CONTROLS_CONFIG
722 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 250 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, alt_hold_deadband) },
723 { "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) },
724 { "deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 32 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, deadband) },
725 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_deadband) },
726 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, .config.minmax = { -1, 1 }, PG_RC_CONTROLS_CONFIG, offsetof(rcControlsConfig_t, yaw_control_direction) },
728 // PG_PID_CONFIG
729 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, MAX_PID_PROCESS_DENOM }, PG_PID_CONFIG, offsetof(pidConfig_t, pid_process_denom) },
731 // PG_PID_PROFILE
732 { "d_lowpass_type", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_LOWPASS_TYPE }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_filter_type) },
733 { "d_lowpass", VAR_INT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_lpf_hz) },
734 { "d_notch_hz", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_hz) },
735 { "d_notch_cut", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 1, 16000 }, PG_PID_PROFILE, offsetof(pidProfile_t, dterm_notch_cutoff) },
736 { "vbat_pid_gain", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, vbatPidCompensation) },
737 { "pid_at_min_throttle", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_PID_PROFILE, offsetof(pidProfile_t, pidAtMinThrottle) },
738 { "anti_gravity_thresh", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 20, 1000 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermThrottleThreshold) },
739 { "anti_gravity_gain", VAR_FLOAT | PROFILE_VALUE, .config.minmax = { 1, 30 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermAcceleratorGain) },
740 { "setpoint_relax_ratio", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, setpointRelaxRatio) },
741 { "d_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 254 }, PG_PID_PROFILE, offsetof(pidProfile_t, dtermSetpointWeight) },
742 { "yaw_accel_limit", VAR_FLOAT | PROFILE_VALUE, .config.minmax = { 0.1f, 50.0f }, PG_PID_PROFILE, offsetof(pidProfile_t, yawRateAccelLimit) },
743 { "accel_limit", VAR_FLOAT | PROFILE_VALUE, .config.minmax = { 0.1f, 50.0f }, PG_PID_PROFILE, offsetof(pidProfile_t, rateAccelLimit) },
745 { "iterm_windup", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 30, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, itermWindupPointPercent) },
746 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, .config.minmax = { 0, 500 }, PG_PID_PROFILE, offsetof(pidProfile_t, yaw_lpf_hz) },
747 { "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, .config.minmax = { 0.1, 1.0 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimit) },
748 { "pidsum_limit_yaw", VAR_FLOAT | PROFILE_VALUE, .config.minmax = { 0.1, 1.0 }, PG_PID_PROFILE, offsetof(pidProfile_t, pidSumLimitYaw) },
750 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PITCH]) },
751 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PITCH]) },
752 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PITCH]) },
753 { "p_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[ROLL]) },
754 { "i_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[ROLL]) },
755 { "d_roll", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[ROLL]) },
756 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[YAW]) },
757 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[YAW]) },
758 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[YAW]) },
760 { "p_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDALT]) },
761 { "i_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDALT]) },
762 { "d_alt", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDALT]) },
764 { "p_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDLEVEL]) },
765 { "i_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDLEVEL]) },
766 { "d_level", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDLEVEL]) },
768 { "p_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDVEL]) },
769 { "i_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDVEL]) },
770 { "d_vel", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDVEL]) },
772 { "level_sensitivity", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelSensitivity) },
773 { "level_limit", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 10, 120 }, PG_PID_PROFILE, offsetof(pidProfile_t, levelAngleLimit) },
774 #ifdef GPS
775 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOS]) },
776 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOS]) },
777 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOS]) },
778 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDPOSR]) },
779 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDPOSR]) },
780 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDPOSR]) },
781 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, P8[PIDNAVR]) },
782 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, I8[PIDNAVR]) },
783 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, .config.minmax = { 0, 200 }, PG_PID_PROFILE, offsetof(pidProfile_t, D8[PIDNAVR]) },
784 #endif
786 // PG_TELEMETRY_CONFIG
787 #ifdef TELEMETRY
788 { "tlm_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_switch) },
789 { "tlm_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, telemetry_inversion) },
790 { "sport_halfduplex", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, sportHalfDuplex) },
791 { "frsky_default_lat", VAR_FLOAT | MASTER_VALUE, .config.minmax = { -90.0, 90.0 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLatitude) },
792 { "frsky_default_long", VAR_FLOAT | MASTER_VALUE, .config.minmax = { -180.0, 180.0 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, gpsNoFixLongitude) },
793 { "frsky_gps_format", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_coordinate_format) },
794 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_unit) },
795 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, frsky_vfas_precision) },
796 { "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) },
797 { "hott_alarm_int", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 120 }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, hottAlarmSoundInterval) },
798 { "pid_in_tlm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = {TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, pidValuesAsTelemetry) },
799 #if defined(TELEMETRY_IBUS)
800 { "ibus_report_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_TELEMETRY_CONFIG, offsetof(telemetryConfig_t, report_cell_voltage) },
801 #endif
802 #endif
804 // PG_LED_STRIP_CONFIG
805 #ifdef LED_STRIP
806 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ledstrip_visual_beeper) },
807 #endif
809 // PG_SDCARD_CONFIG
810 #ifdef USE_SDCARD
811 { "sdcard_dma", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SDCARD_CONFIG, offsetof(sdcardConfig_t, useDma) },
812 #endif
814 // PG_OSD_CONFIG
815 #ifdef OSD
816 { "osd_units", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_UNIT }, PG_OSD_CONFIG, offsetof(osdConfig_t, units) },
818 { "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
819 { "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
820 { "osd_time_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 60 }, PG_OSD_CONFIG, offsetof(osdConfig_t, time_alarm) },
821 { "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
823 { "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]) },
824 { "osd_rssi_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_RSSI_VALUE]) },
825 { "osd_flytimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYTIME]) },
826 { "osd_ontimer_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ONTIME]) },
827 { "osd_flymode_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_FLYMODE]) },
828 { "osd_throttle_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_THROTTLE_POS]) },
829 { "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]) },
830 { "osd_crosshairs", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CROSSHAIRS]) },
831 { "osd_horizon_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ARTIFICIAL_HORIZON]) },
832 { "osd_current_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_CURRENT_DRAW]) },
833 { "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]) },
834 { "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]) },
835 { "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]) },
836 { "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]) },
837 { "osd_altitude_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_ALTITUDE]) },
838 { "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]) },
839 { "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]) },
840 { "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]) },
841 { "osd_power_pos", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 0, OSD_POSCFG_MAX }, PG_OSD_CONFIG, offsetof(osdConfig_t, item_pos[OSD_POWER]) },
842 { "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]) },
843 { "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]) },
844 { "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]) },
845 #endif
847 // PG_SYSTEM_CONFIG
848 #ifndef SKIP_TASK_STATISTICS
849 { "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
850 #endif
851 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_DEBUG }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, debug_mode) },
853 // PG_VTX_CONFIG
854 #ifdef VTX
855 { "vtx_band", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 5 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_band) },
856 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 1, 8 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_channel) },
857 { "vtx_mode", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 2 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_mode) },
858 { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, .config.minmax = { 5600, 5950 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_mhz) },
859 #endif
860 #if defined(USE_RTC6705)
861 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 39 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_channel) },
862 { "vtx_power", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 1 }, PG_VTX_CONFIG, offsetof(vtxConfig_t, vtx_power) },
863 #endif
865 // PG_VCD_CONFIG
866 #ifdef USE_MAX7456
867 { "vcd_video_system", VAR_UINT8 | MASTER_VALUE, .config.minmax = { 0, 2 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, video_system) },
868 { "vcd_h_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -32, 31 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, h_offset) },
869 { "vcd_v_offset", VAR_INT8 | MASTER_VALUE, .config.minmax = { -15, 16 }, PG_VCD_CONFIG, offsetof(vcdProfile_t, v_offset) },
870 #endif
872 // PG_DISPLAY_PORT_MSP_CONFIG
873 #ifdef USE_MSP_DISPLAYPORT
874 { "displayport_msp_col_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
875 { "displayport_msp_row_adjust", VAR_INT8 | MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
876 #endif
878 // PG_DISPLAY_PORT_MSP_CONFIG
879 #ifdef USE_MAX7456
880 { "displayport_max7456_col_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -6, 0 }, PG_DISPLAY_PORT_MSP_CONFIG, offsetof(displayPortProfile_t, colAdjust) },
881 { "displayport_max7456_row_adjust", VAR_INT8| MASTER_VALUE, .config.minmax = { -3, 0 }, PG_DISPLAY_PORT_MAX7456_CONFIG, offsetof(displayPortProfile_t, rowAdjust) },
882 #endif
885 static featureConfig_t featureConfigCopy;
886 static gyroConfig_t gyroConfigCopy;
887 static accelerometerConfig_t accelerometerConfigCopy;
888 #ifdef MAG
889 static compassConfig_t compassConfigCopy;
890 #endif
891 #ifdef BARO
892 static barometerConfig_t barometerConfigCopy;
893 #endif
894 #ifdef PITOT
895 static pitotmeterConfig_t pitotmeterConfigCopy;
896 #endif
897 static featureConfig_t featureConfigCopy;
898 static rxConfig_t rxConfigCopy;
899 // PG_PWM_CONFIG
900 #ifdef USE_PWM
901 static pwmConfig_t pwmConfigCopy;
902 #endif
903 #ifdef BLACKBOX
904 static blackboxConfig_t blackboxConfigCopy;
905 #endif
906 static rxFailsafeChannelConfig_t rxFailsafeChannelConfigsCopy[MAX_SUPPORTED_RC_CHANNEL_COUNT];
907 static rxChannelRangeConfig_t rxChannelRangeConfigsCopy[NON_AUX_CHANNEL_COUNT];
908 static motorConfig_t motorConfigCopy;
909 static throttleCorrectionConfig_t throttleCorrectionConfigCopy;
910 static failsafeConfig_t failsafeConfigCopy;
911 static boardAlignment_t boardAlignmentCopy;
912 #ifdef USE_SERVOS
913 static servoConfig_t servoConfigCopy;
914 static gimbalConfig_t gimbalConfigCopy;
915 static servoMixer_t customServoMixersCopy[MAX_SERVO_RULES];
916 static servoParam_t servoParamsCopy[MAX_SUPPORTED_SERVOS];
917 #endif
918 static batteryConfig_t batteryConfigCopy;
919 static voltageSensorADCConfig_t voltageSensorADCConfigCopy[MAX_VOLTAGE_SENSOR_ADC];
920 static currentSensorADCConfig_t currentSensorADCConfigCopy;
921 static currentSensorVirtualConfig_t currentSensorVirtualConfigCopy;
922 static motorMixer_t customMotorMixerCopy[MAX_SUPPORTED_MOTORS];
923 static mixerConfig_t mixerConfigCopy;
924 static flight3DConfig_t flight3DConfigCopy;
925 static serialConfig_t serialConfigCopy;
926 static imuConfig_t imuConfigCopy;
927 static armingConfig_t armingConfigCopy;
928 static rcControlsConfig_t rcControlsConfigCopy;
929 #ifdef GPS
930 static gpsConfig_t gpsConfigCopy;
931 static navigationConfig_t navigationConfigCopy;
932 #endif
933 static airplaneConfig_t airplaneConfigCopy;
934 #ifdef TELEMETRY
935 static telemetryConfig_t telemetryConfigCopy;
936 #endif
937 static modeActivationCondition_t modeActivationConditionsCopy[MAX_MODE_ACTIVATION_CONDITION_COUNT];
938 static adjustmentRange_t adjustmentRangesCopy[MAX_ADJUSTMENT_RANGE_COUNT];
939 #ifdef LED_STRIP
940 static ledStripConfig_t ledStripConfigCopy;
941 #endif
942 #ifdef USE_SDCARD
943 static sdcardConfig_t sdcardConfigCopy;
944 #endif
945 #ifdef OSD
946 static osdConfig_t osdConfigCopy;
947 #endif
948 static systemConfig_t systemConfigCopy;
949 #ifdef BEEPER
950 static beeperDevConfig_t beeperDevConfigCopy;
951 static beeperConfig_t beeperConfigCopy;
952 #endif
953 #if defined(USE_RTC6705) || defined(VTX)
954 static vtxConfig_t vtxConfigCopy;
955 #endif
956 #ifdef USE_MAX7456
957 vcdProfile_t vcdProfileCopy;
958 #endif
959 #ifdef USE_MSP_DISPLAYPORT
960 displayPortProfile_t displayPortProfileMspCopy;
961 #endif
962 #ifdef USE_MAX7456
963 displayPortProfile_t displayPortProfileMax7456Copy;
964 #endif
965 static pidConfig_t pidConfigCopy;
966 static controlRateConfig_t controlRateProfilesCopy[CONTROL_RATE_PROFILE_COUNT];
967 static pidProfile_t pidProfileCopy[MAX_PROFILE_COUNT];
968 #endif // USE_PARAMETER_GROUPS
970 static void cliPrint(const char *str)
972 while (*str) {
973 bufWriterAppend(cliWriter, *str++);
975 bufWriterFlush(cliWriter);
978 #ifdef MINIMAL_CLI
979 #define cliPrintHashLine(str)
980 #else
981 static void cliPrintHashLine(const char *str)
983 cliPrint("\r\n# ");
984 cliPrint(str);
985 cliPrint("\r\n");
987 #endif
989 static void cliPutp(void *p, char ch)
991 bufWriterAppend(p, ch);
994 typedef enum {
995 DUMP_MASTER = (1 << 0),
996 DUMP_PROFILE = (1 << 1),
997 DUMP_RATES = (1 << 2),
998 DUMP_ALL = (1 << 3),
999 DO_DIFF = (1 << 4),
1000 SHOW_DEFAULTS = (1 << 5),
1001 HIDE_UNUSED = (1 << 6)
1002 } dumpFlags_e;
1004 static bool cliDumpPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
1006 if (!((dumpMask & DO_DIFF) && equalsDefault)) {
1007 va_list va;
1008 va_start(va, format);
1009 tfp_format(cliWriter, cliPutp, format, va);
1010 va_end(va);
1011 bufWriterFlush(cliWriter);
1012 return true;
1013 } else {
1014 return false;
1018 static void cliWrite(uint8_t ch)
1020 bufWriterAppend(cliWriter, ch);
1023 static bool cliDefaultPrintf(uint8_t dumpMask, bool equalsDefault, const char *format, ...)
1025 if ((dumpMask & SHOW_DEFAULTS) && !equalsDefault) {
1026 cliWrite('#');
1028 va_list va;
1029 va_start(va, format);
1030 tfp_format(cliWriter, cliPutp, format, va);
1031 va_end(va);
1032 bufWriterFlush(cliWriter);
1033 return true;
1034 } else {
1035 return false;
1039 static void cliPrintf(const char *format, ...)
1041 va_list va;
1042 va_start(va, format);
1043 tfp_format(cliWriter, cliPutp, format, va);
1044 va_end(va);
1045 bufWriterFlush(cliWriter);
1048 static void printValuePointer(const clivalue_t *var, const void *valuePointer, uint32_t full)
1050 int32_t value = 0;
1051 char buf[8];
1053 switch (var->type & VALUE_TYPE_MASK) {
1054 case VAR_UINT8:
1055 value = *(uint8_t *)valuePointer;
1056 break;
1058 case VAR_INT8:
1059 value = *(int8_t *)valuePointer;
1060 break;
1062 case VAR_UINT16:
1063 value = *(uint16_t *)valuePointer;
1064 break;
1066 case VAR_INT16:
1067 value = *(int16_t *)valuePointer;
1068 break;
1070 /* not currently used
1071 case VAR_UINT32:
1072 value = *(uint32_t *)valuePointer;
1073 break; */
1075 case VAR_FLOAT:
1076 cliPrintf("%s", ftoa(*(float *)valuePointer, buf));
1077 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
1078 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
1079 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
1081 return; // return from case for float only
1084 switch(var->type & VALUE_MODE_MASK) {
1085 case MODE_DIRECT:
1086 cliPrintf("%d", value);
1087 if (full) {
1088 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
1090 break;
1091 case MODE_LOOKUP:
1092 cliPrint(lookupTables[var->config.lookup.tableIndex].values[value]);
1093 break;
1097 #ifdef USE_PARAMETER_GROUPS
1099 static bool valuePtrEqualsDefault(uint8_t type, const void *ptr, const void *ptrDefault)
1101 bool result = false;
1102 switch (type & VALUE_TYPE_MASK) {
1103 case VAR_UINT8:
1104 result = *(uint8_t *)ptr == *(uint8_t *)ptrDefault;
1105 break;
1107 case VAR_INT8:
1108 result = *(int8_t *)ptr == *(int8_t *)ptrDefault;
1109 break;
1111 case VAR_UINT16:
1112 result = *(uint16_t *)ptr == *(uint16_t *)ptrDefault;
1113 break;
1115 case VAR_INT16:
1116 result = *(int16_t *)ptr == *(int16_t *)ptrDefault;
1117 break;
1119 /* not currently used
1120 case VAR_UINT32:
1121 result = *(uint32_t *)ptr == *(uint32_t *)ptrDefault;
1122 break;*/
1124 case VAR_FLOAT:
1125 result = *(float *)ptr == *(float *)ptrDefault;
1126 break;
1128 return result;
1131 typedef struct cliCurrentAndDefaultConfig_s {
1132 const void *currentConfig; // the copy
1133 const void *defaultConfig; // the PG value as set by default
1134 } cliCurrentAndDefaultConfig_t;
1136 static const cliCurrentAndDefaultConfig_t *getCurrentAndDefaultConfigs(pgn_t pgn)
1138 static cliCurrentAndDefaultConfig_t ret;
1140 switch (pgn) {
1141 case PG_GYRO_CONFIG:
1142 ret.currentConfig = &gyroConfigCopy;
1143 ret.defaultConfig = gyroConfig();
1144 break;
1145 case PG_ACCELEROMETER_CONFIG:
1146 ret.currentConfig = &accelerometerConfigCopy;
1147 ret.defaultConfig = accelerometerConfig();
1148 break;
1149 #ifdef MAG
1150 case PG_COMPASS_CONFIG:
1151 ret.currentConfig = &compassConfigCopy;
1152 ret.defaultConfig = compassConfig();
1153 break;
1154 #endif
1155 #ifdef BARO
1156 case PG_BAROMETER_CONFIG:
1157 ret.currentConfig = &barometerConfigCopy;
1158 ret.defaultConfig = barometerConfig();
1159 break;
1160 #endif
1161 #ifdef PITOT
1162 case PG_PITOTMETER_CONFIG:
1163 ret.currentConfig = &pitotmeterConfigCopy;
1164 ret.defaultConfig = pitotmeterConfig();
1165 break;
1166 #endif
1167 case PG_FEATURE_CONFIG:
1168 ret.currentConfig = &featureConfigCopy;
1169 ret.defaultConfig = featureConfig();
1170 break;
1171 case PG_RX_CONFIG:
1172 ret.currentConfig = &rxConfigCopy;
1173 ret.defaultConfig = rxConfig();
1174 break;
1175 #ifdef USE_PWM
1176 case PG_PWM_CONFIG:
1177 ret.currentConfig = &pwmConfigCopy;
1178 ret.defaultConfig = pwmConfig();
1179 break;
1180 #endif
1181 #ifdef BLACKBOX
1182 case PG_BLACKBOX_CONFIG:
1183 ret.currentConfig = &blackboxConfigCopy;
1184 ret.defaultConfig = blackboxConfig();
1185 break;
1186 #endif
1187 case PG_MOTOR_CONFIG:
1188 ret.currentConfig = &motorConfigCopy;
1189 ret.defaultConfig = motorConfig();
1190 break;
1191 case PG_THROTTLE_CORRECTION_CONFIG:
1192 ret.currentConfig = &throttleCorrectionConfigCopy;
1193 ret.defaultConfig = throttleCorrectionConfig();
1194 break;
1195 case PG_FAILSAFE_CONFIG:
1196 ret.currentConfig = &failsafeConfigCopy;
1197 ret.defaultConfig = failsafeConfig();
1198 break;
1199 case PG_BOARD_ALIGNMENT:
1200 ret.currentConfig = &boardAlignmentCopy;
1201 ret.defaultConfig = boardAlignment();
1202 break;
1203 case PG_MIXER_CONFIG:
1204 ret.currentConfig = &mixerConfigCopy;
1205 ret.defaultConfig = mixerConfig();
1206 break;
1207 case PG_MOTOR_3D_CONFIG:
1208 ret.currentConfig = &flight3DConfigCopy;
1209 ret.defaultConfig = flight3DConfig();
1210 break;
1211 #ifdef USE_SERVOS
1212 case PG_SERVO_CONFIG:
1213 ret.currentConfig = &servoConfigCopy;
1214 ret.defaultConfig = servoConfig();
1215 break;
1216 case PG_GIMBAL_CONFIG:
1217 ret.currentConfig = &gimbalConfigCopy;
1218 ret.defaultConfig = gimbalConfig();
1219 break;
1220 #endif
1221 case PG_BATTERY_CONFIG:
1222 ret.currentConfig = &batteryConfigCopy;
1223 ret.defaultConfig = batteryConfig();
1224 break;
1225 case PG_VOLTAGE_SENSOR_ADC_CONFIG:
1226 ret.currentConfig = &voltageSensorADCConfigCopy[0];
1227 ret.defaultConfig = voltageSensorADCConfig(0);
1228 break;
1229 case PG_CURRENT_SENSOR_ADC_CONFIG:
1230 ret.currentConfig = &currentSensorADCConfigCopy;
1231 ret.defaultConfig = currentSensorADCConfig();
1232 break;
1233 case PG_CURRENT_SENSOR_VIRTUAL_CONFIG:
1234 ret.currentConfig = &currentSensorVirtualConfigCopy;
1235 ret.defaultConfig = currentSensorVirtualConfig();
1236 break;
1237 case PG_SERIAL_CONFIG:
1238 ret.currentConfig = &serialConfigCopy;
1239 ret.defaultConfig = serialConfig();
1240 break;
1241 case PG_IMU_CONFIG:
1242 ret.currentConfig = &imuConfigCopy;
1243 ret.defaultConfig = imuConfig();
1244 break;
1245 case PG_RC_CONTROLS_CONFIG:
1246 ret.currentConfig = &rcControlsConfigCopy;
1247 ret.defaultConfig = rcControlsConfig();
1248 break;
1249 case PG_ARMING_CONFIG:
1250 ret.currentConfig = &armingConfigCopy;
1251 ret.defaultConfig = armingConfig();
1252 break;
1253 #ifdef GPS
1254 case PG_GPS_CONFIG:
1255 ret.currentConfig = &gpsConfigCopy;
1256 ret.defaultConfig = gpsConfig();
1257 break;
1258 case PG_NAVIGATION_CONFIG:
1259 ret.currentConfig = &navigationConfigCopy;
1260 ret.defaultConfig = navigationConfig();
1261 break;
1262 #endif
1263 case PG_AIRPLANE_CONFIG:
1264 ret.currentConfig = &airplaneConfigCopy;
1265 ret.defaultConfig = airplaneConfig();
1266 break;
1267 #ifdef TELEMETRY
1268 case PG_TELEMETRY_CONFIG:
1269 ret.currentConfig = &telemetryConfigCopy;
1270 ret.defaultConfig = telemetryConfig();
1271 break;
1272 #endif
1273 #ifdef LED_STRIP
1274 case PG_LED_STRIP_CONFIG:
1275 ret.currentConfig = &ledStripConfigCopy;
1276 ret.defaultConfig = ledStripConfig();
1277 break;
1278 #endif
1279 #ifdef USE_SDCARD
1280 case PG_SDCARD_CONFIG:
1281 ret.currentConfig = &sdcardConfigCopy;
1282 ret.defaultConfig = sdcardConfig();
1283 break;
1284 #endif
1285 #ifdef OSD
1286 case PG_OSD_CONFIG:
1287 ret.currentConfig = &osdConfigCopy;
1288 ret.defaultConfig = osdConfig();
1289 break;
1290 #endif
1291 case PG_SYSTEM_CONFIG:
1292 ret.currentConfig = &systemConfigCopy;
1293 ret.defaultConfig = systemConfig();
1294 break;
1295 case PG_CONTROL_RATE_PROFILES:
1296 ret.currentConfig = &controlRateProfilesCopy[0];
1297 ret.defaultConfig = controlRateProfiles(0);
1298 break;
1299 case PG_PID_PROFILE:
1300 ret.currentConfig = &pidProfileCopy[0];
1301 ret.defaultConfig = pidProfiles(0);
1302 break;
1303 case PG_RX_FAILSAFE_CHANNEL_CONFIG:
1304 ret.currentConfig = &rxFailsafeChannelConfigsCopy[0];
1305 ret.defaultConfig = rxFailsafeChannelConfigs(0);
1306 break;
1307 case PG_RX_CHANNEL_RANGE_CONFIG:
1308 ret.currentConfig = &rxChannelRangeConfigsCopy[0];
1309 ret.defaultConfig = rxChannelRangeConfigs(0);
1310 break;
1311 #ifdef USE_SERVOS
1312 case PG_SERVO_MIXER:
1313 ret.currentConfig = &customServoMixersCopy[0];
1314 ret.defaultConfig = customServoMixers(0);
1315 break;
1316 case PG_SERVO_PARAMS:
1317 ret.currentConfig = &servoParamsCopy[0];
1318 ret.defaultConfig = servoParams(0);
1319 break;
1320 #endif
1321 case PG_MOTOR_MIXER:
1322 ret.currentConfig = &customMotorMixerCopy[0];
1323 ret.defaultConfig = customMotorMixer(0);
1324 break;
1325 case PG_MODE_ACTIVATION_PROFILE:
1326 ret.currentConfig = &modeActivationConditionsCopy[0];
1327 ret.defaultConfig = modeActivationConditions(0);
1328 break;
1329 case PG_ADJUSTMENT_RANGE_CONFIG:
1330 ret.currentConfig = &adjustmentRangesCopy[0];
1331 ret.defaultConfig = adjustmentRanges(0);
1332 break;
1333 #ifdef BEEPER
1334 case PG_BEEPER_CONFIG:
1335 ret.currentConfig = &beeperConfigCopy;
1336 ret.defaultConfig = beeperConfig();
1337 break;
1338 case PG_BEEPER_DEV_CONFIG:
1339 ret.currentConfig = &beeperDevConfigCopy;
1340 ret.defaultConfig = beeperDevConfig();
1341 break;
1342 #endif
1343 #ifdef VTX
1344 case PG_VTX_CONFIG:
1345 ret.currentConfig = &vtxConfigCopy;
1346 ret.defaultConfig = vtxConfig();
1347 break;
1348 #endif
1349 #ifdef USE_MAX7456
1350 case PG_VCD_CONFIG:
1351 ret.currentConfig = &vcdProfileCopy;
1352 ret.defaultConfig = vcdProfile();
1353 break;
1354 #endif
1355 #ifdef USE_MSP_DISPLAYPORT
1356 case PG_DISPLAY_PORT_MSP_CONFIG:
1357 ret.currentConfig = &displayPortProfileMspCopy;
1358 ret.defaultConfig = displayPortProfileMsp();
1359 break;
1360 #endif
1361 #ifdef USE_MAX7456
1362 case PG_DISPLAY_PORT_MAX7456_CONFIG:
1363 ret.currentConfig = &displayPortProfileMax7456Copy;
1364 ret.defaultConfig = displayPortProfileMax7456();
1365 break;
1366 #endif
1367 case PG_PID_CONFIG:
1368 ret.currentConfig = &pidConfigCopy;
1369 ret.defaultConfig = pidConfig();
1370 break;
1371 default:
1372 ret.currentConfig = NULL;
1373 ret.defaultConfig = NULL;
1374 break;
1376 return &ret;
1379 static uint16_t getValueOffset(const clivalue_t *value)
1381 switch (value->type & VALUE_SECTION_MASK) {
1382 case MASTER_VALUE:
1383 return value->offset;
1384 case PROFILE_VALUE:
1385 return value->offset + sizeof(pidProfile_t) * getCurrentPidProfileIndex();
1386 case PROFILE_RATE_VALUE:
1387 return value->offset + sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
1389 return 0;
1392 static void *getValuePointer(const clivalue_t *value)
1394 const pgRegistry_t* rec = pgFind(value->pgn);
1395 return CONST_CAST(void *, rec->address + getValueOffset(value));
1398 static void dumpPgValue(const clivalue_t *value, uint8_t dumpMask)
1400 const char *format = "set %s = ";
1401 const cliCurrentAndDefaultConfig_t *config = getCurrentAndDefaultConfigs(value->pgn);
1402 if (config->currentConfig == NULL || config->defaultConfig == NULL) {
1403 // has not been set up properly
1404 cliPrintf("VALUE %s ERROR\r\n", value->name);
1405 return;
1407 const int valueOffset = getValueOffset(value);
1408 switch (dumpMask & (DO_DIFF | SHOW_DEFAULTS)) {
1409 case DO_DIFF:
1410 if (valuePtrEqualsDefault(value->type, (uint8_t*)config->currentConfig + valueOffset, (uint8_t*)config->defaultConfig + valueOffset)) {
1411 break;
1413 // drop through, since not equal to default
1414 case 0:
1415 case SHOW_DEFAULTS:
1416 cliPrintf(format, value->name);
1417 printValuePointer(value, (uint8_t*)config->currentConfig + valueOffset, 0);
1418 cliPrint("\r\n");
1419 break;
1423 static void dumpAllValues(uint16_t valueSection, uint8_t dumpMask)
1425 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
1426 const clivalue_t *value = &valueTable[i];
1427 bufWriterFlush(cliWriter);
1428 if ((value->type & VALUE_SECTION_MASK) == valueSection) {
1429 dumpPgValue(value, dumpMask);
1434 #else
1436 void *getValuePointer(const clivalue_t *value)
1438 uint8_t *ptr = value->ptr;
1440 if ((value->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
1441 ptr += sizeof(pidProfile_t) * getCurrentPidProfileIndex();
1442 } else if ((value->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
1443 ptr += sizeof(controlRateConfig_t) * getCurrentControlRateProfileIndex();
1446 return ptr;
1449 static void *getDefaultPointer(void *valuePointer, const master_t *defaultConfig)
1451 return ((uint8_t *)valuePointer) - (uint32_t)&masterConfig + (uint32_t)defaultConfig;
1454 static bool valueEqualsDefault(const clivalue_t *value, const master_t *defaultConfig)
1456 void *ptr = getValuePointer(value);
1458 void *ptrDefault = getDefaultPointer(ptr, defaultConfig);
1460 bool result = false;
1461 switch (value->type & VALUE_TYPE_MASK) {
1462 case VAR_UINT8:
1463 result = *(uint8_t *)ptr == *(uint8_t *)ptrDefault;
1464 break;
1466 case VAR_INT8:
1467 result = *(int8_t *)ptr == *(int8_t *)ptrDefault;
1468 break;
1470 case VAR_UINT16:
1471 result = *(uint16_t *)ptr == *(uint16_t *)ptrDefault;
1472 break;
1474 case VAR_INT16:
1475 result = *(int16_t *)ptr == *(int16_t *)ptrDefault;
1476 break;
1478 /* not currently used
1479 case VAR_UINT32:
1480 result = *(uint32_t *)ptr == *(uint32_t *)ptrDefault;
1481 break; */
1483 case VAR_FLOAT:
1484 result = *(float *)ptr == *(float *)ptrDefault;
1485 break;
1487 return result;
1490 static void cliPrintVarDefault(const clivalue_t *var, uint32_t full, const master_t *defaultConfig)
1492 void *ptr = getValuePointer(var);
1494 void *defaultPtr = getDefaultPointer(ptr, defaultConfig);
1496 printValuePointer(var, defaultPtr, full);
1499 static void dumpValues(uint16_t valueSection, uint8_t dumpMask, const master_t *defaultConfig)
1501 const clivalue_t *value;
1502 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
1503 value = &valueTable[i];
1505 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1506 continue;
1509 const char *format = "set %s = ";
1510 if (cliDefaultPrintf(dumpMask, valueEqualsDefault(value, defaultConfig), format, valueTable[i].name)) {
1511 cliPrintVarDefault(value, 0, defaultConfig);
1512 cliPrint("\r\n");
1514 if (cliDumpPrintf(dumpMask, valueEqualsDefault(value, defaultConfig), format, valueTable[i].name)) {
1515 cliPrintVar(value, 0);
1516 cliPrint("\r\n");
1520 #endif // USE_PARAMETER_GROUPS
1522 static void cliPrintVar(const clivalue_t *var, uint32_t full)
1524 const void *ptr = getValuePointer(var);
1526 printValuePointer(var, ptr, full);
1529 static void cliPrintVarRange(const clivalue_t *var)
1531 switch (var->type & VALUE_MODE_MASK) {
1532 case (MODE_DIRECT): {
1533 cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
1535 break;
1536 case (MODE_LOOKUP): {
1537 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
1538 cliPrint("Allowed values:");
1539 for (uint32_t i = 0; i < tableEntry->valueCount ; i++) {
1540 if (i > 0)
1541 cliPrint(",");
1542 cliPrintf(" %s", tableEntry->values[i]);
1544 cliPrint("\r\n");
1546 break;
1550 typedef union {
1551 int32_t int_value;
1552 float float_value;
1553 } int_float_value_t;
1555 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
1557 void *ptr = getValuePointer(var);
1559 switch (var->type & VALUE_TYPE_MASK) {
1560 case VAR_UINT8:
1561 case VAR_INT8:
1562 *(int8_t *)ptr = value.int_value;
1563 break;
1565 case VAR_UINT16:
1566 case VAR_INT16:
1567 *(int16_t *)ptr = value.int_value;
1568 break;
1570 /* not currently used
1571 case VAR_UINT32:
1572 *(uint32_t *)ptr = value.int_value;
1573 break; */
1575 case VAR_FLOAT:
1576 *(float *)ptr = (float)value.float_value;
1577 break;
1581 #ifndef MINIMAL_CLI
1582 static void cliRepeat(char ch, uint8_t len)
1584 for (int i = 0; i < len; i++) {
1585 bufWriterAppend(cliWriter, ch);
1587 cliPrint("\r\n");
1589 #endif
1591 static void cliPrompt(void)
1593 cliPrint("\r\n# ");
1596 static void cliShowParseError(void)
1598 cliPrint("Parse error\r\n");
1601 static void cliShowArgumentRangeError(char *name, int min, int max)
1603 cliPrintf("%s not between %d and %d\r\n", name, min, max);
1606 static const char *nextArg(const char *currentArg)
1608 const char *ptr = strchr(currentArg, ' ');
1609 while (ptr && *ptr == ' ') {
1610 ptr++;
1613 return ptr;
1616 static const char *processChannelRangeArgs(const char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
1618 for (uint32_t argIndex = 0; argIndex < 2; argIndex++) {
1619 ptr = nextArg(ptr);
1620 if (ptr) {
1621 int val = atoi(ptr);
1622 val = CHANNEL_VALUE_TO_STEP(val);
1623 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
1624 if (argIndex == 0) {
1625 range->startStep = val;
1626 } else {
1627 range->endStep = val;
1629 (*validArgumentCount)++;
1634 return ptr;
1637 // Check if a string's length is zero
1638 static bool isEmpty(const char *string)
1640 return (string == NULL || *string == '\0') ? true : false;
1643 static void printRxFailsafe(uint8_t dumpMask, const rxFailsafeChannelConfig_t *rxFailsafeChannelConfigs, const rxFailsafeChannelConfig_t *defaultRxFailsafeChannelConfigs)
1645 // print out rxConfig failsafe settings
1646 for (uint32_t channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
1647 const rxFailsafeChannelConfig_t *channelFailsafeConfig = &rxFailsafeChannelConfigs[channel];
1648 const rxFailsafeChannelConfig_t *defaultChannelFailsafeConfig = &defaultRxFailsafeChannelConfigs[channel];
1649 const bool equalsDefault = channelFailsafeConfig->mode == defaultChannelFailsafeConfig->mode
1650 && channelFailsafeConfig->step == defaultChannelFailsafeConfig->step;
1651 const bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
1652 if (requireValue) {
1653 const char *format = "rxfail %u %c %d\r\n";
1654 cliDefaultPrintf(dumpMask, equalsDefault, format,
1655 channel,
1656 rxFailsafeModeCharacters[defaultChannelFailsafeConfig->mode],
1657 RXFAIL_STEP_TO_CHANNEL_VALUE(defaultChannelFailsafeConfig->step)
1659 cliDumpPrintf(dumpMask, equalsDefault, format,
1660 channel,
1661 rxFailsafeModeCharacters[channelFailsafeConfig->mode],
1662 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
1664 } else {
1665 const char *format = "rxfail %u %c\r\n";
1666 cliDefaultPrintf(dumpMask, equalsDefault, format,
1667 channel,
1668 rxFailsafeModeCharacters[defaultChannelFailsafeConfig->mode]
1670 cliDumpPrintf(dumpMask, equalsDefault, format,
1671 channel,
1672 rxFailsafeModeCharacters[channelFailsafeConfig->mode]
1678 static void cliRxFailsafe(char *cmdline)
1680 uint8_t channel;
1681 char buf[3];
1683 if (isEmpty(cmdline)) {
1684 // print out rxConfig failsafe settings
1685 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
1686 cliRxFailsafe(itoa(channel, buf, 10));
1688 } else {
1689 const char *ptr = cmdline;
1690 channel = atoi(ptr++);
1691 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
1693 rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigsMutable(channel);
1695 const rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
1696 rxFailsafeChannelMode_e mode = channelFailsafeConfig->mode;
1697 bool requireValue = channelFailsafeConfig->mode == RX_FAILSAFE_MODE_SET;
1699 ptr = nextArg(ptr);
1700 if (ptr) {
1701 const char *p = strchr(rxFailsafeModeCharacters, *(ptr));
1702 if (p) {
1703 const uint8_t requestedMode = p - rxFailsafeModeCharacters;
1704 mode = rxFailsafeModesTable[type][requestedMode];
1705 } else {
1706 mode = RX_FAILSAFE_MODE_INVALID;
1708 if (mode == RX_FAILSAFE_MODE_INVALID) {
1709 cliShowParseError();
1710 return;
1713 requireValue = mode == RX_FAILSAFE_MODE_SET;
1715 ptr = nextArg(ptr);
1716 if (ptr) {
1717 if (!requireValue) {
1718 cliShowParseError();
1719 return;
1721 uint16_t value = atoi(ptr);
1722 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
1723 if (value > MAX_RXFAIL_RANGE_STEP) {
1724 cliPrint("Value out of range\r\n");
1725 return;
1728 channelFailsafeConfig->step = value;
1729 } else if (requireValue) {
1730 cliShowParseError();
1731 return;
1733 channelFailsafeConfig->mode = mode;
1736 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfig->mode];
1738 // double use of cliPrintf below
1739 // 1. acknowledge interpretation on command,
1740 // 2. query current setting on single item,
1742 if (requireValue) {
1743 cliPrintf("rxfail %u %c %d\r\n",
1744 channel,
1745 modeCharacter,
1746 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig->step)
1748 } else {
1749 cliPrintf("rxfail %u %c\r\n",
1750 channel,
1751 modeCharacter
1754 } else {
1755 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
1760 static void printAux(uint8_t dumpMask, const modeActivationCondition_t *modeActivationConditions, const modeActivationCondition_t *defaultModeActivationConditions)
1762 const char *format = "aux %u %u %u %u %u\r\n";
1763 // print out aux channel settings
1764 for (uint32_t i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
1765 const modeActivationCondition_t *mac = &modeActivationConditions[i];
1766 bool equalsDefault = false;
1767 if (defaultModeActivationConditions) {
1768 const modeActivationCondition_t *macDefault = &defaultModeActivationConditions[i];
1769 equalsDefault = mac->modeId == macDefault->modeId
1770 && mac->auxChannelIndex == macDefault->auxChannelIndex
1771 && mac->range.startStep == macDefault->range.startStep
1772 && mac->range.endStep == macDefault->range.endStep;
1773 cliDefaultPrintf(dumpMask, equalsDefault, format,
1775 macDefault->modeId,
1776 macDefault->auxChannelIndex,
1777 MODE_STEP_TO_CHANNEL_VALUE(macDefault->range.startStep),
1778 MODE_STEP_TO_CHANNEL_VALUE(macDefault->range.endStep)
1781 cliDumpPrintf(dumpMask, equalsDefault, format,
1783 mac->modeId,
1784 mac->auxChannelIndex,
1785 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
1786 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
1791 static void cliAux(char *cmdline)
1793 int i, val = 0;
1794 const char *ptr;
1796 if (isEmpty(cmdline)) {
1797 printAux(DUMP_MASTER, modeActivationConditions(0), NULL);
1798 } else {
1799 ptr = cmdline;
1800 i = atoi(ptr++);
1801 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
1802 modeActivationCondition_t *mac = modeActivationConditionsMutable(i);
1803 uint8_t validArgumentCount = 0;
1804 ptr = nextArg(ptr);
1805 if (ptr) {
1806 val = atoi(ptr);
1807 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
1808 mac->modeId = val;
1809 validArgumentCount++;
1812 ptr = nextArg(ptr);
1813 if (ptr) {
1814 val = atoi(ptr);
1815 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1816 mac->auxChannelIndex = val;
1817 validArgumentCount++;
1820 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
1822 if (validArgumentCount != 4) {
1823 memset(mac, 0, sizeof(modeActivationCondition_t));
1825 } else {
1826 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
1831 static void printSerial(uint8_t dumpMask, const serialConfig_t *serialConfig, const serialConfig_t *serialConfigDefault)
1833 const char *format = "serial %d %d %ld %ld %ld %ld\r\n";
1834 for (uint32_t i = 0; i < SERIAL_PORT_COUNT; i++) {
1835 if (!serialIsPortAvailable(serialConfig->portConfigs[i].identifier)) {
1836 continue;
1838 bool equalsDefault = false;
1839 if (serialConfigDefault) {
1840 equalsDefault = serialConfig->portConfigs[i].identifier == serialConfigDefault->portConfigs[i].identifier
1841 && serialConfig->portConfigs[i].functionMask == serialConfigDefault->portConfigs[i].functionMask
1842 && serialConfig->portConfigs[i].msp_baudrateIndex == serialConfigDefault->portConfigs[i].msp_baudrateIndex
1843 && serialConfig->portConfigs[i].gps_baudrateIndex == serialConfigDefault->portConfigs[i].gps_baudrateIndex
1844 && serialConfig->portConfigs[i].telemetry_baudrateIndex == serialConfigDefault->portConfigs[i].telemetry_baudrateIndex
1845 && serialConfig->portConfigs[i].blackbox_baudrateIndex == serialConfigDefault->portConfigs[i].blackbox_baudrateIndex;
1846 cliDefaultPrintf(dumpMask, equalsDefault, format,
1847 serialConfigDefault->portConfigs[i].identifier,
1848 serialConfigDefault->portConfigs[i].functionMask,
1849 baudRates[serialConfigDefault->portConfigs[i].msp_baudrateIndex],
1850 baudRates[serialConfigDefault->portConfigs[i].gps_baudrateIndex],
1851 baudRates[serialConfigDefault->portConfigs[i].telemetry_baudrateIndex],
1852 baudRates[serialConfigDefault->portConfigs[i].blackbox_baudrateIndex]
1855 cliDumpPrintf(dumpMask, equalsDefault, format,
1856 serialConfig->portConfigs[i].identifier,
1857 serialConfig->portConfigs[i].functionMask,
1858 baudRates[serialConfig->portConfigs[i].msp_baudrateIndex],
1859 baudRates[serialConfig->portConfigs[i].gps_baudrateIndex],
1860 baudRates[serialConfig->portConfigs[i].telemetry_baudrateIndex],
1861 baudRates[serialConfig->portConfigs[i].blackbox_baudrateIndex]
1866 static void cliSerial(char *cmdline)
1868 if (isEmpty(cmdline)) {
1869 printSerial(DUMP_MASTER, serialConfig(), NULL);
1870 return;
1872 serialPortConfig_t portConfig;
1873 memset(&portConfig, 0 , sizeof(portConfig));
1875 serialPortConfig_t *currentConfig;
1877 uint8_t validArgumentCount = 0;
1879 const char *ptr = cmdline;
1881 int val = atoi(ptr++);
1882 currentConfig = serialFindPortConfiguration(val);
1883 if (currentConfig) {
1884 portConfig.identifier = val;
1885 validArgumentCount++;
1888 ptr = nextArg(ptr);
1889 if (ptr) {
1890 val = atoi(ptr);
1891 portConfig.functionMask = val & 0xFFFF;
1892 validArgumentCount++;
1895 for (int i = 0; i < 4; i ++) {
1896 ptr = nextArg(ptr);
1897 if (!ptr) {
1898 break;
1901 val = atoi(ptr);
1903 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1904 if (baudRates[baudRateIndex] != (uint32_t) val) {
1905 break;
1908 switch(i) {
1909 case 0:
1910 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_1000000) {
1911 continue;
1913 portConfig.msp_baudrateIndex = baudRateIndex;
1914 break;
1915 case 1:
1916 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1917 continue;
1919 portConfig.gps_baudrateIndex = baudRateIndex;
1920 break;
1921 case 2:
1922 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1923 continue;
1925 portConfig.telemetry_baudrateIndex = baudRateIndex;
1926 break;
1927 case 3:
1928 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1929 continue;
1931 portConfig.blackbox_baudrateIndex = baudRateIndex;
1932 break;
1935 validArgumentCount++;
1938 if (validArgumentCount < 6) {
1939 cliShowParseError();
1940 return;
1943 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1946 #ifndef SKIP_SERIAL_PASSTHROUGH
1947 static void cliSerialPassthrough(char *cmdline)
1949 if (isEmpty(cmdline)) {
1950 cliShowParseError();
1951 return;
1954 int id = -1;
1955 uint32_t baud = 0;
1956 unsigned mode = 0;
1957 char *saveptr;
1958 char* tok = strtok_r(cmdline, " ", &saveptr);
1959 int index = 0;
1961 while (tok != NULL) {
1962 switch(index) {
1963 case 0:
1964 id = atoi(tok);
1965 break;
1966 case 1:
1967 baud = atoi(tok);
1968 break;
1969 case 2:
1970 if (strstr(tok, "rx") || strstr(tok, "RX"))
1971 mode |= MODE_RX;
1972 if (strstr(tok, "tx") || strstr(tok, "TX"))
1973 mode |= MODE_TX;
1974 break;
1976 index++;
1977 tok = strtok_r(NULL, " ", &saveptr);
1980 serialPort_t *passThroughPort;
1981 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1982 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1983 if (!baud) {
1984 printf("Port %d is closed, must specify baud.\r\n", id);
1985 return;
1987 if (!mode)
1988 mode = MODE_RXTX;
1990 passThroughPort = openSerialPort(id, FUNCTION_NONE, NULL,
1991 baud, mode,
1992 SERIAL_NOT_INVERTED);
1993 if (!passThroughPort) {
1994 printf("Port %d could not be opened.\r\n", id);
1995 return;
1997 printf("Port %d opened, baud = %d.\r\n", id, baud);
1998 } else {
1999 passThroughPort = passThroughPortUsage->serialPort;
2000 // If the user supplied a mode, override the port's mode, otherwise
2001 // leave the mode unchanged. serialPassthrough() handles one-way ports.
2002 printf("Port %d already open.\r\n", id);
2003 if (mode && passThroughPort->mode != mode) {
2004 printf("Adjusting mode from %d to %d.\r\n",
2005 passThroughPort->mode, mode);
2006 serialSetMode(passThroughPort, mode);
2008 // If this port has a rx callback associated we need to remove it now.
2009 // Otherwise no data will be pushed in the serial port buffer!
2010 if (passThroughPort->rxCallback) {
2011 printf("Removing rxCallback\r\n");
2012 passThroughPort->rxCallback = 0;
2016 printf("Forwarding data to %d, power cycle to exit.\r\n", id);
2018 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
2020 #endif
2022 static void printAdjustmentRange(uint8_t dumpMask, const adjustmentRange_t *adjustmentRanges, const adjustmentRange_t *defaultAdjustmentRanges)
2024 const char *format = "adjrange %u %u %u %u %u %u %u\r\n";
2025 // print out adjustment ranges channel settings
2026 for (uint32_t i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
2027 const adjustmentRange_t *ar = &adjustmentRanges[i];
2028 bool equalsDefault = false;
2029 if (defaultAdjustmentRanges) {
2030 const adjustmentRange_t *arDefault = &defaultAdjustmentRanges[i];
2031 equalsDefault = ar->auxChannelIndex == arDefault->auxChannelIndex
2032 && ar->range.startStep == arDefault->range.startStep
2033 && ar->range.endStep == arDefault->range.endStep
2034 && ar->adjustmentFunction == arDefault->adjustmentFunction
2035 && ar->auxSwitchChannelIndex == arDefault->auxSwitchChannelIndex
2036 && ar->adjustmentIndex == arDefault->adjustmentIndex;
2037 cliDefaultPrintf(dumpMask, equalsDefault, format,
2039 arDefault->adjustmentIndex,
2040 arDefault->auxChannelIndex,
2041 MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.startStep),
2042 MODE_STEP_TO_CHANNEL_VALUE(arDefault->range.endStep),
2043 arDefault->adjustmentFunction,
2044 arDefault->auxSwitchChannelIndex
2047 cliDumpPrintf(dumpMask, equalsDefault, format,
2049 ar->adjustmentIndex,
2050 ar->auxChannelIndex,
2051 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
2052 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
2053 ar->adjustmentFunction,
2054 ar->auxSwitchChannelIndex
2059 static void cliAdjustmentRange(char *cmdline)
2061 int i, val = 0;
2062 const char *ptr;
2064 if (isEmpty(cmdline)) {
2065 printAdjustmentRange(DUMP_MASTER, adjustmentRanges(0), NULL);
2066 } else {
2067 ptr = cmdline;
2068 i = atoi(ptr++);
2069 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
2070 adjustmentRange_t *ar = adjustmentRangesMutable(i);
2071 uint8_t validArgumentCount = 0;
2073 ptr = nextArg(ptr);
2074 if (ptr) {
2075 val = atoi(ptr);
2076 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
2077 ar->adjustmentIndex = val;
2078 validArgumentCount++;
2081 ptr = nextArg(ptr);
2082 if (ptr) {
2083 val = atoi(ptr);
2084 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2085 ar->auxChannelIndex = val;
2086 validArgumentCount++;
2090 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
2092 ptr = nextArg(ptr);
2093 if (ptr) {
2094 val = atoi(ptr);
2095 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
2096 ar->adjustmentFunction = val;
2097 validArgumentCount++;
2100 ptr = nextArg(ptr);
2101 if (ptr) {
2102 val = atoi(ptr);
2103 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2104 ar->auxSwitchChannelIndex = val;
2105 validArgumentCount++;
2109 if (validArgumentCount != 6) {
2110 memset(ar, 0, sizeof(adjustmentRange_t));
2111 cliShowParseError();
2113 } else {
2114 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
2119 #ifndef USE_QUAD_MIXER_ONLY
2120 static void printMotorMix(uint8_t dumpMask, const motorMixer_t *customMotorMixer, const motorMixer_t *defaultCustomMotorMixer)
2122 const char *format = "mmix %d %s %s %s %s\r\n";
2123 char buf0[8];
2124 char buf1[8];
2125 char buf2[8];
2126 char buf3[8];
2127 for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2128 if (customMotorMixer[i].throttle == 0.0f)
2129 break;
2130 const float thr = customMotorMixer[i].throttle;
2131 const float roll = customMotorMixer[i].roll;
2132 const float pitch = customMotorMixer[i].pitch;
2133 const float yaw = customMotorMixer[i].yaw;
2134 bool equalsDefault = false;
2135 if (defaultCustomMotorMixer) {
2136 const float thrDefault = defaultCustomMotorMixer[i].throttle;
2137 const float rollDefault = defaultCustomMotorMixer[i].roll;
2138 const float pitchDefault = defaultCustomMotorMixer[i].pitch;
2139 const float yawDefault = defaultCustomMotorMixer[i].yaw;
2140 const bool equalsDefault = thr == thrDefault && roll == rollDefault && pitch == pitchDefault && yaw == yawDefault;
2142 cliDefaultPrintf(dumpMask, equalsDefault, format,
2144 ftoa(thrDefault, buf0),
2145 ftoa(rollDefault, buf1),
2146 ftoa(pitchDefault, buf2),
2147 ftoa(yawDefault, buf3));
2149 cliDumpPrintf(dumpMask, equalsDefault, format,
2151 ftoa(thr, buf0),
2152 ftoa(roll, buf1),
2153 ftoa(pitch, buf2),
2154 ftoa(yaw, buf3));
2157 #endif // USE_QUAD_MIXER_ONLY
2159 static void cliMotorMix(char *cmdline)
2161 #ifdef USE_QUAD_MIXER_ONLY
2162 UNUSED(cmdline);
2163 #else
2164 int check = 0;
2165 uint8_t len;
2166 const char *ptr;
2168 if (isEmpty(cmdline)) {
2169 printMotorMix(DUMP_MASTER, customMotorMixer(0), NULL);
2170 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
2171 // erase custom mixer
2172 for (uint32_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2173 customMotorMixerMutable(i)->throttle = 0.0f;
2175 } else if (strncasecmp(cmdline, "load", 4) == 0) {
2176 ptr = nextArg(cmdline);
2177 if (ptr) {
2178 len = strlen(ptr);
2179 for (uint32_t i = 0; ; i++) {
2180 if (mixerNames[i] == NULL) {
2181 cliPrint("Invalid name\r\n");
2182 break;
2184 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
2185 mixerLoadMix(i, customMotorMixerMutable(0));
2186 cliPrintf("Loaded %s\r\n", mixerNames[i]);
2187 cliMotorMix("");
2188 break;
2192 } else {
2193 ptr = cmdline;
2194 uint32_t i = atoi(ptr); // get motor number
2195 if (i < MAX_SUPPORTED_MOTORS) {
2196 ptr = nextArg(ptr);
2197 if (ptr) {
2198 customMotorMixerMutable(i)->throttle = fastA2F(ptr);
2199 check++;
2201 ptr = nextArg(ptr);
2202 if (ptr) {
2203 customMotorMixerMutable(i)->roll = fastA2F(ptr);
2204 check++;
2206 ptr = nextArg(ptr);
2207 if (ptr) {
2208 customMotorMixerMutable(i)->pitch = fastA2F(ptr);
2209 check++;
2211 ptr = nextArg(ptr);
2212 if (ptr) {
2213 customMotorMixerMutable(i)->yaw = fastA2F(ptr);
2214 check++;
2216 if (check != 4) {
2217 cliShowParseError();
2218 } else {
2219 printMotorMix(DUMP_MASTER, customMotorMixer(0), NULL);
2221 } else {
2222 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2225 #endif
2228 static void printRxRange(uint8_t dumpMask, const rxChannelRangeConfig_t *channelRangeConfigs, const rxChannelRangeConfig_t *defaultChannelRangeConfigs)
2230 const char *format = "rxrange %u %u %u\r\n";
2231 for (uint32_t i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
2232 bool equalsDefault = false;
2233 if (defaultChannelRangeConfigs) {
2234 equalsDefault = channelRangeConfigs[i].min == defaultChannelRangeConfigs[i].min
2235 && channelRangeConfigs[i].max == defaultChannelRangeConfigs[i].max;
2236 cliDefaultPrintf(dumpMask, equalsDefault, format,
2238 defaultChannelRangeConfigs[i].min,
2239 defaultChannelRangeConfigs[i].max
2242 cliDumpPrintf(dumpMask, equalsDefault, format,
2244 channelRangeConfigs[i].min,
2245 channelRangeConfigs[i].max
2250 static void cliRxRange(char *cmdline)
2252 int i, validArgumentCount = 0;
2253 const char *ptr;
2255 if (isEmpty(cmdline)) {
2256 printRxRange(DUMP_MASTER, rxChannelRangeConfigs(0), NULL);
2257 } else if (strcasecmp(cmdline, "reset") == 0) {
2258 resetAllRxChannelRangeConfigurations(rxChannelRangeConfigsMutable(0));
2259 } else {
2260 ptr = cmdline;
2261 i = atoi(ptr);
2262 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
2263 int rangeMin, rangeMax;
2265 ptr = nextArg(ptr);
2266 if (ptr) {
2267 rangeMin = atoi(ptr);
2268 validArgumentCount++;
2271 ptr = nextArg(ptr);
2272 if (ptr) {
2273 rangeMax = atoi(ptr);
2274 validArgumentCount++;
2277 if (validArgumentCount != 2) {
2278 cliShowParseError();
2279 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
2280 cliShowParseError();
2281 } else {
2282 rxChannelRangeConfig_t *channelRangeConfig = rxChannelRangeConfigsMutable(i);
2283 channelRangeConfig->min = rangeMin;
2284 channelRangeConfig->max = rangeMax;
2286 } else {
2287 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
2292 #ifdef LED_STRIP
2293 static void printLed(uint8_t dumpMask, const ledConfig_t *ledConfigs, const ledConfig_t *defaultLedConfigs)
2295 const char *format = "led %u %s\r\n";
2296 char ledConfigBuffer[20];
2297 char ledConfigDefaultBuffer[20];
2298 for (uint32_t i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
2299 ledConfig_t ledConfig = ledConfigs[i];
2300 generateLedConfig(&ledConfig, ledConfigBuffer, sizeof(ledConfigBuffer));
2301 bool equalsDefault = false;
2302 if (defaultLedConfigs) {
2303 ledConfig_t ledConfigDefault = defaultLedConfigs[i];
2304 equalsDefault = ledConfig == ledConfigDefault;
2305 generateLedConfig(&ledConfigDefault, ledConfigDefaultBuffer, sizeof(ledConfigDefaultBuffer));
2306 cliDefaultPrintf(dumpMask, equalsDefault, format, i, ledConfigDefaultBuffer);
2308 cliDumpPrintf(dumpMask, equalsDefault, format, i, ledConfigBuffer);
2312 static void cliLed(char *cmdline)
2314 int i;
2315 const char *ptr;
2317 if (isEmpty(cmdline)) {
2318 printLed(DUMP_MASTER, ledStripConfig()->ledConfigs, NULL);
2319 } else {
2320 ptr = cmdline;
2321 i = atoi(ptr);
2322 if (i < LED_MAX_STRIP_LENGTH) {
2323 ptr = nextArg(cmdline);
2324 if (!parseLedStripConfig(i, ptr)) {
2325 cliShowParseError();
2327 } else {
2328 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH - 1);
2333 static void printColor(uint8_t dumpMask, const hsvColor_t *colors, const hsvColor_t *defaultColors)
2335 const char *format = "color %u %d,%u,%u\r\n";
2336 for (uint32_t i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
2337 const hsvColor_t *color = &colors[i];
2338 bool equalsDefault = false;
2339 if (defaultColors) {
2340 const hsvColor_t *colorDefault = &defaultColors[i];
2341 equalsDefault = color->h == colorDefault->h
2342 && color->s == colorDefault->s
2343 && color->v == colorDefault->v;
2344 cliDefaultPrintf(dumpMask, equalsDefault, format, i,colorDefault->h, colorDefault->s, colorDefault->v);
2346 cliDumpPrintf(dumpMask, equalsDefault, format, i, color->h, color->s, color->v);
2350 static void cliColor(char *cmdline)
2352 if (isEmpty(cmdline)) {
2353 printColor(DUMP_MASTER, ledStripConfig()->colors, NULL);
2354 } else {
2355 const char *ptr = cmdline;
2356 const int i = atoi(ptr);
2357 if (i < LED_CONFIGURABLE_COLOR_COUNT) {
2358 ptr = nextArg(cmdline);
2359 if (!parseColor(i, ptr)) {
2360 cliShowParseError();
2362 } else {
2363 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT - 1);
2368 static void printModeColor(uint8_t dumpMask, const ledStripConfig_t *ledStripConfig, const ledStripConfig_t *defaultLedStripConfig)
2370 const char *format = "mode_color %u %u %u\r\n";
2371 for (uint32_t i = 0; i < LED_MODE_COUNT; i++) {
2372 for (uint32_t j = 0; j < LED_DIRECTION_COUNT; j++) {
2373 int colorIndex = ledStripConfig->modeColors[i].color[j];
2374 bool equalsDefault = false;
2375 if (defaultLedStripConfig) {
2376 int colorIndexDefault = defaultLedStripConfig->modeColors[i].color[j];
2377 equalsDefault = colorIndex == colorIndexDefault;
2378 cliDefaultPrintf(dumpMask, equalsDefault, format, i, j, colorIndexDefault);
2380 cliDumpPrintf(dumpMask, equalsDefault, format, i, j, colorIndex);
2384 for (uint32_t j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
2385 const int colorIndex = ledStripConfig->specialColors.color[j];
2386 bool equalsDefault = false;
2387 if (defaultLedStripConfig) {
2388 const int colorIndexDefault = defaultLedStripConfig->specialColors.color[j];
2389 equalsDefault = colorIndex == colorIndexDefault;
2390 cliDefaultPrintf(dumpMask, equalsDefault, format, LED_SPECIAL, j, colorIndexDefault);
2392 cliDumpPrintf(dumpMask, equalsDefault, format, LED_SPECIAL, j, colorIndex);
2395 const int ledStripAuxChannel = ledStripConfig->ledstrip_aux_channel;
2396 bool equalsDefault = false;
2397 if (defaultLedStripConfig) {
2398 const int ledStripAuxChannelDefault = defaultLedStripConfig->ledstrip_aux_channel;
2399 equalsDefault = ledStripAuxChannel == ledStripAuxChannelDefault;
2400 cliDefaultPrintf(dumpMask, equalsDefault, format, LED_AUX_CHANNEL, 0, ledStripAuxChannelDefault);
2402 cliDumpPrintf(dumpMask, equalsDefault, format, LED_AUX_CHANNEL, 0, ledStripAuxChannel);
2405 static void cliModeColor(char *cmdline)
2407 if (isEmpty(cmdline)) {
2408 printModeColor(DUMP_MASTER, ledStripConfig(), NULL);
2409 } else {
2410 enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
2411 int args[ARGS_COUNT];
2412 int argNo = 0;
2413 char *saveptr;
2414 const char* ptr = strtok_r(cmdline, " ", &saveptr);
2415 while (ptr && argNo < ARGS_COUNT) {
2416 args[argNo++] = atoi(ptr);
2417 ptr = strtok_r(NULL, " ", &saveptr);
2420 if (ptr != NULL || argNo != ARGS_COUNT) {
2421 cliShowParseError();
2422 return;
2425 int modeIdx = args[MODE];
2426 int funIdx = args[FUNCTION];
2427 int color = args[COLOR];
2428 if(!setModeColor(modeIdx, funIdx, color)) {
2429 cliShowParseError();
2430 return;
2432 // values are validated
2433 cliPrintf("mode_color %u %u %u\r\n", modeIdx, funIdx, color);
2436 #endif
2438 #ifdef USE_SERVOS
2439 static void printServo(uint8_t dumpMask, const servoParam_t *servoParams, const servoParam_t *defaultServoParams)
2441 // print out servo settings
2442 const char *format = "servo %u %d %d %d %d %d %d %d\r\n";
2443 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2444 const servoParam_t *servoConf = &servoParams[i];
2445 bool equalsDefault = false;
2446 if (defaultServoParams) {
2447 const servoParam_t *defaultServoConf = &defaultServoParams[i];
2448 equalsDefault = servoConf->min == defaultServoConf->min
2449 && servoConf->max == defaultServoConf->max
2450 && servoConf->middle == defaultServoConf->middle
2451 && servoConf->angleAtMin == defaultServoConf->angleAtMax
2452 && servoConf->rate == defaultServoConf->rate
2453 && servoConf->forwardFromChannel == defaultServoConf->forwardFromChannel;
2454 cliDefaultPrintf(dumpMask, equalsDefault, format,
2456 defaultServoConf->min,
2457 defaultServoConf->max,
2458 defaultServoConf->middle,
2459 defaultServoConf->angleAtMin,
2460 defaultServoConf->angleAtMax,
2461 defaultServoConf->rate,
2462 defaultServoConf->forwardFromChannel
2465 cliDumpPrintf(dumpMask, equalsDefault, format,
2467 servoConf->min,
2468 servoConf->max,
2469 servoConf->middle,
2470 servoConf->angleAtMin,
2471 servoConf->angleAtMax,
2472 servoConf->rate,
2473 servoConf->forwardFromChannel
2476 // print servo directions
2477 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2478 const char *format = "smix reverse %d %d r\r\n";
2479 const servoParam_t *servoConf = &servoParams[i];
2480 const servoParam_t *servoConfDefault = &defaultServoParams[i];
2481 if (defaultServoParams) {
2482 bool equalsDefault = servoConf->reversedSources == servoConfDefault->reversedSources;
2483 for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2484 equalsDefault = ~(servoConf->reversedSources ^ servoConfDefault->reversedSources) & (1 << channel);
2485 if (servoConfDefault->reversedSources & (1 << channel)) {
2486 cliDefaultPrintf(dumpMask, equalsDefault, format, i , channel);
2488 if (servoConf->reversedSources & (1 << channel)) {
2489 cliDumpPrintf(dumpMask, equalsDefault, format, i , channel);
2492 } else {
2493 for (uint32_t channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2494 if (servoConf->reversedSources & (1 << channel)) {
2495 cliDumpPrintf(dumpMask, true, format, i , channel);
2502 static void cliServo(char *cmdline)
2504 enum { SERVO_ARGUMENT_COUNT = 8 };
2505 int16_t arguments[SERVO_ARGUMENT_COUNT];
2507 servoParam_t *servo;
2509 int i;
2510 char *ptr;
2512 if (isEmpty(cmdline)) {
2513 printServo(DUMP_MASTER, servoParams(0), NULL);
2514 } else {
2515 int validArgumentCount = 0;
2517 ptr = cmdline;
2519 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
2521 // If command line doesn't fit the format, don't modify the config
2522 while (*ptr) {
2523 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
2524 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
2525 cliShowParseError();
2526 return;
2529 arguments[validArgumentCount++] = atoi(ptr);
2531 do {
2532 ptr++;
2533 } while (*ptr >= '0' && *ptr <= '9');
2534 } else if (*ptr == ' ') {
2535 ptr++;
2536 } else {
2537 cliShowParseError();
2538 return;
2542 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
2544 i = arguments[INDEX];
2546 // Check we got the right number of args and the servo index is correct (don't validate the other values)
2547 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
2548 cliShowParseError();
2549 return;
2552 servo = servoParamsMutable(i);
2554 if (
2555 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
2556 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
2557 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
2558 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
2559 arguments[RATE] < -100 || arguments[RATE] > 100 ||
2560 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
2561 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
2562 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
2564 cliShowParseError();
2565 return;
2568 servo->min = arguments[1];
2569 servo->max = arguments[2];
2570 servo->middle = arguments[3];
2571 servo->angleAtMin = arguments[4];
2572 servo->angleAtMax = arguments[5];
2573 servo->rate = arguments[6];
2574 servo->forwardFromChannel = arguments[7];
2577 #endif
2579 #ifdef USE_SERVOS
2580 static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixers, const servoMixer_t *defaultCustomServoMixers)
2582 const char *format = "smix %d %d %d %d %d %d %d %d\r\n";
2583 for (uint32_t i = 0; i < MAX_SERVO_RULES; i++) {
2584 const servoMixer_t customServoMixer = customServoMixers[i];
2585 if (customServoMixer.rate == 0) {
2586 break;
2589 bool equalsDefault = false;
2590 if (defaultCustomServoMixers) {
2591 servoMixer_t customServoMixerDefault = defaultCustomServoMixers[i];
2592 equalsDefault = customServoMixer.targetChannel == customServoMixerDefault.targetChannel
2593 && customServoMixer.inputSource == customServoMixerDefault.inputSource
2594 && customServoMixer.rate == customServoMixerDefault.rate
2595 && customServoMixer.speed == customServoMixerDefault.speed
2596 && customServoMixer.min == customServoMixerDefault.min
2597 && customServoMixer.max == customServoMixerDefault.max
2598 && customServoMixer.box == customServoMixerDefault.box;
2600 cliDefaultPrintf(dumpMask, equalsDefault, format,
2602 customServoMixerDefault.targetChannel,
2603 customServoMixerDefault.inputSource,
2604 customServoMixerDefault.rate,
2605 customServoMixerDefault.speed,
2606 customServoMixerDefault.min,
2607 customServoMixerDefault.max,
2608 customServoMixerDefault.box
2611 cliDumpPrintf(dumpMask, equalsDefault, format,
2613 customServoMixer.targetChannel,
2614 customServoMixer.inputSource,
2615 customServoMixer.rate,
2616 customServoMixer.speed,
2617 customServoMixer.min,
2618 customServoMixer.max,
2619 customServoMixer.box
2623 cliPrint("\r\n");
2626 static void cliServoMix(char *cmdline)
2628 int args[8], check = 0;
2629 int len = strlen(cmdline);
2631 if (len == 0) {
2632 printServoMix(DUMP_MASTER, customServoMixers(0), NULL);
2633 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
2634 // erase custom mixer
2635 #ifdef USE_PARAMETER_GROUPS
2636 memset(customServoMixers_array(), 0, sizeof(*customServoMixers_array()));
2637 #else
2638 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
2639 #endif
2640 for (uint32_t i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2641 servoParamsMutable(i)->reversedSources = 0;
2643 } else if (strncasecmp(cmdline, "load", 4) == 0) {
2644 const char *ptr = nextArg(cmdline);
2645 if (ptr) {
2646 len = strlen(ptr);
2647 for (uint32_t i = 0; ; i++) {
2648 if (mixerNames[i] == NULL) {
2649 cliPrintf("Invalid name\r\n");
2650 break;
2652 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
2653 servoMixerLoadMix(i);
2654 cliPrintf("Loaded %s\r\n", mixerNames[i]);
2655 cliServoMix("");
2656 break;
2660 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
2661 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
2662 char *ptr = strchr(cmdline, ' ');
2664 len = strlen(ptr);
2665 if (len == 0) {
2666 cliPrintf("s");
2667 for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
2668 cliPrintf("\ti%d", inputSource);
2669 cliPrintf("\r\n");
2671 for (uint32_t servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
2672 cliPrintf("%d", servoIndex);
2673 for (uint32_t inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
2674 cliPrintf("\t%s ", (servoParams(servoIndex)->reversedSources & (1 << inputSource)) ? "r" : "n");
2675 cliPrintf("\r\n");
2677 return;
2680 char *saveptr;
2681 ptr = strtok_r(ptr, " ", &saveptr);
2682 while (ptr != NULL && check < ARGS_COUNT - 1) {
2683 args[check++] = atoi(ptr);
2684 ptr = strtok_r(NULL, " ", &saveptr);
2687 if (ptr == NULL || check != ARGS_COUNT - 1) {
2688 cliShowParseError();
2689 return;
2692 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
2693 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
2694 && (*ptr == 'r' || *ptr == 'n')) {
2695 if (*ptr == 'r')
2696 servoParamsMutable(args[SERVO])->reversedSources |= 1 << args[INPUT];
2697 else
2698 servoParamsMutable(args[SERVO])->reversedSources &= ~(1 << args[INPUT]);
2699 } else
2700 cliShowParseError();
2702 cliServoMix("reverse");
2703 } else {
2704 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
2705 char *saveptr;
2706 char *ptr = strtok_r(cmdline, " ", &saveptr);
2707 while (ptr != NULL && check < ARGS_COUNT) {
2708 args[check++] = atoi(ptr);
2709 ptr = strtok_r(NULL, " ", &saveptr);
2712 if (ptr != NULL || check != ARGS_COUNT) {
2713 cliShowParseError();
2714 return;
2717 int32_t i = args[RULE];
2718 if (i >= 0 && i < MAX_SERVO_RULES &&
2719 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
2720 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
2721 args[RATE] >= -100 && args[RATE] <= 100 &&
2722 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
2723 args[MIN] >= 0 && args[MIN] <= 100 &&
2724 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
2725 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
2726 customServoMixersMutable(i)->targetChannel = args[TARGET];
2727 customServoMixersMutable(i)->inputSource = args[INPUT];
2728 customServoMixersMutable(i)->rate = args[RATE];
2729 customServoMixersMutable(i)->speed = args[SPEED];
2730 customServoMixersMutable(i)->min = args[MIN];
2731 customServoMixersMutable(i)->max = args[MAX];
2732 customServoMixersMutable(i)->box = args[BOX];
2733 cliServoMix("");
2734 } else {
2735 cliShowParseError();
2739 #endif
2741 #ifdef USE_SDCARD
2743 static void cliWriteBytes(const uint8_t *buffer, int count)
2745 while (count > 0) {
2746 cliWrite(*buffer);
2747 buffer++;
2748 count--;
2752 static void cliSdInfo(char *cmdline)
2754 UNUSED(cmdline);
2756 cliPrint("SD card: ");
2758 if (!sdcard_isInserted()) {
2759 cliPrint("None inserted\r\n");
2760 return;
2763 if (!sdcard_isInitialized()) {
2764 cliPrint("Startup failed\r\n");
2765 return;
2768 const sdcardMetadata_t *metadata = sdcard_getMetadata();
2770 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
2771 metadata->manufacturerID,
2772 metadata->numBlocks / 2, /* One block is half a kB */
2773 metadata->productionMonth,
2774 metadata->productionYear,
2775 metadata->productRevisionMajor,
2776 metadata->productRevisionMinor
2779 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
2781 cliPrint("'\r\n" "Filesystem: ");
2783 switch (afatfs_getFilesystemState()) {
2784 case AFATFS_FILESYSTEM_STATE_READY:
2785 cliPrint("Ready");
2786 break;
2787 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
2788 cliPrint("Initializing");
2789 break;
2790 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
2791 case AFATFS_FILESYSTEM_STATE_FATAL:
2792 cliPrint("Fatal");
2794 switch (afatfs_getLastError()) {
2795 case AFATFS_ERROR_BAD_MBR:
2796 cliPrint(" - no FAT MBR partitions");
2797 break;
2798 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
2799 cliPrint(" - bad FAT header");
2800 break;
2801 case AFATFS_ERROR_GENERIC:
2802 case AFATFS_ERROR_NONE:
2803 ; // Nothing more detailed to print
2804 break;
2806 break;
2808 cliPrint("\r\n");
2811 #endif
2813 #ifdef USE_FLASHFS
2815 static void cliFlashInfo(char *cmdline)
2817 const flashGeometry_t *layout = flashfsGetGeometry();
2819 UNUSED(cmdline);
2821 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
2822 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
2826 static void cliFlashErase(char *cmdline)
2828 UNUSED(cmdline);
2830 #ifndef MINIMAL_CLI
2831 uint32_t i = 0;
2832 cliPrintf("Erasing, please wait ... \r\n");
2833 #else
2834 cliPrintf("Erasing,\r\n");
2835 #endif
2837 bufWriterFlush(cliWriter);
2838 flashfsEraseCompletely();
2840 while (!flashfsIsReady()) {
2841 #ifndef MINIMAL_CLI
2842 cliPrintf(".");
2843 if (i++ > 120) {
2844 i=0;
2845 cliPrintf("\r\n");
2848 bufWriterFlush(cliWriter);
2849 #endif
2850 delay(100);
2852 beeper(BEEPER_BLACKBOX_ERASE);
2853 cliPrintf("\r\nDone.\r\n");
2856 #ifdef USE_FLASH_TOOLS
2858 static void cliFlashWrite(char *cmdline)
2860 const uint32_t address = atoi(cmdline);
2861 const char *text = strchr(cmdline, ' ');
2863 if (!text) {
2864 cliShowParseError();
2865 } else {
2866 flashfsSeekAbs(address);
2867 flashfsWrite((uint8_t*)text, strlen(text), true);
2868 flashfsFlushSync();
2870 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
2874 static void cliFlashRead(char *cmdline)
2876 uint32_t address = atoi(cmdline);
2878 const char *nextArg = strchr(cmdline, ' ');
2880 if (!nextArg) {
2881 cliShowParseError();
2882 } else {
2883 uint32_t length = atoi(nextArg);
2885 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
2887 uint8_t buffer[32];
2888 while (length > 0) {
2889 int bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
2891 for (int i = 0; i < bytesRead; i++) {
2892 cliWrite(buffer[i]);
2895 length -= bytesRead;
2896 address += bytesRead;
2898 if (bytesRead == 0) {
2899 //Assume we reached the end of the volume or something fatal happened
2900 break;
2903 cliPrintf("\r\n");
2907 #endif
2908 #endif
2910 #if defined(USE_RTC6705) || defined(VTX)
2911 static void printVtx(uint8_t dumpMask, const vtxConfig_t *vtxConfig, const vtxConfig_t *vtxConfigDefault)
2913 // print out vtx channel settings
2914 const char *format = "vtx %u %u %u %u %u %u\r\n";
2915 bool equalsDefault = false;
2916 for (uint32_t i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
2917 const vtxChannelActivationCondition_t *cac = &vtxConfig->vtxChannelActivationConditions[i];
2918 if (vtxConfigDefault) {
2919 const vtxChannelActivationCondition_t *cacDefault = &vtxConfigDefault->vtxChannelActivationConditions[i];
2920 equalsDefault = cac->auxChannelIndex == cacDefault->auxChannelIndex
2921 && cac->band == cacDefault->band
2922 && cac->channel == cacDefault->channel
2923 && cac->range.startStep == cacDefault->range.startStep
2924 && cac->range.endStep == cacDefault->range.endStep;
2925 cliDefaultPrintf(dumpMask, equalsDefault, format,
2927 cacDefault->auxChannelIndex,
2928 cacDefault->band,
2929 cacDefault->channel,
2930 MODE_STEP_TO_CHANNEL_VALUE(cacDefault->range.startStep),
2931 MODE_STEP_TO_CHANNEL_VALUE(cacDefault->range.endStep)
2934 cliDumpPrintf(dumpMask, equalsDefault, format,
2936 cac->auxChannelIndex,
2937 cac->band,
2938 cac->channel,
2939 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
2940 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
2945 #ifdef VTX
2946 static void cliVtx(char *cmdline)
2948 int i, val = 0;
2949 const char *ptr;
2951 if (isEmpty(cmdline)) {
2952 printVtx(DUMP_MASTER, vtxConfig(), NULL);
2953 } else {
2954 ptr = cmdline;
2955 i = atoi(ptr++);
2956 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
2957 vtxChannelActivationCondition_t *cac = &vtxConfigMutable()->vtxChannelActivationConditions[i];
2958 uint8_t validArgumentCount = 0;
2959 ptr = nextArg(ptr);
2960 if (ptr) {
2961 val = atoi(ptr);
2962 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
2963 cac->auxChannelIndex = val;
2964 validArgumentCount++;
2967 ptr = nextArg(ptr);
2968 if (ptr) {
2969 val = atoi(ptr);
2970 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
2971 cac->band = val;
2972 validArgumentCount++;
2975 ptr = nextArg(ptr);
2976 if (ptr) {
2977 val = atoi(ptr);
2978 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
2979 cac->channel = val;
2980 validArgumentCount++;
2983 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
2985 if (validArgumentCount != 5) {
2986 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
2988 } else {
2989 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
2993 #endif // VTX
2994 #endif
2996 static void printName(uint8_t dumpMask, const systemConfig_t *systemConfig)
2998 const bool equalsDefault = strlen(systemConfig->name) == 0;
2999 cliDumpPrintf(dumpMask, equalsDefault, "name %s\r\n", equalsDefault ? emptyName : systemConfig->name);
3002 static void cliName(char *cmdline)
3004 const uint32_t len = strlen(cmdline);
3005 if (len > 0) {
3006 memset(systemConfigMutable()->name, 0, ARRAYLEN(systemConfig()->name));
3007 if (strncmp(cmdline, emptyName, len)) {
3008 strncpy(systemConfigMutable()->name, cmdline, MIN(len, MAX_NAME_LENGTH));
3011 printName(DUMP_MASTER, systemConfig());
3014 static void printFeature(uint8_t dumpMask, const featureConfig_t *featureConfig, const featureConfig_t *featureConfigDefault)
3016 const uint32_t mask = featureConfig->enabledFeatures;
3017 const uint32_t defaultMask = featureConfigDefault->enabledFeatures;
3018 for (uint32_t i = 0; featureNames[i]; i++) { // disable all feature first
3019 const char *format = "feature -%s\r\n";
3020 cliDefaultPrintf(dumpMask, (defaultMask | ~mask) & (1 << i), format, featureNames[i]);
3021 cliDumpPrintf(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
3023 for (uint32_t i = 0; featureNames[i]; i++) { // reenable what we want.
3024 const char *format = "feature %s\r\n";
3025 if (defaultMask & (1 << i)) {
3026 cliDefaultPrintf(dumpMask, (~defaultMask | mask) & (1 << i), format, featureNames[i]);
3028 if (mask & (1 << i)) {
3029 cliDumpPrintf(dumpMask, (defaultMask | ~mask) & (1 << i), format, featureNames[i]);
3034 static void cliFeature(char *cmdline)
3036 uint32_t len = strlen(cmdline);
3037 uint32_t mask = featureMask();
3039 if (len == 0) {
3040 cliPrint("Enabled: ");
3041 for (uint32_t i = 0; ; i++) {
3042 if (featureNames[i] == NULL)
3043 break;
3044 if (mask & (1 << i))
3045 cliPrintf("%s ", featureNames[i]);
3047 cliPrint("\r\n");
3048 } else if (strncasecmp(cmdline, "list", len) == 0) {
3049 cliPrint("Available: ");
3050 for (uint32_t i = 0; ; i++) {
3051 if (featureNames[i] == NULL)
3052 break;
3053 cliPrintf("%s ", featureNames[i]);
3055 cliPrint("\r\n");
3056 return;
3057 } else {
3058 bool remove = false;
3059 if (cmdline[0] == '-') {
3060 // remove feature
3061 remove = true;
3062 cmdline++; // skip over -
3063 len--;
3066 for (uint32_t i = 0; ; i++) {
3067 if (featureNames[i] == NULL) {
3068 cliPrint("Invalid name\r\n");
3069 break;
3072 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
3074 mask = 1 << i;
3075 #ifndef GPS
3076 if (mask & FEATURE_GPS) {
3077 cliPrint("unavailable\r\n");
3078 break;
3080 #endif
3081 #ifndef SONAR
3082 if (mask & FEATURE_SONAR) {
3083 cliPrint("unavailable\r\n");
3084 break;
3086 #endif
3087 if (remove) {
3088 featureClear(mask);
3089 cliPrint("Disabled");
3090 } else {
3091 featureSet(mask);
3092 cliPrint("Enabled");
3094 cliPrintf(" %s\r\n", featureNames[i]);
3095 break;
3101 #ifdef BEEPER
3102 static void printBeeper(uint8_t dumpMask, const beeperConfig_t *beeperConfig, const beeperConfig_t *beeperConfigDefault)
3104 const uint8_t beeperCount = beeperTableEntryCount();
3105 const uint32_t mask = beeperConfig->beeper_off_flags;
3106 const uint32_t defaultMask = beeperConfigDefault->beeper_off_flags;
3107 for (int32_t i = 0; i < beeperCount - 2; i++) {
3108 const char *formatOff = "beeper -%s\r\n";
3109 const char *formatOn = "beeper %s\r\n";
3110 cliDefaultPrintf(dumpMask, ~(mask ^ defaultMask) & (1 << i), mask & (1 << i) ? formatOn : formatOff, beeperNameForTableIndex(i));
3111 cliDumpPrintf(dumpMask, ~(mask ^ defaultMask) & (1 << i), mask & (1 << i) ? formatOff : formatOn, beeperNameForTableIndex(i));
3115 static void cliBeeper(char *cmdline)
3117 uint32_t len = strlen(cmdline);
3118 uint8_t beeperCount = beeperTableEntryCount();
3119 uint32_t mask = getBeeperOffMask();
3121 if (len == 0) {
3122 cliPrintf("Disabled:");
3123 for (int32_t i = 0; ; i++) {
3124 if (i == beeperCount - 2){
3125 if (mask == 0)
3126 cliPrint(" none");
3127 break;
3129 if (mask & (1 << i))
3130 cliPrintf(" %s", beeperNameForTableIndex(i));
3132 cliPrint("\r\n");
3133 } else if (strncasecmp(cmdline, "list", len) == 0) {
3134 cliPrint("Available:");
3135 for (uint32_t i = 0; i < beeperCount; i++)
3136 cliPrintf(" %s", beeperNameForTableIndex(i));
3137 cliPrint("\r\n");
3138 return;
3139 } else {
3140 bool remove = false;
3141 if (cmdline[0] == '-') {
3142 remove = true; // this is for beeper OFF condition
3143 cmdline++;
3144 len--;
3147 for (uint32_t i = 0; ; i++) {
3148 if (i == beeperCount) {
3149 cliPrint("Invalid name\r\n");
3150 break;
3152 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
3153 if (remove) { // beeper off
3154 if (i == BEEPER_ALL-1)
3155 beeperOffSetAll(beeperCount-2);
3156 else
3157 if (i == BEEPER_PREFERENCE-1)
3158 setBeeperOffMask(getPreferredBeeperOffMask());
3159 else {
3160 mask = 1 << i;
3161 beeperOffSet(mask);
3163 cliPrint("Disabled");
3165 else { // beeper on
3166 if (i == BEEPER_ALL-1)
3167 beeperOffClearAll();
3168 else
3169 if (i == BEEPER_PREFERENCE-1)
3170 setPreferredBeeperOffMask(getBeeperOffMask());
3171 else {
3172 mask = 1 << i;
3173 beeperOffClear(mask);
3175 cliPrint("Enabled");
3177 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
3178 break;
3183 #endif
3185 static void printMap(uint8_t dumpMask, const rxConfig_t *rxConfig, const rxConfig_t *defaultRxConfig)
3187 bool equalsDefault = true;
3188 char buf[16];
3189 char bufDefault[16];
3190 uint32_t i;
3191 for (i = 0; i < MAX_MAPPABLE_RX_INPUTS; i++) {
3192 buf[rxConfig->rcmap[i]] = rcChannelLetters[i];
3193 if (defaultRxConfig) {
3194 bufDefault[defaultRxConfig->rcmap[i]] = rcChannelLetters[i];
3195 equalsDefault = equalsDefault && (rxConfig->rcmap[i] == defaultRxConfig->rcmap[i]);
3198 buf[i] = '\0';
3200 const char *formatMap = "map %s\r\n";
3201 cliDefaultPrintf(dumpMask, equalsDefault, formatMap, bufDefault);
3202 cliDumpPrintf(dumpMask, equalsDefault, formatMap, buf);
3205 static void cliMap(char *cmdline)
3207 uint32_t len;
3208 char out[9];
3210 len = strlen(cmdline);
3212 if (len == 8) {
3213 // uppercase it
3214 for (uint32_t i = 0; i < 8; i++)
3215 cmdline[i] = toupper((unsigned char)cmdline[i]);
3216 for (uint32_t i = 0; i < 8; i++) {
3217 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
3218 continue;
3219 cliShowParseError();
3220 return;
3222 parseRcChannels(cmdline, rxConfigMutable());
3224 cliPrint("Map: ");
3225 uint32_t i;
3226 for (i = 0; i < 8; i++)
3227 out[rxConfig()->rcmap[i]] = rcChannelLetters[i];
3228 out[i] = '\0';
3229 cliPrintf("%s\r\n", out);
3232 static char *checkCommand(char *cmdLine, const char *command)
3234 if(!strncasecmp(cmdLine, command, strlen(command)) // command names match
3235 && (isspace((unsigned)cmdLine[strlen(command)]) || cmdLine[strlen(command)] == 0)) {
3236 return cmdLine + strlen(command) + 1;
3237 } else {
3238 return 0;
3242 static void cliRebootEx(bool bootLoader)
3244 cliPrint("\r\nRebooting");
3245 bufWriterFlush(cliWriter);
3246 waitForSerialPortToFinishTransmitting(cliPort);
3247 stopPwmAllMotors();
3248 if (bootLoader) {
3249 systemResetToBootloader();
3250 return;
3252 systemReset();
3255 static void cliReboot(void)
3257 cliRebootEx(false);
3260 static void cliBootloader(char *cmdLine)
3262 UNUSED(cmdLine);
3264 cliPrintHashLine("restarting in bootloader mode");
3265 cliRebootEx(true);
3268 static void cliExit(char *cmdline)
3270 UNUSED(cmdline);
3272 cliPrintHashLine("leaving CLI mode, unsaved changes lost");
3273 bufWriterFlush(cliWriter);
3275 *cliBuffer = '\0';
3276 bufferIndex = 0;
3277 cliMode = 0;
3278 // incase a motor was left running during motortest, clear it here
3279 mixerResetDisarmedMotors();
3280 cliReboot();
3282 cliWriter = NULL;
3285 #ifdef GPS
3286 static void cliGpsPassthrough(char *cmdline)
3288 UNUSED(cmdline);
3290 gpsEnablePassthrough(cliPort);
3292 #endif
3294 #if defined(USE_ESCSERIAL) || defined(USE_DSHOT)
3296 #ifndef ALL_ESCS
3297 #define ALL_ESCS 255
3298 #endif
3300 static int parseEscNumber(char *pch, bool allowAllEscs) {
3301 int escNumber = atoi(pch);
3302 if ((escNumber >= 0) && (escNumber < getMotorCount())) {
3303 printf("Programming on ESC %d.\r\n", escNumber);
3304 } else if (allowAllEscs && escNumber == ALL_ESCS) {
3305 printf("Programming on all ESCs.\r\n");
3306 } else {
3307 printf("Invalid ESC number, range: 0 to %d.\r\n", getMotorCount() - 1);
3309 return -1;
3312 return escNumber;
3314 #endif
3316 #ifdef USE_DSHOT
3317 static void cliDshotProg(char *cmdline)
3319 if (isEmpty(cmdline) || motorConfig()->dev.motorPwmProtocol < PWM_TYPE_DSHOT150) {
3320 cliShowParseError();
3322 return;
3325 char *saveptr;
3326 char *pch = strtok_r(cmdline, " ", &saveptr);
3327 int pos = 0;
3328 int escNumber = 0;
3329 while (pch != NULL) {
3330 switch (pos) {
3331 case 0:
3332 escNumber = parseEscNumber(pch, true);
3333 if (escNumber == -1) {
3334 return;
3337 break;
3338 default:
3339 motorControlEnable = false;
3341 int command = atoi(pch);
3342 if (command >= 0 && command < DSHOT_MIN_THROTTLE) {
3343 if (escNumber == ALL_ESCS) {
3344 for (unsigned i = 0; i < getMotorCount(); i++) {
3345 pwmWriteDshotCommand(i, command);
3347 } else {
3348 pwmWriteDshotCommand(escNumber, command);
3351 if (command <= 5) {
3352 delay(10); // wait for sound output to finish
3355 printf("Command %d written.\r\n", command);
3356 } else {
3357 printf("Invalid command, range 1 to %d.\r\n", DSHOT_MIN_THROTTLE - 1);
3360 break;
3363 pos++;
3364 pch = strtok_r(NULL, " ", &saveptr);
3367 motorControlEnable = true;
3369 #endif
3371 #ifdef USE_ESCSERIAL
3372 static void cliEscPassthrough(char *cmdline)
3374 if (isEmpty(cmdline)) {
3375 cliShowParseError();
3377 return;
3380 char *saveptr;
3381 char *pch = strtok_r(cmdline, " ", &saveptr);
3382 int pos = 0;
3383 uint8_t mode = 0;
3384 int escNumber = 0;
3385 while (pch != NULL) {
3386 switch (pos) {
3387 case 0:
3388 if(strncasecmp(pch, "sk", strlen(pch)) == 0) {
3389 mode = PROTOCOL_SIMONK;
3390 } else if(strncasecmp(pch, "bl", strlen(pch)) == 0) {
3391 mode = PROTOCOL_BLHELI;
3392 } else if(strncasecmp(pch, "ki", strlen(pch)) == 0) {
3393 mode = PROTOCOL_KISS;
3394 } else if(strncasecmp(pch, "cc", strlen(pch)) == 0) {
3395 mode = PROTOCOL_KISSALL;
3396 } else {
3397 cliShowParseError();
3399 return;
3401 break;
3402 case 1:
3403 escNumber = parseEscNumber(pch, mode == PROTOCOL_KISS);
3404 if (escNumber == -1) {
3405 return;
3408 break;
3409 default:
3410 cliShowParseError();
3412 return;
3414 break;
3417 pos++;
3418 pch = strtok_r(NULL, " ", &saveptr);
3421 escEnablePassthrough(cliPort, escNumber, mode);
3423 #endif
3425 #ifndef USE_QUAD_MIXER_ONLY
3426 static void cliMixer(char *cmdline)
3428 int len;
3430 len = strlen(cmdline);
3432 if (len == 0) {
3433 cliPrintf("Mixer: %s\r\n", mixerNames[mixerConfig()->mixerMode - 1]);
3434 return;
3435 } else if (strncasecmp(cmdline, "list", len) == 0) {
3436 cliPrint("Available mixers: ");
3437 for (uint32_t i = 0; ; i++) {
3438 if (mixerNames[i] == NULL)
3439 break;
3440 cliPrintf("%s ", mixerNames[i]);
3442 cliPrint("\r\n");
3443 return;
3446 for (uint32_t i = 0; ; i++) {
3447 if (mixerNames[i] == NULL) {
3448 cliPrint("Invalid name\r\n");
3449 return;
3451 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
3452 mixerConfigMutable()->mixerMode = i + 1;
3453 break;
3457 cliMixer("");
3459 #endif
3461 static void cliMotor(char *cmdline)
3463 int motor_index = 0;
3464 int motor_value = 0;
3465 int index = 0;
3466 char *pch = NULL;
3467 char *saveptr;
3469 if (isEmpty(cmdline)) {
3470 cliShowParseError();
3471 return;
3474 pch = strtok_r(cmdline, " ", &saveptr);
3475 while (pch != NULL) {
3476 switch (index) {
3477 case 0:
3478 motor_index = atoi(pch);
3479 break;
3480 case 1:
3481 motor_value = atoi(pch);
3482 break;
3484 index++;
3485 pch = strtok_r(NULL, " ", &saveptr);
3488 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
3489 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
3490 return;
3493 if (index == 2) {
3494 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
3495 cliShowArgumentRangeError("value", 1000, 2000);
3496 } else {
3497 motor_disarmed[motor_index] = convertExternalToMotor(motor_value);
3499 cliPrintf("motor %d: %d\r\n", motor_index, convertMotorToExternal(motor_disarmed[motor_index]));
3505 #ifndef MINIMAL_CLI
3506 static void cliPlaySound(char *cmdline)
3508 int i;
3509 const char *name;
3510 static int lastSoundIdx = -1;
3512 if (isEmpty(cmdline)) {
3513 i = lastSoundIdx + 1; //next sound index
3514 if ((name=beeperNameForTableIndex(i)) == NULL) {
3515 while (true) { //no name for index; try next one
3516 if (++i >= beeperTableEntryCount())
3517 i = 0; //if end then wrap around to first entry
3518 if ((name=beeperNameForTableIndex(i)) != NULL)
3519 break; //if name OK then play sound below
3520 if (i == lastSoundIdx + 1) { //prevent infinite loop
3521 cliPrintf("Error playing sound\r\n");
3522 return;
3526 } else { //index value was given
3527 i = atoi(cmdline);
3528 if ((name=beeperNameForTableIndex(i)) == NULL) {
3529 cliPrintf("No sound for index %d\r\n", i);
3530 return;
3533 lastSoundIdx = i;
3534 beeperSilence();
3535 cliPrintf("Playing sound %d: %s\r\n", i, name);
3536 beeper(beeperModeForTableIndex(i));
3538 #endif
3540 static void cliProfile(char *cmdline)
3542 if (isEmpty(cmdline)) {
3543 cliPrintf("profile %d\r\n", getCurrentPidProfileIndex());
3544 return;
3545 } else {
3546 const int i = atoi(cmdline);
3547 if (i >= 0 && i < MAX_PROFILE_COUNT) {
3548 systemConfigMutable()->pidProfileIndex = i;
3549 cliProfile("");
3554 static void cliRateProfile(char *cmdline)
3556 if (isEmpty(cmdline)) {
3557 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfileIndex());
3558 return;
3559 } else {
3560 const int i = atoi(cmdline);
3561 if (i >= 0 && i < CONTROL_RATE_PROFILE_COUNT) {
3562 changeControlRateProfile(i);
3563 cliRateProfile("");
3568 #ifdef USE_PARAMETER_GROUPS
3569 static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask)
3571 if (pidProfileIndex >= MAX_PROFILE_COUNT) {
3572 // Faulty values
3573 return;
3575 changePidProfile(pidProfileIndex);
3576 cliPrintHashLine("profile");
3577 cliProfile("");
3578 cliPrint("\r\n");
3579 dumpAllValues(PROFILE_VALUE, dumpMask);
3582 static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask)
3584 if (rateProfileIndex >= CONTROL_RATE_PROFILE_COUNT) {
3585 // Faulty values
3586 return;
3588 changeControlRateProfile(rateProfileIndex);
3589 cliPrintHashLine("rateprofile");
3590 cliRateProfile("");
3591 cliPrint("\r\n");
3592 dumpAllValues(PROFILE_RATE_VALUE, dumpMask);
3594 #else
3595 static void cliDumpPidProfile(uint8_t pidProfileIndex, uint8_t dumpMask, const master_t *defaultConfig)
3597 if (pidProfileIndex >= MAX_PROFILE_COUNT) {
3598 // Faulty values
3599 return;
3601 changePidProfile(pidProfileIndex);
3602 cliPrintHashLine("profile");
3603 cliProfile("");
3604 cliPrint("\r\n");
3605 dumpValues(PROFILE_VALUE, dumpMask, defaultConfig);
3608 static void cliDumpRateProfile(uint8_t rateProfileIndex, uint8_t dumpMask, const master_t *defaultConfig)
3610 if (rateProfileIndex >= CONTROL_RATE_PROFILE_COUNT) {
3611 // Faulty values
3612 return;
3614 changeControlRateProfile(rateProfileIndex);
3615 cliPrintHashLine("rateprofile");
3616 cliRateProfile("");
3617 cliPrint("\r\n");
3618 dumpValues(PROFILE_RATE_VALUE, dumpMask, defaultConfig);
3620 #endif
3622 static void cliSave(char *cmdline)
3624 UNUSED(cmdline);
3626 cliPrintHashLine("saving");
3627 writeEEPROM();
3628 cliReboot();
3631 static void cliDefaults(char *cmdline)
3633 UNUSED(cmdline);
3635 cliPrintHashLine("resetting to defaults");
3636 resetEEPROM();
3637 cliReboot();
3640 static void cliGet(char *cmdline)
3642 const clivalue_t *val;
3643 int matchedCommands = 0;
3645 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3646 if (strstr(valueTable[i].name, cmdline)) {
3647 val = &valueTable[i];
3648 cliPrintf("%s = ", valueTable[i].name);
3649 cliPrintVar(val, 0);
3650 cliPrint("\r\n");
3651 cliPrintVarRange(val);
3652 cliPrint("\r\n");
3654 matchedCommands++;
3659 if (matchedCommands) {
3660 return;
3663 cliPrint("Invalid name\r\n");
3666 static void cliSet(char *cmdline)
3668 uint32_t len;
3669 const clivalue_t *val;
3670 char *eqptr = NULL;
3672 len = strlen(cmdline);
3674 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
3675 cliPrint("Current settings: \r\n");
3676 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3677 val = &valueTable[i];
3678 cliPrintf("%s = ", valueTable[i].name);
3679 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
3680 cliPrint("\r\n");
3682 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
3683 // has equals
3685 char *lastNonSpaceCharacter = eqptr;
3686 while (*(lastNonSpaceCharacter - 1) == ' ') {
3687 lastNonSpaceCharacter--;
3689 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
3691 // skip the '=' and any ' ' characters
3692 eqptr++;
3693 while (*(eqptr) == ' ') {
3694 eqptr++;
3697 for (uint32_t i = 0; i < ARRAYLEN(valueTable); i++) {
3698 val = &valueTable[i];
3699 // ensure exact match when setting to prevent setting variables with shorter names
3700 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
3702 bool changeValue = false;
3703 int_float_value_t tmp = { 0 };
3704 switch (valueTable[i].type & VALUE_MODE_MASK) {
3705 case MODE_DIRECT: {
3706 int32_t value = 0;
3707 float valuef = 0;
3709 value = atoi(eqptr);
3710 valuef = fastA2F(eqptr);
3712 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
3714 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
3715 tmp.float_value = valuef;
3716 else
3717 tmp.int_value = value;
3719 changeValue = true;
3722 break;
3723 case MODE_LOOKUP: {
3724 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
3725 bool matched = false;
3726 for (uint32_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
3727 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
3729 if (matched) {
3730 tmp.int_value = tableValueIndex;
3731 changeValue = true;
3735 break;
3738 if (changeValue) {
3739 cliSetVar(val, tmp);
3741 cliPrintf("%s set to ", valueTable[i].name);
3742 cliPrintVar(val, 0);
3743 } else {
3744 cliPrint("Invalid value\r\n");
3745 cliPrintVarRange(val);
3748 return;
3751 cliPrint("Invalid name\r\n");
3752 } else {
3753 // no equals, check for matching variables.
3754 cliGet(cmdline);
3758 static void cliStatus(char *cmdline)
3760 UNUSED(cmdline);
3762 cliPrintf("System Uptime: %d seconds\r\n", millis() / 1000);
3763 cliPrintf("Voltage: %d * 0.1V (%dS battery - %s)\r\n", getBatteryVoltage(), getBatteryCellCount(), getBatteryStateString());
3765 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
3767 #if defined(USE_SENSOR_NAMES)
3768 const uint32_t detectedSensorsMask = sensorsMask();
3769 for (uint32_t i = 0; ; i++) {
3770 if (sensorTypeNames[i] == NULL) {
3771 break;
3773 const uint32_t mask = (1 << i);
3774 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
3775 const uint8_t sensorHardwareIndex = detectedSensors[i];
3776 const char *sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
3777 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
3778 if (mask == SENSOR_ACC && acc.dev.revisionCode) {
3779 cliPrintf(".%c", acc.dev.revisionCode);
3783 #endif /* USE_SENSOR_NAMES */
3784 cliPrint("\r\n");
3786 #ifdef USE_SDCARD
3787 cliSdInfo(NULL);
3788 #endif
3790 #ifdef USE_I2C
3791 const uint16_t i2cErrorCounter = i2cGetErrorCounter();
3792 #else
3793 const uint16_t i2cErrorCounter = 0;
3794 #endif
3796 #ifdef STACK_CHECK
3797 cliPrintf("Stack used: %d, ", stackUsedSize());
3798 #endif
3799 cliPrintf("Stack size: %d, Stack address: 0x%x\r\n", stackTotalSize(), stackHighMem());
3801 #ifdef USE_PARAMETER_GROUPS
3802 cliPrintf("I2C Errors: %d, config size: %d, max available config: %d\r\n", i2cErrorCounter, getEEPROMConfigSize(), &__config_end - &__config_start);
3803 #else
3804 cliPrintf("I2C Errors: %d, config size: %d\r\n", i2cErrorCounter, sizeof(master_t));
3805 #endif
3807 const int gyroRate = getTaskDeltaTime(TASK_GYROPID) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_GYROPID)));
3808 const int rxRate = getTaskDeltaTime(TASK_RX) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_RX)));
3809 const int systemRate = getTaskDeltaTime(TASK_SYSTEM) == 0 ? 0 : (int)(1000000.0f / ((float)getTaskDeltaTime(TASK_SYSTEM)));
3810 cliPrintf("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d\r\n",
3811 constrain(averageSystemLoadPercent, 0, 100), getTaskDeltaTime(TASK_GYROPID), gyroRate, rxRate, systemRate);
3815 #ifndef SKIP_TASK_STATISTICS
3816 static void cliTasks(char *cmdline)
3818 UNUSED(cmdline);
3819 int maxLoadSum = 0;
3820 int averageLoadSum = 0;
3822 #ifndef MINIMAL_CLI
3823 if (systemConfig()->task_statistics) {
3824 cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
3825 } else {
3826 cliPrintf("Task list\r\n");
3828 #endif
3829 for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; taskId++) {
3830 cfTaskInfo_t taskInfo;
3831 getTaskInfo(taskId, &taskInfo);
3832 if (taskInfo.isEnabled) {
3833 int taskFrequency;
3834 int subTaskFrequency;
3835 if (taskId == TASK_GYROPID) {
3836 subTaskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
3837 taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom;
3838 if (pidConfig()->pid_process_denom > 1) {
3839 cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
3840 } else {
3841 taskFrequency = subTaskFrequency;
3842 cliPrintf("%02d - (%11s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
3844 } else {
3845 taskFrequency = taskInfo.latestDeltaTime == 0 ? 0 : (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
3846 cliPrintf("%02d - (%15s) ", taskId, taskInfo.taskName);
3848 const int maxLoad = taskInfo.maxExecutionTime == 0 ? 0 :(taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
3849 const int averageLoad = taskInfo.averageExecutionTime == 0 ? 0 : (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
3850 if (taskId != TASK_SERIAL) {
3851 maxLoadSum += maxLoad;
3852 averageLoadSum += averageLoad;
3854 if (systemConfig()->task_statistics) {
3855 cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n",
3856 taskFrequency, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime,
3857 maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
3858 } else {
3859 cliPrintf("%6d\r\n", taskFrequency);
3861 if (taskId == TASK_GYROPID && pidConfig()->pid_process_denom > 1) {
3862 cliPrintf(" - (%15s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency);
3866 if (systemConfig()->task_statistics) {
3867 cfCheckFuncInfo_t checkFuncInfo;
3868 getCheckFuncInfo(&checkFuncInfo);
3869 cliPrintf("RX Check Function %17d %7d %25d\r\n", checkFuncInfo.maxExecutionTime, checkFuncInfo.averageExecutionTime, checkFuncInfo.totalExecutionTime / 1000);
3870 cliPrintf("Total (excluding SERIAL) %23d.%1d%% %4d.%1d%%\r\n", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
3873 #endif
3875 static void cliVersion(char *cmdline)
3877 UNUSED(cmdline);
3879 cliPrintf("# %s / %s %s %s / %s (%s)\r\n",
3880 FC_FIRMWARE_NAME,
3881 targetName,
3882 FC_VERSION_STRING,
3883 buildDate,
3884 buildTime,
3885 shortGitRevision
3889 #if defined(USE_RESOURCE_MGMT)
3891 #define MAX_RESOURCE_INDEX(x) ((x) == 0 ? 1 : (x))
3893 typedef struct {
3894 const uint8_t owner;
3895 pgn_t pgn;
3896 uint16_t offset;
3897 const uint8_t maxIndex;
3898 } cliResourceValue_t;
3900 const cliResourceValue_t resourceTable[] = {
3901 #ifdef BEEPER
3902 { OWNER_BEEPER, PG_BEEPER_DEV_CONFIG, offsetof(beeperDevConfig_t, ioTag), 0 },
3903 #endif
3904 { OWNER_MOTOR, PG_MOTOR_CONFIG, offsetof(motorConfig_t, dev.ioTags[0]), MAX_SUPPORTED_MOTORS },
3905 #ifdef USE_SERVOS
3906 { OWNER_SERVO, PG_SERVO_CONFIG, offsetof(servoConfig_t, dev.ioTags[0]), MAX_SUPPORTED_SERVOS },
3907 #endif
3908 #if defined(USE_PWM) || defined(USE_PPM)
3909 { OWNER_PPMINPUT, PG_PPM_CONFIG, offsetof(ppmConfig_t, ioTag), 0 },
3910 { OWNER_PWMINPUT, PG_PWM_CONFIG, offsetof(pwmConfig_t, ioTags[0]), PWM_INPUT_PORT_COUNT },
3911 #endif
3912 #ifdef SONAR
3913 { OWNER_SONAR_TRIGGER, PG_SONAR_CONFIG, offsetof(sonarConfig_t, triggerTag), 0 },
3914 { OWNER_SONAR_ECHO, PG_SERIAL_CONFIG, offsetof(sonarConfig_t, echoTag), 0 },
3915 #endif
3916 #ifdef LED_STRIP
3917 { OWNER_LED_STRIP, PG_LED_STRIP_CONFIG, offsetof(ledStripConfig_t, ioTag), 0 },
3918 #endif
3919 { OWNER_SERIAL_TX, PG_SERIAL_CONFIG, offsetof(serialPinConfig_t, ioTagTx[0]), SERIAL_PORT_MAX_INDEX },
3920 { OWNER_SERIAL_RX, PG_SERIAL_CONFIG, offsetof(serialPinConfig_t, ioTagRx[0]), SERIAL_PORT_MAX_INDEX },
3923 static ioTag_t *getIoTag(const cliResourceValue_t value, uint8_t index)
3925 const pgRegistry_t* rec = pgFind(value.pgn);
3926 return CONST_CAST(ioTag_t *, rec->address + value.offset + index);
3929 static void printResource(uint8_t dumpMask)
3931 for (unsigned int i = 0; i < ARRAYLEN(resourceTable); i++) {
3932 const char* owner = ownerNames[resourceTable[i].owner];
3933 const void *currentConfig;
3934 const void *defaultConfig;
3935 if (dumpMask & DO_DIFF || dumpMask & SHOW_DEFAULTS) {
3936 const cliCurrentAndDefaultConfig_t *config = getCurrentAndDefaultConfigs(resourceTable[i].pgn);
3937 currentConfig = config->currentConfig;
3938 defaultConfig = config->defaultConfig;
3939 } else { // Not guaranteed to have initialised default configs in this case
3940 currentConfig = pgFind(resourceTable[i].pgn)->address;
3941 defaultConfig = currentConfig;
3944 for (int index = 0; index < MAX_RESOURCE_INDEX(resourceTable[i].maxIndex); index++) {
3945 const ioTag_t ioTag = *((const ioTag_t *)currentConfig + resourceTable[i].offset + index);
3946 const ioTag_t ioTagDefault = *((const ioTag_t *)defaultConfig + resourceTable[i].offset + index);
3948 bool equalsDefault = ioTag == ioTagDefault;
3949 const char *format = "resource %s %d %c%02d\r\n";
3950 const char *formatUnassigned = "resource %s %d NONE\r\n";
3951 if (!ioTagDefault) {
3952 cliDefaultPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
3953 } else {
3954 cliDefaultPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdxByTag(ioTagDefault) + 'A', IO_GPIOPinIdxByTag(ioTagDefault));
3956 if (!ioTag) {
3957 if (!(dumpMask & HIDE_UNUSED)) {
3958 cliDumpPrintf(dumpMask, equalsDefault, formatUnassigned, owner, RESOURCE_INDEX(index));
3960 } else {
3961 cliDumpPrintf(dumpMask, equalsDefault, format, owner, RESOURCE_INDEX(index), IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag));
3967 static void printResourceOwner(uint8_t owner, uint8_t index)
3969 cliPrintf("%s", ownerNames[resourceTable[owner].owner]);
3971 if (resourceTable[owner].maxIndex > 0) {
3972 cliPrintf(" %d", RESOURCE_INDEX(index));
3976 static void resourceCheck(uint8_t resourceIndex, uint8_t index, ioTag_t newTag)
3978 if (!newTag) {
3979 return;
3982 const char * format = "\r\nNOTE: %c%02d already assigned to ";
3983 for (int r = 0; r < (int)ARRAYLEN(resourceTable); r++) {
3984 for (int i = 0; i < MAX_RESOURCE_INDEX(resourceTable[r].maxIndex); i++) {
3985 ioTag_t *tag = getIoTag(resourceTable[r], i);
3986 if (*tag == newTag) {
3987 bool cleared = false;
3988 if (r == resourceIndex) {
3989 if (i == index) {
3990 continue;
3992 *tag = IO_TAG_NONE;
3993 cleared = true;
3996 cliPrintf(format, DEFIO_TAG_GPIOID(newTag) + 'A', DEFIO_TAG_PIN(newTag));
3998 printResourceOwner(r, i);
4000 if (cleared) {
4001 cliPrintf(". ");
4002 printResourceOwner(r, i);
4003 cliPrintf(" disabled");
4006 cliPrint(".\r\n");
4012 static void cliResource(char *cmdline)
4014 int len = strlen(cmdline);
4016 if (len == 0) {
4017 printResource(DUMP_MASTER | HIDE_UNUSED);
4019 return;
4020 } else if (strncasecmp(cmdline, "list", len) == 0) {
4021 #ifdef MINIMAL_CLI
4022 cliPrintf("IO\r\n");
4023 #else
4024 cliPrintf("Currently active IO resource assignments:\r\n(reboot to update)\r\n");
4025 cliRepeat('-', 20);
4026 #endif
4027 for (int i = 0; i < DEFIO_IO_USED_COUNT; i++) {
4028 const char* owner;
4029 owner = ownerNames[ioRecs[i].owner];
4031 cliPrintf("%c%02d: %s ", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner);
4032 if (ioRecs[i].index > 0) {
4033 cliPrintf("%d", ioRecs[i].index);
4035 cliPrintf("\r\n");
4038 cliPrintf("\r\n\r\n");
4039 #ifdef MINIMAL_CLI
4040 cliPrintf("DMA:\r\n");
4041 #else
4042 cliPrintf("Currently active DMA:\r\n");
4043 cliRepeat('-', 20);
4044 #endif
4045 for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
4046 const char* owner;
4047 owner = ownerNames[dmaGetOwner(i)];
4049 cliPrintf(DMA_OUTPUT_STRING, i / DMA_MOD_VALUE + 1, (i % DMA_MOD_VALUE) + DMA_MOD_OFFSET);
4050 uint8_t resourceIndex = dmaGetResourceIndex(i);
4051 if (resourceIndex > 0) {
4052 cliPrintf(" %s %d\r\n", owner, resourceIndex);
4053 } else {
4054 cliPrintf(" %s\r\n", owner);
4058 #ifndef MINIMAL_CLI
4059 cliPrintf("\r\nUse: 'resource' to see how to change resources.\r\n");
4060 #endif
4062 return;
4065 uint8_t resourceIndex = 0;
4066 int index = 0;
4067 char *pch = NULL;
4068 char *saveptr;
4070 pch = strtok_r(cmdline, " ", &saveptr);
4071 for (resourceIndex = 0; ; resourceIndex++) {
4072 if (resourceIndex >= ARRAYLEN(resourceTable)) {
4073 cliPrint("Invalid\r\n");
4074 return;
4077 if (strncasecmp(pch, ownerNames[resourceTable[resourceIndex].owner], len) == 0) {
4078 break;
4082 pch = strtok_r(NULL, " ", &saveptr);
4083 index = atoi(pch);
4085 if (resourceTable[resourceIndex].maxIndex > 0 || index > 0) {
4086 if (index <= 0 || index > MAX_RESOURCE_INDEX(resourceTable[resourceIndex].maxIndex)) {
4087 cliShowArgumentRangeError("index", 1, MAX_RESOURCE_INDEX(resourceTable[resourceIndex].maxIndex));
4088 return;
4090 index -= 1;
4092 pch = strtok_r(NULL, " ", &saveptr);
4095 ioTag_t *tag = getIoTag(resourceTable[resourceIndex], index);
4097 uint8_t pin = 0;
4098 if (strlen(pch) > 0) {
4099 if (strcasecmp(pch, "NONE") == 0) {
4100 *tag = IO_TAG_NONE;
4101 #ifdef MINIMAL_CLI
4102 cliPrintf("Freed\r\n");
4103 #else
4104 cliPrintf("Resource is freed\r\n");
4105 #endif
4106 return;
4107 } else {
4108 uint8_t port = (*pch) - 'A';
4109 if (port >= 8) {
4110 port = (*pch) - 'a';
4113 if (port < 8) {
4114 pch++;
4115 pin = atoi(pch);
4116 if (pin < 16) {
4117 ioRec_t *rec = IO_Rec(IOGetByTag(DEFIO_TAG_MAKE(port, pin)));
4118 if (rec) {
4119 resourceCheck(resourceIndex, index, DEFIO_TAG_MAKE(port, pin));
4120 #ifdef MINIMAL_CLI
4121 cliPrintf(" %c%02d set\r\n", port + 'A', pin);
4122 #else
4123 cliPrintf("\r\nResource is set to %c%02d!\r\n", port + 'A', pin);
4124 #endif
4125 *tag = DEFIO_TAG_MAKE(port, pin);
4126 } else {
4127 cliShowParseError();
4129 return;
4135 cliShowParseError();
4137 #endif /* USE_RESOURCE_MGMT */
4139 #ifdef USE_PARAMETER_GROUPS
4140 static void backupConfigs(void)
4142 // make copies of configs to do differencing
4143 PG_FOREACH(reg) {
4144 // currentConfig is the copy
4145 const cliCurrentAndDefaultConfig_t *cliCurrentAndDefaultConfig = getCurrentAndDefaultConfigs(pgN(reg));
4146 if (cliCurrentAndDefaultConfig->currentConfig) {
4147 if (pgIsProfile(reg)) {
4148 //memcpy((uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->address, reg->size * MAX_PROFILE_COUNT);
4149 } else {
4150 memcpy((uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->address, reg->size);
4152 #ifdef SERIAL_CLI_DEBUG
4153 } else {
4154 cliPrintf("BACKUP %d SET UP INCORRECTLY\r\n", pgN(reg));
4155 #endif
4160 static void restoreConfigs(void)
4162 PG_FOREACH(reg) {
4163 // currentConfig is the copy
4164 const cliCurrentAndDefaultConfig_t *cliCurrentAndDefaultConfig = getCurrentAndDefaultConfigs(pgN(reg));
4165 if (cliCurrentAndDefaultConfig->currentConfig) {
4166 if (pgIsProfile(reg)) {
4167 //memcpy(reg->address, (uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->size * MAX_PROFILE_COUNT);
4168 } else {
4169 memcpy(reg->address, (uint8_t *)cliCurrentAndDefaultConfig->currentConfig, reg->size);
4171 #ifdef SERIAL_CLI_DEBUG
4172 } else {
4173 cliPrintf("RESTORE %d SET UP INCORRECTLY\r\n", pgN(reg));
4174 #endif
4178 #endif
4180 static void printConfig(char *cmdline, bool doDiff)
4182 uint8_t dumpMask = DUMP_MASTER;
4183 char *options;
4184 if ((options = checkCommand(cmdline, "master"))) {
4185 dumpMask = DUMP_MASTER; // only
4186 } else if ((options = checkCommand(cmdline, "profile"))) {
4187 dumpMask = DUMP_PROFILE; // only
4188 } else if ((options = checkCommand(cmdline, "rates"))) {
4189 dumpMask = DUMP_RATES; // only
4190 } else if ((options = checkCommand(cmdline, "all"))) {
4191 dumpMask = DUMP_ALL; // all profiles and rates
4192 } else {
4193 options = cmdline;
4196 if (doDiff) {
4197 dumpMask = dumpMask | DO_DIFF;
4200 backupConfigs();
4201 // reset all configs to defaults to do differencing
4202 resetConfigs();
4204 #if defined(TARGET_CONFIG)
4205 targetConfiguration();
4206 #endif
4207 if (checkCommand(options, "showdefaults")) {
4208 dumpMask = dumpMask | SHOW_DEFAULTS; // add default values as comments for changed values
4211 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
4212 cliPrintHashLine("version");
4213 cliVersion(NULL);
4215 if ((dumpMask & (DUMP_ALL | DO_DIFF)) == (DUMP_ALL | DO_DIFF)) {
4216 cliPrintHashLine("reset configuration to default settings");
4217 cliPrint("defaults\r\n");
4220 cliPrintHashLine("name");
4221 printName(dumpMask, &systemConfigCopy);
4223 #ifdef USE_RESOURCE_MGMT
4224 cliPrintHashLine("resources");
4225 printResource(dumpMask);
4226 #endif
4228 #ifndef USE_QUAD_MIXER_ONLY
4229 cliPrintHashLine("mixer");
4230 const bool equalsDefault = mixerConfigCopy.mixerMode == mixerConfig()->mixerMode;
4231 const char *formatMixer = "mixer %s\r\n";
4232 cliDefaultPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfig()->mixerMode - 1]);
4233 cliDumpPrintf(dumpMask, equalsDefault, formatMixer, mixerNames[mixerConfigCopy.mixerMode - 1]);
4235 cliDumpPrintf(dumpMask, customMotorMixer(0)->throttle == 0.0f, "\r\nmmix reset\r\n\r\n");
4237 printMotorMix(dumpMask, customMotorMixerCopy, customMotorMixer(0));
4239 #ifdef USE_SERVOS
4240 cliPrintHashLine("servo");
4241 printServo(dumpMask, servoParamsCopy, servoParams(0));
4243 cliPrintHashLine("servo mix");
4244 // print custom servo mixer if exists
4245 cliDumpPrintf(dumpMask, customServoMixers(0)->rate == 0, "smix reset\r\n\r\n");
4246 printServoMix(dumpMask, customServoMixersCopy, customServoMixers(0));
4247 #endif
4248 #endif
4250 cliPrintHashLine("feature");
4251 printFeature(dumpMask, &featureConfigCopy, featureConfig());
4253 #ifdef BEEPER
4254 cliPrintHashLine("beeper");
4255 printBeeper(dumpMask, &beeperConfigCopy, beeperConfig());
4256 #endif
4258 cliPrintHashLine("map");
4259 printMap(dumpMask, &rxConfigCopy, rxConfig());
4261 cliPrintHashLine("serial");
4262 printSerial(dumpMask, &serialConfigCopy, serialConfig());
4264 #ifdef LED_STRIP
4265 cliPrintHashLine("led");
4266 printLed(dumpMask, ledStripConfigCopy.ledConfigs, ledStripConfig()->ledConfigs);
4268 cliPrintHashLine("color");
4269 printColor(dumpMask, ledStripConfigCopy.colors, ledStripConfig()->colors);
4271 cliPrintHashLine("mode_color");
4272 printModeColor(dumpMask, &ledStripConfigCopy, ledStripConfig());
4273 #endif
4275 cliPrintHashLine("aux");
4276 printAux(dumpMask, modeActivationConditionsCopy, modeActivationConditions(0));
4278 cliPrintHashLine("adjrange");
4279 printAdjustmentRange(dumpMask, adjustmentRangesCopy, adjustmentRanges(0));
4281 cliPrintHashLine("rxrange");
4282 printRxRange(dumpMask, rxChannelRangeConfigsCopy, rxChannelRangeConfigs(0));
4284 #if defined(USE_RTC6705) || defined(VTX)
4285 cliPrintHashLine("vtx");
4286 printVtx(dumpMask, &vtxConfigCopy, vtxConfig());
4287 #endif
4289 cliPrintHashLine("rxfail");
4290 printRxFailsafe(dumpMask, rxFailsafeChannelConfigsCopy, rxFailsafeChannelConfigs(0));
4292 cliPrintHashLine("master");
4293 dumpAllValues(MASTER_VALUE, dumpMask);
4295 if (dumpMask & DUMP_ALL) {
4296 const uint8_t pidProfileIndexSave = systemConfigCopy.pidProfileIndex;
4297 for (uint32_t pidProfileIndex = 0; pidProfileIndex < MAX_PROFILE_COUNT; pidProfileIndex++) {
4298 cliDumpPidProfile(pidProfileIndex, dumpMask);
4300 changePidProfile(pidProfileIndexSave);
4301 cliPrintHashLine("restore original profile selection");
4302 cliProfile("");
4304 const uint8_t controlRateProfileIndexSave = systemConfigCopy.activeRateProfile;
4305 for (uint32_t rateIndex = 0; rateIndex < CONTROL_RATE_PROFILE_COUNT; rateIndex++) {
4306 cliDumpRateProfile(rateIndex, dumpMask);
4308 changeControlRateProfile(controlRateProfileIndexSave);
4309 cliPrintHashLine("restore original rateprofile selection");
4310 cliRateProfile("");
4312 cliPrintHashLine("save configuration");
4313 cliPrint("save");
4314 } else {
4315 cliDumpPidProfile(systemConfigCopy.pidProfileIndex, dumpMask);
4317 cliDumpRateProfile(systemConfigCopy.activeRateProfile, dumpMask);
4321 if (dumpMask & DUMP_PROFILE) {
4322 cliDumpPidProfile(systemConfigCopy.pidProfileIndex, dumpMask);
4325 if (dumpMask & DUMP_RATES) {
4326 cliDumpRateProfile(systemConfigCopy.activeRateProfile, dumpMask);
4328 #ifdef USE_PARAMETER_GROUPS
4329 // restore configs from copies
4330 restoreConfigs();
4331 #endif
4334 static void cliDump(char *cmdline)
4336 printConfig(cmdline, false);
4339 static void cliDiff(char *cmdline)
4341 printConfig(cmdline, true);
4344 typedef struct {
4345 const char *name;
4346 #ifndef MINIMAL_CLI
4347 const char *description;
4348 const char *args;
4349 #endif
4350 void (*func)(char *cmdline);
4351 } clicmd_t;
4353 #ifndef MINIMAL_CLI
4354 #define CLI_COMMAND_DEF(name, description, args, method) \
4356 name , \
4357 description , \
4358 args , \
4359 method \
4361 #else
4362 #define CLI_COMMAND_DEF(name, description, args, method) \
4364 name, \
4365 method \
4367 #endif
4369 static void cliHelp(char *cmdline);
4371 // should be sorted a..z for bsearch()
4372 const clicmd_t cmdTable[] = {
4373 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
4374 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
4375 #ifdef BEEPER
4376 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
4377 "\t<+|->[name]", cliBeeper),
4378 #endif
4379 #ifdef LED_STRIP
4380 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
4381 #endif
4382 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
4383 CLI_COMMAND_DEF("bl", "reboot into bootloader", NULL, cliBootloader),
4384 CLI_COMMAND_DEF("diff", "list configuration changes from default",
4385 "[master|profile|rates|all] {showdefaults}", cliDiff),
4386 #ifdef USE_DSHOT
4387 CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg),
4388 #endif
4389 CLI_COMMAND_DEF("dump", "dump configuration",
4390 "[master|profile|rates|all] {showdefaults}", cliDump),
4391 #ifdef USE_ESCSERIAL
4392 CLI_COMMAND_DEF("escprog", "passthrough esc to serial", "<mode [sk/bl/ki/cc]> <index>", cliEscPassthrough),
4393 #endif
4394 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
4395 CLI_COMMAND_DEF("feature", "configure features",
4396 "list\r\n"
4397 "\t<+|->[name]", cliFeature),
4398 #ifdef USE_FLASHFS
4399 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
4400 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
4401 #ifdef USE_FLASH_TOOLS
4402 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
4403 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
4404 #endif
4405 #endif
4406 CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet),
4407 #ifdef GPS
4408 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
4409 #endif
4410 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
4411 #ifdef LED_STRIP
4412 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
4413 #endif
4414 CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap),
4415 #ifndef USE_QUAD_MIXER_ONLY
4416 CLI_COMMAND_DEF("mixer", "configure mixer", "list\r\n\t<name>", cliMixer),
4417 #endif
4418 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
4419 #ifdef LED_STRIP
4420 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
4421 #endif
4422 CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor),
4423 CLI_COMMAND_DEF("name", "name of craft", NULL, cliName),
4424 #ifndef MINIMAL_CLI
4425 CLI_COMMAND_DEF("play_sound", NULL, "[<index>]", cliPlaySound),
4426 #endif
4427 CLI_COMMAND_DEF("profile", "change profile", "[<index>]", cliProfile),
4428 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
4429 #if defined(USE_RESOURCE_MGMT)
4430 CLI_COMMAND_DEF("resource", "show/set resources", NULL, cliResource),
4431 #endif
4432 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFailsafe),
4433 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
4434 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
4435 #ifdef USE_SDCARD
4436 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
4437 #endif
4438 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
4439 #ifndef SKIP_SERIAL_PASSTHROUGH
4440 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
4441 #endif
4442 #ifdef USE_SERVOS
4443 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
4444 #endif
4445 CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet),
4446 #ifdef USE_SERVOS
4447 CLI_COMMAND_DEF("smix", "servo mixer", "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
4448 "\treset\r\n"
4449 "\tload <mixer>\r\n"
4450 "\treverse <servo> <source> r|n", cliServoMix),
4451 #endif
4452 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
4453 #ifndef SKIP_TASK_STATISTICS
4454 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
4455 #endif
4456 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
4457 #ifdef VTX
4458 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
4459 #endif
4461 static void cliHelp(char *cmdline)
4463 UNUSED(cmdline);
4465 for (uint32_t i = 0; i < ARRAYLEN(cmdTable); i++) {
4466 cliPrint(cmdTable[i].name);
4467 #ifndef MINIMAL_CLI
4468 if (cmdTable[i].description) {
4469 cliPrintf(" - %s", cmdTable[i].description);
4471 if (cmdTable[i].args) {
4472 cliPrintf("\r\n\t%s", cmdTable[i].args);
4474 #endif
4475 cliPrint("\r\n");
4479 void cliProcess(void)
4481 if (!cliWriter) {
4482 return;
4485 // Be a little bit tricky. Flush the last inputs buffer, if any.
4486 bufWriterFlush(cliWriter);
4488 while (serialRxBytesWaiting(cliPort)) {
4489 uint8_t c = serialRead(cliPort);
4490 if (c == '\t' || c == '?') {
4491 // do tab completion
4492 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
4493 uint32_t i = bufferIndex;
4494 for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
4495 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
4496 continue;
4497 if (!pstart)
4498 pstart = cmd;
4499 pend = cmd;
4501 if (pstart) { /* Buffer matches one or more commands */
4502 for (; ; bufferIndex++) {
4503 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
4504 break;
4505 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
4506 /* Unambiguous -- append a space */
4507 cliBuffer[bufferIndex++] = ' ';
4508 cliBuffer[bufferIndex] = '\0';
4509 break;
4511 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
4514 if (!bufferIndex || pstart != pend) {
4515 /* Print list of ambiguous matches */
4516 cliPrint("\r\033[K");
4517 for (cmd = pstart; cmd <= pend; cmd++) {
4518 cliPrint(cmd->name);
4519 cliWrite('\t');
4521 cliPrompt();
4522 i = 0; /* Redraw prompt */
4524 for (; i < bufferIndex; i++)
4525 cliWrite(cliBuffer[i]);
4526 } else if (!bufferIndex && c == 4) { // CTRL-D
4527 cliExit(cliBuffer);
4528 return;
4529 } else if (c == 12) { // NewPage / CTRL-L
4530 // clear screen
4531 cliPrint("\033[2J\033[1;1H");
4532 cliPrompt();
4533 } else if (bufferIndex && (c == '\n' || c == '\r')) {
4534 // enter pressed
4535 cliPrint("\r\n");
4537 // Strip comment starting with # from line
4538 char *p = cliBuffer;
4539 p = strchr(p, '#');
4540 if (NULL != p) {
4541 bufferIndex = (uint32_t)(p - cliBuffer);
4544 // Strip trailing whitespace
4545 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
4546 bufferIndex--;
4549 // Process non-empty lines
4550 if (bufferIndex > 0) {
4551 cliBuffer[bufferIndex] = 0; // null terminate
4553 const clicmd_t *cmd;
4554 char *options;
4555 for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
4556 if ((options = checkCommand(cliBuffer, cmd->name))) {
4557 break;
4560 if(cmd < cmdTable + ARRAYLEN(cmdTable))
4561 cmd->func(options);
4562 else
4563 cliPrint("Unknown command, try 'help'");
4564 bufferIndex = 0;
4567 memset(cliBuffer, 0, sizeof(cliBuffer));
4569 // 'exit' will reset this flag, so we don't need to print prompt again
4570 if (!cliMode)
4571 return;
4573 cliPrompt();
4574 } else if (c == 127) {
4575 // backspace
4576 if (bufferIndex) {
4577 cliBuffer[--bufferIndex] = 0;
4578 cliPrint("\010 \010");
4580 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
4581 if (!bufferIndex && c == ' ')
4582 continue; // Ignore leading spaces
4583 cliBuffer[bufferIndex++] = c;
4584 cliWrite(c);
4589 void cliEnter(serialPort_t *serialPort)
4591 cliMode = 1;
4592 cliPort = serialPort;
4593 setPrintfSerialPort(cliPort);
4594 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufShim, serialPort);
4596 schedulerSetCalulateTaskStatistics(systemConfig()->task_statistics);
4598 #ifndef MINIMAL_CLI
4599 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
4600 #else
4601 cliPrint("\r\nCLI\r\n");
4602 #endif
4603 cliPrompt();
4605 ENABLE_ARMING_FLAG(PREVENT_ARMING);
4608 void cliInit(const serialConfig_t *serialConfig)
4610 UNUSED(serialConfig);
4611 BUILD_BUG_ON(LOOKUP_TABLE_COUNT != ARRAYLEN(lookupTables));
4613 #endif // USE_CLI