Add rc_rate_yaw // SuperExpo feature renamed to SUPEREXPO_RATES
[betaflight.git] / src / main / io / serial_cli.c
blobd077b961483046eca8c67d8e24d6aaf04c8e520f
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"
27 #include "scheduler.h"
28 #include "version.h"
29 #include "debug.h"
31 #include "build_config.h"
33 #include "common/axis.h"
34 #include "common/maths.h"
35 #include "common/color.h"
36 #include "common/typeconversion.h"
38 #include "drivers/system.h"
40 #include "drivers/sensor.h"
41 #include "drivers/accgyro.h"
42 #include "drivers/compass.h"
44 #include "drivers/serial.h"
45 #include "drivers/bus_i2c.h"
46 #include "drivers/gpio.h"
47 #include "drivers/timer.h"
48 #include "drivers/pwm_rx.h"
49 #include "drivers/sdcard.h"
50 #include "drivers/gyro_sync.h"
52 #include "drivers/buf_writer.h"
54 #include "io/escservo.h"
55 #include "io/gps.h"
56 #include "io/gimbal.h"
57 #include "io/rc_controls.h"
58 #include "io/serial.h"
59 #include "io/ledstrip.h"
60 #include "io/flashfs.h"
61 #include "io/beeper.h"
62 #include "io/asyncfatfs/asyncfatfs.h"
63 #include "io/vtx.h"
65 #include "rx/rx.h"
66 #include "rx/spektrum.h"
68 #include "sensors/battery.h"
69 #include "sensors/boardalignment.h"
70 #include "sensors/sensors.h"
71 #include "sensors/acceleration.h"
72 #include "sensors/gyro.h"
73 #include "sensors/compass.h"
74 #include "sensors/barometer.h"
76 #include "flight/pid.h"
77 #include "flight/imu.h"
78 #include "flight/mixer.h"
79 #include "flight/navigation.h"
80 #include "flight/failsafe.h"
82 #include "telemetry/telemetry.h"
83 #include "telemetry/frsky.h"
85 #include "config/runtime_config.h"
86 #include "config/config.h"
87 #include "config/config_profile.h"
88 #include "config/config_master.h"
90 #include "common/printf.h"
92 #include "serial_cli.h"
94 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
95 // signal that we're in cli mode
96 uint8_t cliMode = 0;
98 #ifdef USE_CLI
100 extern uint16_t cycleTime; // FIXME dependency on mw.c
102 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
104 static serialPort_t *cliPort;
105 static bufWriter_t *cliWriter;
106 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
108 static void cliAux(char *cmdline);
109 static void cliRxFail(char *cmdline);
110 static void cliAdjustmentRange(char *cmdline);
111 static void cliMotorMix(char *cmdline);
112 static void cliDefaults(char *cmdline);
113 static void cliDump(char *cmdLine);
114 void cliDumpProfile(uint8_t profileIndex);
115 void cliDumpRateProfile(uint8_t rateProfileIndex) ;
116 static void cliExit(char *cmdline);
117 static void cliFeature(char *cmdline);
118 static void cliMotor(char *cmdline);
119 static void cliPlaySound(char *cmdline);
120 static void cliProfile(char *cmdline);
121 static void cliRateProfile(char *cmdline);
122 static void cliReboot(void);
123 static void cliSave(char *cmdline);
124 static void cliSerial(char *cmdline);
125 #ifndef SKIP_SERIAL_PASSTHROUGH
126 static void cliSerialPassthrough(char *cmdline);
127 #endif
129 #ifdef USE_SERVOS
130 static void cliServo(char *cmdline);
131 static void cliServoMix(char *cmdline);
132 #endif
134 static void cliSet(char *cmdline);
135 static void cliGet(char *cmdline);
136 static void cliStatus(char *cmdline);
137 #ifndef SKIP_TASK_STATISTICS
138 static void cliTasks(char *cmdline);
139 #endif
140 static void cliVersion(char *cmdline);
141 static void cliRxRange(char *cmdline);
143 #ifdef GPS
144 static void cliGpsPassthrough(char *cmdline);
145 #endif
147 static void cliHelp(char *cmdline);
148 static void cliMap(char *cmdline);
150 #ifdef LED_STRIP
151 static void cliLed(char *cmdline);
152 static void cliColor(char *cmdline);
153 #endif
155 #ifndef USE_QUAD_MIXER_ONLY
156 static void cliMixer(char *cmdline);
157 #endif
159 #ifdef USE_FLASHFS
160 static void cliFlashInfo(char *cmdline);
161 static void cliFlashErase(char *cmdline);
162 #ifdef USE_FLASH_TOOLS
163 static void cliFlashWrite(char *cmdline);
164 static void cliFlashRead(char *cmdline);
165 #endif
166 #endif
168 #ifdef VTX
169 static void cliVtx(char *cmdline);
170 #endif
172 #ifdef USE_SDCARD
173 static void cliSdInfo(char *cmdline);
174 #endif
176 #ifdef BEEPER
177 static void cliBeeper(char *cmdline);
178 #endif
180 // buffer
181 static char cliBuffer[48];
182 static uint32_t bufferIndex = 0;
184 #ifndef USE_QUAD_MIXER_ONLY
185 // sync this with mixerMode_e
186 static const char * const mixerNames[] = {
187 "TRI", "QUADP", "QUADX", "BI",
188 "GIMBAL", "Y6", "HEX6",
189 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
190 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
191 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
192 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
194 #endif
196 // sync this with features_e
197 static const char * const featureNames[] = {
198 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
199 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
200 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
201 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
202 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES",
203 NULL
206 // sync this with rxFailsafeChannelMode_e
207 static const char rxFailsafeModeCharacters[] = "ahs";
209 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
210 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
211 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
214 #ifndef CJMCU
215 // sync this with sensors_e
216 static const char * const sensorTypeNames[] = {
217 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
220 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
222 static const char * const sensorHardwareNames[4][11] = {
223 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
224 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
225 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
226 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
228 #endif
230 typedef struct {
231 const char *name;
232 #ifndef SKIP_CLI_COMMAND_HELP
233 const char *description;
234 const char *args;
235 #endif
236 void (*func)(char *cmdline);
237 } clicmd_t;
239 #ifndef SKIP_CLI_COMMAND_HELP
240 #define CLI_COMMAND_DEF(name, description, args, method) \
242 name , \
243 description , \
244 args , \
245 method \
247 #else
248 #define CLI_COMMAND_DEF(name, description, args, method) \
250 name, \
251 method \
253 #endif
255 // should be sorted a..z for bsearch()
256 const clicmd_t cmdTable[] = {
257 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
258 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
259 #ifdef LED_STRIP
260 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
261 #endif
262 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
263 CLI_COMMAND_DEF("dump", "dump configuration",
264 "[master|profile]", cliDump),
265 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
266 CLI_COMMAND_DEF("feature", "configure features",
267 "list\r\n"
268 "\t<+|->[name]", cliFeature),
269 #ifdef USE_FLASHFS
270 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
271 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
272 #ifdef USE_FLASH_TOOLS
273 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
274 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
275 #endif
276 #endif
277 CLI_COMMAND_DEF("get", "get variable value",
278 "[name]", cliGet),
279 #ifdef GPS
280 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
281 #endif
282 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
283 #ifdef LED_STRIP
284 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
285 #endif
286 CLI_COMMAND_DEF("map", "configure rc channel order",
287 "[<map>]", cliMap),
288 #ifndef USE_QUAD_MIXER_ONLY
289 CLI_COMMAND_DEF("mixer", "configure mixer",
290 "list\r\n"
291 "\t<name>", cliMixer),
292 #endif
293 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
294 CLI_COMMAND_DEF("motor", "get/set motor",
295 "<index> [<value>]", cliMotor),
296 CLI_COMMAND_DEF("play_sound", NULL,
297 "[<index>]\r\n", cliPlaySound),
298 CLI_COMMAND_DEF("profile", "change profile",
299 "[<index>]", cliProfile),
300 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
301 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
302 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
303 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
304 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
305 #ifndef SKIP_SERIAL_PASSTHROUGH
306 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
307 "<id> [baud] [mode] : passthrough to serial",
308 cliSerialPassthrough),
309 #endif
310 #ifdef USE_SERVOS
311 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
312 #endif
313 CLI_COMMAND_DEF("set", "change setting",
314 "[<name>=<value>]", cliSet),
315 #ifdef USE_SERVOS
316 CLI_COMMAND_DEF("smix", "servo mixer",
317 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
318 "\treset\r\n"
319 "\tload <mixer>\r\n"
320 "\treverse <servo> <source> r|n", cliServoMix),
321 #endif
322 #ifdef USE_SDCARD
323 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
324 #endif
325 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
326 #ifndef SKIP_TASK_STATISTICS
327 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
328 #endif
329 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
330 #ifdef BEEPER
331 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
332 "\t<+|->[name]", cliBeeper),
333 #endif
334 #ifdef VTX
335 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
336 #endif
338 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
340 static const char * const lookupTableOffOn[] = {
341 "OFF", "ON"
344 static const char * const lookupTableUnit[] = {
345 "IMPERIAL", "METRIC"
348 static const char * const lookupTableAlignment[] = {
349 "DEFAULT",
350 "CW0",
351 "CW90",
352 "CW180",
353 "CW270",
354 "CW0FLIP",
355 "CW90FLIP",
356 "CW180FLIP",
357 "CW270FLIP"
360 #ifdef GPS
361 static const char * const lookupTableGPSProvider[] = {
362 "NMEA", "UBLOX"
365 static const char * const lookupTableGPSSBASMode[] = {
366 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
368 #endif
370 static const char * const lookupTableCurrentSensor[] = {
371 "NONE", "ADC", "VIRTUAL"
374 static const char * const lookupTableGimbalMode[] = {
375 "NORMAL", "MIXTILT"
378 static const char * const lookupTableBlackboxDevice[] = {
379 "SERIAL", "SPIFLASH", "SDCARD"
383 static const char * const lookupTablePidController[] = {
384 "UNUSED", "MWREWRITE", "LUX"
387 static const char * const lookupTableSerialRX[] = {
388 "SPEK1024",
389 "SPEK2048",
390 "SBUS",
391 "SUMD",
392 "SUMH",
393 "XB-B",
394 "XB-B-RJ01",
395 "IBUS",
396 "JETIEXBUS"
399 static const char * const lookupTableGyroLpf[] = {
400 "OFF",
401 "188HZ",
402 "98HZ",
403 "42HZ",
404 "20HZ",
405 "10HZ",
406 "5HZ",
407 "EXPERIMENTAL"
410 static const char * const lookupTableAccHardware[] = {
411 "AUTO",
412 "NONE",
413 "ADXL345",
414 "MPU6050",
415 "MMA8452",
416 "BMA280",
417 "LSM303DLHC",
418 "MPU6000",
419 "MPU6500",
420 "FAKE"
423 static const char * const lookupTableBaroHardware[] = {
424 "AUTO",
425 "NONE",
426 "BMP085",
427 "MS5611",
428 "BMP280"
431 static const char * const lookupTableMagHardware[] = {
432 "AUTO",
433 "NONE",
434 "HMC5883",
435 "AK8975",
436 "AK8963"
439 static const char * const lookupTableDebug[DEBUG_COUNT] = {
440 "NONE",
441 "CYCLETIME",
442 "BATTERY",
443 "GYRO",
444 "ACCELEROMETER",
445 "MIXER",
446 "AIRMODE",
447 "PIDLOOP",
450 static const char * const lookupTableSuperExpoYaw[] = {
451 "OFF", "ON", "ALWAYS"
454 static const char * const lookupTableFastPwm[] = {
455 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT"
458 typedef struct lookupTableEntry_s {
459 const char * const *values;
460 const uint8_t valueCount;
461 } lookupTableEntry_t;
463 typedef enum {
464 TABLE_OFF_ON = 0,
465 TABLE_UNIT,
466 TABLE_ALIGNMENT,
467 #ifdef GPS
468 TABLE_GPS_PROVIDER,
469 TABLE_GPS_SBAS_MODE,
470 #endif
471 #ifdef BLACKBOX
472 TABLE_BLACKBOX_DEVICE,
473 #endif
474 TABLE_CURRENT_SENSOR,
475 TABLE_GIMBAL_MODE,
476 TABLE_PID_CONTROLLER,
477 TABLE_SERIAL_RX,
478 TABLE_GYRO_LPF,
479 TABLE_ACC_HARDWARE,
480 TABLE_BARO_HARDWARE,
481 TABLE_MAG_HARDWARE,
482 TABLE_DEBUG,
483 TABLE_SUPEREXPO_YAW,
484 TABLE_FAST_PWM,
485 } lookupTableIndex_e;
487 static const lookupTableEntry_t lookupTables[] = {
488 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
489 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
490 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
491 #ifdef GPS
492 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
493 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
494 #endif
495 #ifdef BLACKBOX
496 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
497 #endif
498 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
499 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
500 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
501 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
502 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
503 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
504 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
505 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
506 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
507 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
508 { lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) },
511 #define VALUE_TYPE_OFFSET 0
512 #define VALUE_SECTION_OFFSET 4
513 #define VALUE_MODE_OFFSET 6
515 typedef enum {
516 // value type
517 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
518 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
519 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
520 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
521 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
522 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
524 // value section
525 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
526 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
527 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
528 // value mode
529 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
530 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
531 } cliValueFlag_e;
533 #define VALUE_TYPE_MASK (0x0F)
534 #define VALUE_SECTION_MASK (0x30)
535 #define VALUE_MODE_MASK (0xC0)
537 typedef struct cliMinMaxConfig_s {
538 const int32_t min;
539 const int32_t max;
540 } cliMinMaxConfig_t;
542 typedef struct cliLookupTableConfig_s {
543 const lookupTableIndex_e tableIndex;
544 } cliLookupTableConfig_t;
546 typedef union {
547 cliLookupTableConfig_t lookup;
548 cliMinMaxConfig_t minmax;
550 } cliValueConfig_t;
552 typedef struct {
553 const char *name;
554 const uint8_t type; // see cliValueFlag_e
555 void *ptr;
556 const cliValueConfig_t config;
557 } clivalue_t;
559 const clivalue_t valueTable[] = {
560 // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
562 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
563 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
564 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
565 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
566 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
567 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
568 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
569 { "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_OFF_ON } },
570 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
571 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
572 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
574 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
575 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
576 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
577 { "anti_desync_power_step", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.escDesyncProtection, .config.minmax = { 0, 10000 } },
578 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
580 { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME upper limit should match code in the mixer, 1500 currently
581 { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, // FIXME lower limit should match code in the mixer, 1500 currently,
582 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
583 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
585 { "unsynced_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
586 { "fast_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.fast_pwm_protocol, .config.lookup = { TABLE_FAST_PWM } },
587 #ifdef CC3D
588 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
589 #endif
590 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } },
591 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
593 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
594 { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
595 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
596 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
598 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
600 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
602 #ifdef GPS
603 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
604 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
605 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
606 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
608 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
609 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
610 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
611 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
612 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
613 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
614 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
615 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
616 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
617 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
618 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
619 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
620 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
621 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
622 #endif
623 #ifdef GTUNE
624 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
625 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
626 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
627 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
628 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
629 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
630 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
631 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
632 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
633 #endif
635 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
636 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
637 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
638 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
640 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
641 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
642 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
643 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
644 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
645 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
646 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
647 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
648 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
650 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
651 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
652 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
653 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
654 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
655 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
656 { "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
657 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
658 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
659 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
660 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
662 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
663 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
664 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
666 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
667 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
668 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
670 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
672 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
673 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
674 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
675 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
676 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
677 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
679 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
680 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
681 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
682 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
684 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
685 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
687 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
689 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
690 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
691 #ifdef USE_SERVOS
692 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
693 { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
694 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
695 #endif
697 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
698 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawRate8, .config.minmax = { 0, 250 } },
699 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
700 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
701 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
702 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
703 { "roll_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
704 { "pitch_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
705 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
706 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
707 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
708 { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } },
710 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
711 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
712 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
713 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
714 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
715 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
717 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
718 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
720 #ifdef USE_SERVOS
721 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
722 #endif
724 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
725 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
726 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
727 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
728 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
729 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
730 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
732 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
733 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
734 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
735 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
736 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
738 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
739 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
740 { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
741 { "dynamic_pid", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pid, .config.lookup = { TABLE_OFF_ON } },
742 { "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {50, 1000 } },
743 { "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {25, 1000 } },
744 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
745 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
747 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
749 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
750 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
751 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
752 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
753 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
754 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
755 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
756 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
757 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
759 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
760 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
761 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
763 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
764 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
765 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
767 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
768 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
769 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
771 #ifdef BLACKBOX
772 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
773 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
774 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
775 #endif
777 #ifdef VTX
778 { "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } },
779 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } },
780 { "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } },
781 { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
782 #endif
784 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
785 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
786 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
787 #ifdef LED_STRIP
788 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
789 #endif
792 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
795 typedef union {
796 int32_t int_value;
797 float float_value;
798 } int_float_value_t;
800 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
801 static void cliPrintVar(const clivalue_t *var, uint32_t full);
802 static void cliPrintVarRange(const clivalue_t *var);
803 static void cliPrint(const char *str);
804 static void cliPrintf(const char *fmt, ...);
805 static void cliWrite(uint8_t ch);
807 static void cliPrompt(void)
809 cliPrint("\r\n# ");
810 bufWriterFlush(cliWriter);
813 static void cliShowParseError(void)
815 cliPrint("Parse error\r\n");
818 static void cliShowArgumentRangeError(char *name, int min, int max)
820 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
823 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
825 int val;
827 for (int argIndex = 0; argIndex < 2; argIndex++) {
828 ptr = strchr(ptr, ' ');
829 if (ptr) {
830 val = atoi(++ptr);
831 val = CHANNEL_VALUE_TO_STEP(val);
832 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
833 if (argIndex == 0) {
834 range->startStep = val;
835 } else {
836 range->endStep = val;
838 (*validArgumentCount)++;
843 return ptr;
846 // Check if a string's length is zero
847 static bool isEmpty(const char *string)
849 return *string == '\0';
852 static void cliRxFail(char *cmdline)
854 uint8_t channel;
855 char buf[3];
857 if (isEmpty(cmdline)) {
858 // print out rxConfig failsafe settings
859 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
860 cliRxFail(itoa(channel, buf, 10));
862 } else {
863 char *ptr = cmdline;
864 channel = atoi(ptr++);
865 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
867 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
869 uint16_t value;
870 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
871 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
872 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
874 ptr = strchr(ptr, ' ');
875 if (ptr) {
876 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
877 if (p) {
878 uint8_t requestedMode = p - rxFailsafeModeCharacters;
879 mode = rxFailsafeModesTable[type][requestedMode];
880 } else {
881 mode = RX_FAILSAFE_MODE_INVALID;
883 if (mode == RX_FAILSAFE_MODE_INVALID) {
884 cliShowParseError();
885 return;
888 requireValue = mode == RX_FAILSAFE_MODE_SET;
890 ptr = strchr(ptr, ' ');
891 if (ptr) {
892 if (!requireValue) {
893 cliShowParseError();
894 return;
896 value = atoi(++ptr);
897 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
898 if (value > MAX_RXFAIL_RANGE_STEP) {
899 cliPrint("Value out of range\r\n");
900 return;
903 channelFailsafeConfiguration->step = value;
904 } else if (requireValue) {
905 cliShowParseError();
906 return;
908 channelFailsafeConfiguration->mode = mode;
912 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
914 // triple use of cliPrintf below
915 // 1. acknowledge interpretation on command,
916 // 2. query current setting on single item,
917 // 3. recursive use for full list.
919 if (requireValue) {
920 cliPrintf("rxfail %u %c %d\r\n",
921 channel,
922 modeCharacter,
923 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
925 } else {
926 cliPrintf("rxfail %u %c\r\n",
927 channel,
928 modeCharacter
931 } else {
932 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
937 static void cliAux(char *cmdline)
939 int i, val = 0;
940 char *ptr;
942 if (isEmpty(cmdline)) {
943 // print out aux channel settings
944 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
945 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
946 cliPrintf("aux %u %u %u %u %u\r\n",
948 mac->modeId,
949 mac->auxChannelIndex,
950 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
951 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
954 } else {
955 ptr = cmdline;
956 i = atoi(ptr++);
957 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
958 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
959 uint8_t validArgumentCount = 0;
960 ptr = strchr(ptr, ' ');
961 if (ptr) {
962 val = atoi(++ptr);
963 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
964 mac->modeId = val;
965 validArgumentCount++;
968 ptr = strchr(ptr, ' ');
969 if (ptr) {
970 val = atoi(++ptr);
971 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
972 mac->auxChannelIndex = val;
973 validArgumentCount++;
976 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
978 if (validArgumentCount != 4) {
979 memset(mac, 0, sizeof(modeActivationCondition_t));
981 } else {
982 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
987 static void cliSerial(char *cmdline)
989 int i, val;
990 char *ptr;
992 if (isEmpty(cmdline)) {
993 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
994 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
995 continue;
997 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
998 masterConfig.serialConfig.portConfigs[i].identifier,
999 masterConfig.serialConfig.portConfigs[i].functionMask,
1000 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
1001 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
1002 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
1003 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
1006 return;
1009 serialPortConfig_t portConfig;
1010 memset(&portConfig, 0 , sizeof(portConfig));
1012 serialPortConfig_t *currentConfig;
1014 uint8_t validArgumentCount = 0;
1016 ptr = cmdline;
1018 val = atoi(ptr++);
1019 currentConfig = serialFindPortConfiguration(val);
1020 if (currentConfig) {
1021 portConfig.identifier = val;
1022 validArgumentCount++;
1025 ptr = strchr(ptr, ' ');
1026 if (ptr) {
1027 val = atoi(++ptr);
1028 portConfig.functionMask = val & 0xFFFF;
1029 validArgumentCount++;
1032 for (i = 0; i < 4; i ++) {
1033 ptr = strchr(ptr, ' ');
1034 if (!ptr) {
1035 break;
1038 val = atoi(++ptr);
1040 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1041 if (baudRates[baudRateIndex] != (uint32_t) val) {
1042 break;
1045 switch(i) {
1046 case 0:
1047 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1048 continue;
1050 portConfig.msp_baudrateIndex = baudRateIndex;
1051 break;
1052 case 1:
1053 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1054 continue;
1056 portConfig.gps_baudrateIndex = baudRateIndex;
1057 break;
1058 case 2:
1059 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1060 continue;
1062 portConfig.telemetry_baudrateIndex = baudRateIndex;
1063 break;
1064 case 3:
1065 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1066 continue;
1068 portConfig.blackbox_baudrateIndex = baudRateIndex;
1069 break;
1072 validArgumentCount++;
1075 if (validArgumentCount < 6) {
1076 cliShowParseError();
1077 return;
1080 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1084 #ifndef SKIP_SERIAL_PASSTHROUGH
1085 static void cliSerialPassthrough(char *cmdline)
1087 if (isEmpty(cmdline)) {
1088 cliShowParseError();
1089 return;
1092 int id = -1;
1093 uint32_t baud = 0;
1094 unsigned mode = 0;
1095 char* tok = strtok(cmdline, " ");
1096 int index = 0;
1098 while (tok != NULL) {
1099 switch(index) {
1100 case 0:
1101 id = atoi(tok);
1102 break;
1103 case 1:
1104 baud = atoi(tok);
1105 break;
1106 case 2:
1107 if (strstr(tok, "rx") || strstr(tok, "RX"))
1108 mode |= MODE_RX;
1109 if (strstr(tok, "tx") || strstr(tok, "TX"))
1110 mode |= MODE_TX;
1111 break;
1113 index++;
1114 tok = strtok(NULL, " ");
1117 serialPort_t *passThroughPort;
1118 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1119 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1120 if (!baud) {
1121 printf("Port %d is not open, you must specify baud\r\n", id);
1122 return;
1124 if (!mode)
1125 mode = MODE_RXTX;
1127 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1128 baud, mode,
1129 SERIAL_NOT_INVERTED);
1130 if (!passThroughPort) {
1131 printf("Port %d could not be opened\r\n", id);
1132 return;
1134 printf("Port %d opened, baud=%d\r\n", id, baud);
1135 } else {
1136 passThroughPort = passThroughPortUsage->serialPort;
1137 // If the user supplied a mode, override the port's mode, otherwise
1138 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1139 printf("Port %d already open\r\n", id);
1140 if (mode && passThroughPort->mode != mode) {
1141 printf("Adjusting mode from configured value %d to %d\r\n",
1142 passThroughPort->mode, mode);
1143 serialSetMode(passThroughPort, mode);
1147 printf("Relaying data to device on port %d, Reset your board to exit "
1148 "serial passthrough mode.\r\n");
1150 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1152 #endif
1154 static void cliAdjustmentRange(char *cmdline)
1156 int i, val = 0;
1157 char *ptr;
1159 if (isEmpty(cmdline)) {
1160 // print out adjustment ranges channel settings
1161 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1162 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1163 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1165 ar->adjustmentIndex,
1166 ar->auxChannelIndex,
1167 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1168 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1169 ar->adjustmentFunction,
1170 ar->auxSwitchChannelIndex
1173 } else {
1174 ptr = cmdline;
1175 i = atoi(ptr++);
1176 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1177 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1178 uint8_t validArgumentCount = 0;
1180 ptr = strchr(ptr, ' ');
1181 if (ptr) {
1182 val = atoi(++ptr);
1183 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1184 ar->adjustmentIndex = val;
1185 validArgumentCount++;
1188 ptr = strchr(ptr, ' ');
1189 if (ptr) {
1190 val = atoi(++ptr);
1191 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1192 ar->auxChannelIndex = val;
1193 validArgumentCount++;
1197 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1199 ptr = strchr(ptr, ' ');
1200 if (ptr) {
1201 val = atoi(++ptr);
1202 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1203 ar->adjustmentFunction = val;
1204 validArgumentCount++;
1207 ptr = strchr(ptr, ' ');
1208 if (ptr) {
1209 val = atoi(++ptr);
1210 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1211 ar->auxSwitchChannelIndex = val;
1212 validArgumentCount++;
1216 if (validArgumentCount != 6) {
1217 memset(ar, 0, sizeof(adjustmentRange_t));
1218 cliShowParseError();
1220 } else {
1221 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1226 static void cliMotorMix(char *cmdline)
1228 #ifdef USE_QUAD_MIXER_ONLY
1229 UNUSED(cmdline);
1230 #else
1231 int i, check = 0;
1232 int num_motors = 0;
1233 uint8_t len;
1234 char buf[16];
1235 char *ptr;
1237 if (isEmpty(cmdline)) {
1238 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1239 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1240 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1241 break;
1242 num_motors++;
1243 cliPrintf("#%d:\t", i);
1244 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1245 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1246 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1247 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1249 return;
1250 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1251 // erase custom mixer
1252 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1253 masterConfig.customMotorMixer[i].throttle = 0.0f;
1254 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1255 ptr = strchr(cmdline, ' ');
1256 if (ptr) {
1257 len = strlen(++ptr);
1258 for (i = 0; ; i++) {
1259 if (mixerNames[i] == NULL) {
1260 cliPrint("Invalid name\r\n");
1261 break;
1263 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1264 mixerLoadMix(i, masterConfig.customMotorMixer);
1265 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1266 cliMotorMix("");
1267 break;
1271 } else {
1272 ptr = cmdline;
1273 i = atoi(ptr); // get motor number
1274 if (i < MAX_SUPPORTED_MOTORS) {
1275 ptr = strchr(ptr, ' ');
1276 if (ptr) {
1277 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1278 check++;
1280 ptr = strchr(ptr, ' ');
1281 if (ptr) {
1282 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1283 check++;
1285 ptr = strchr(ptr, ' ');
1286 if (ptr) {
1287 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1288 check++;
1290 ptr = strchr(ptr, ' ');
1291 if (ptr) {
1292 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1293 check++;
1295 if (check != 4) {
1296 cliShowParseError();
1297 } else {
1298 cliMotorMix("");
1300 } else {
1301 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1304 #endif
1307 static void cliRxRange(char *cmdline)
1309 int i, validArgumentCount = 0;
1310 char *ptr;
1312 if (isEmpty(cmdline)) {
1313 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1314 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1315 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1317 } else if (strcasecmp(cmdline, "reset") == 0) {
1318 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1319 } else {
1320 ptr = cmdline;
1321 i = atoi(ptr);
1322 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1323 int rangeMin, rangeMax;
1325 ptr = strchr(ptr, ' ');
1326 if (ptr) {
1327 rangeMin = atoi(++ptr);
1328 validArgumentCount++;
1331 ptr = strchr(ptr, ' ');
1332 if (ptr) {
1333 rangeMax = atoi(++ptr);
1334 validArgumentCount++;
1337 if (validArgumentCount != 2) {
1338 cliShowParseError();
1339 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1340 cliShowParseError();
1341 } else {
1342 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1343 channelRangeConfiguration->min = rangeMin;
1344 channelRangeConfiguration->max = rangeMax;
1346 } else {
1347 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1352 #ifdef LED_STRIP
1353 static void cliLed(char *cmdline)
1355 int i;
1356 char *ptr;
1357 char ledConfigBuffer[20];
1359 if (isEmpty(cmdline)) {
1360 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1361 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1362 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1364 } else {
1365 ptr = cmdline;
1366 i = atoi(ptr);
1367 if (i < MAX_LED_STRIP_LENGTH) {
1368 ptr = strchr(cmdline, ' ');
1369 if (!parseLedStripConfig(i, ++ptr)) {
1370 cliShowParseError();
1372 } else {
1373 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1378 static void cliColor(char *cmdline)
1380 int i;
1381 char *ptr;
1383 if (isEmpty(cmdline)) {
1384 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1385 cliPrintf("color %u %d,%u,%u\r\n",
1387 masterConfig.colors[i].h,
1388 masterConfig.colors[i].s,
1389 masterConfig.colors[i].v
1392 } else {
1393 ptr = cmdline;
1394 i = atoi(ptr);
1395 if (i < CONFIGURABLE_COLOR_COUNT) {
1396 ptr = strchr(cmdline, ' ');
1397 if (!parseColor(i, ++ptr)) {
1398 cliShowParseError();
1400 } else {
1401 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1405 #endif
1407 #ifdef USE_SERVOS
1408 static void cliServo(char *cmdline)
1410 enum { SERVO_ARGUMENT_COUNT = 8 };
1411 int16_t arguments[SERVO_ARGUMENT_COUNT];
1413 servoParam_t *servo;
1415 int i;
1416 char *ptr;
1418 if (isEmpty(cmdline)) {
1419 // print out servo settings
1420 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1421 servo = &masterConfig.servoConf[i];
1423 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1425 servo->min,
1426 servo->max,
1427 servo->middle,
1428 servo->angleAtMin,
1429 servo->angleAtMax,
1430 servo->rate,
1431 servo->forwardFromChannel
1434 } else {
1435 int validArgumentCount = 0;
1437 ptr = cmdline;
1439 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1441 // If command line doesn't fit the format, don't modify the config
1442 while (*ptr) {
1443 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1444 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1445 cliShowParseError();
1446 return;
1449 arguments[validArgumentCount++] = atoi(ptr);
1451 do {
1452 ptr++;
1453 } while (*ptr >= '0' && *ptr <= '9');
1454 } else if (*ptr == ' ') {
1455 ptr++;
1456 } else {
1457 cliShowParseError();
1458 return;
1462 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1464 i = arguments[INDEX];
1466 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1467 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1468 cliShowParseError();
1469 return;
1472 servo = &masterConfig.servoConf[i];
1474 if (
1475 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1476 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1477 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1478 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1479 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1480 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1481 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1482 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1484 cliShowParseError();
1485 return;
1488 servo->min = arguments[1];
1489 servo->max = arguments[2];
1490 servo->middle = arguments[3];
1491 servo->angleAtMin = arguments[4];
1492 servo->angleAtMax = arguments[5];
1493 servo->rate = arguments[6];
1494 servo->forwardFromChannel = arguments[7];
1497 #endif
1499 #ifdef USE_SERVOS
1500 static void cliServoMix(char *cmdline)
1502 int i;
1503 uint8_t len;
1504 char *ptr;
1505 int args[8], check = 0;
1506 len = strlen(cmdline);
1508 if (len == 0) {
1510 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1512 for (i = 0; i < MAX_SERVO_RULES; i++) {
1513 if (masterConfig.customServoMixer[i].rate == 0)
1514 break;
1516 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1518 masterConfig.customServoMixer[i].targetChannel,
1519 masterConfig.customServoMixer[i].inputSource,
1520 masterConfig.customServoMixer[i].rate,
1521 masterConfig.customServoMixer[i].speed,
1522 masterConfig.customServoMixer[i].min,
1523 masterConfig.customServoMixer[i].max,
1524 masterConfig.customServoMixer[i].box
1527 cliPrintf("\r\n");
1528 return;
1529 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1530 // erase custom mixer
1531 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1532 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1533 masterConfig.servoConf[i].reversedSources = 0;
1535 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1536 ptr = strchr(cmdline, ' ');
1537 if (ptr) {
1538 len = strlen(++ptr);
1539 for (i = 0; ; i++) {
1540 if (mixerNames[i] == NULL) {
1541 cliPrintf("Invalid name\r\n");
1542 break;
1544 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1545 servoMixerLoadMix(i, masterConfig.customServoMixer);
1546 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1547 cliServoMix("");
1548 break;
1552 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1553 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1554 int servoIndex, inputSource;
1555 ptr = strchr(cmdline, ' ');
1557 len = strlen(ptr);
1558 if (len == 0) {
1559 cliPrintf("s");
1560 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1561 cliPrintf("\ti%d", inputSource);
1562 cliPrintf("\r\n");
1564 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1565 cliPrintf("%d", servoIndex);
1566 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1567 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1568 cliPrintf("\r\n");
1570 return;
1573 ptr = strtok(ptr, " ");
1574 while (ptr != NULL && check < ARGS_COUNT - 1) {
1575 args[check++] = atoi(ptr);
1576 ptr = strtok(NULL, " ");
1579 if (ptr == NULL || check != ARGS_COUNT - 1) {
1580 cliShowParseError();
1581 return;
1584 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1585 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1586 && (*ptr == 'r' || *ptr == 'n')) {
1587 if (*ptr == 'r')
1588 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1589 else
1590 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1591 } else
1592 cliShowParseError();
1594 cliServoMix("reverse");
1595 } else {
1596 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1597 ptr = strtok(cmdline, " ");
1598 while (ptr != NULL && check < ARGS_COUNT) {
1599 args[check++] = atoi(ptr);
1600 ptr = strtok(NULL, " ");
1603 if (ptr != NULL || check != ARGS_COUNT) {
1604 cliShowParseError();
1605 return;
1608 i = args[RULE];
1609 if (i >= 0 && i < MAX_SERVO_RULES &&
1610 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1611 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1612 args[RATE] >= -100 && args[RATE] <= 100 &&
1613 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1614 args[MIN] >= 0 && args[MIN] <= 100 &&
1615 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1616 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1617 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1618 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1619 masterConfig.customServoMixer[i].rate = args[RATE];
1620 masterConfig.customServoMixer[i].speed = args[SPEED];
1621 masterConfig.customServoMixer[i].min = args[MIN];
1622 masterConfig.customServoMixer[i].max = args[MAX];
1623 masterConfig.customServoMixer[i].box = args[BOX];
1624 cliServoMix("");
1625 } else {
1626 cliShowParseError();
1630 #endif
1632 #ifdef USE_SDCARD
1634 static void cliWriteBytes(const uint8_t *buffer, int count)
1636 while (count > 0) {
1637 cliWrite(*buffer);
1638 buffer++;
1639 count--;
1643 static void cliSdInfo(char *cmdline) {
1644 UNUSED(cmdline);
1646 cliPrint("SD card: ");
1648 if (!sdcard_isInserted()) {
1649 cliPrint("None inserted\r\n");
1650 return;
1653 if (!sdcard_isInitialized()) {
1654 cliPrint("Startup failed\r\n");
1655 return;
1658 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1660 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1661 metadata->manufacturerID,
1662 metadata->numBlocks / 2, /* One block is half a kB */
1663 metadata->productionMonth,
1664 metadata->productionYear,
1665 metadata->productRevisionMajor,
1666 metadata->productRevisionMinor
1669 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1671 cliPrint("'\r\n" "Filesystem: ");
1673 switch (afatfs_getFilesystemState()) {
1674 case AFATFS_FILESYSTEM_STATE_READY:
1675 cliPrint("Ready");
1676 break;
1677 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1678 cliPrint("Initializing");
1679 break;
1680 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1681 case AFATFS_FILESYSTEM_STATE_FATAL:
1682 cliPrint("Fatal");
1684 switch (afatfs_getLastError()) {
1685 case AFATFS_ERROR_BAD_MBR:
1686 cliPrint(" - no FAT MBR partitions");
1687 break;
1688 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1689 cliPrint(" - bad FAT header");
1690 break;
1691 case AFATFS_ERROR_GENERIC:
1692 case AFATFS_ERROR_NONE:
1693 ; // Nothing more detailed to print
1694 break;
1697 cliPrint("\r\n");
1698 break;
1702 #endif
1704 #ifdef USE_FLASHFS
1706 static void cliFlashInfo(char *cmdline)
1708 const flashGeometry_t *layout = flashfsGetGeometry();
1710 UNUSED(cmdline);
1712 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1713 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1716 static void cliFlashErase(char *cmdline)
1718 UNUSED(cmdline);
1720 cliPrintf("Erasing...\r\n");
1721 flashfsEraseCompletely();
1723 while (!flashfsIsReady()) {
1724 delay(100);
1727 cliPrintf("Done.\r\n");
1730 #ifdef USE_FLASH_TOOLS
1732 static void cliFlashWrite(char *cmdline)
1734 uint32_t address = atoi(cmdline);
1735 char *text = strchr(cmdline, ' ');
1737 if (!text) {
1738 cliShowParseError();
1739 } else {
1740 flashfsSeekAbs(address);
1741 flashfsWrite((uint8_t*)text, strlen(text), true);
1742 flashfsFlushSync();
1744 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1748 static void cliFlashRead(char *cmdline)
1750 uint32_t address = atoi(cmdline);
1751 uint32_t length;
1752 int i;
1754 uint8_t buffer[32];
1756 char *nextArg = strchr(cmdline, ' ');
1758 if (!nextArg) {
1759 cliShowParseError();
1760 } else {
1761 length = atoi(nextArg);
1763 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1765 while (length > 0) {
1766 int bytesRead;
1768 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1770 for (i = 0; i < bytesRead; i++) {
1771 cliWrite(buffer[i]);
1774 length -= bytesRead;
1775 address += bytesRead;
1777 if (bytesRead == 0) {
1778 //Assume we reached the end of the volume or something fatal happened
1779 break;
1782 cliPrintf("\r\n");
1786 #endif
1787 #endif
1789 #ifdef VTX
1790 static void cliVtx(char *cmdline)
1792 int i, val = 0;
1793 char *ptr;
1795 if (isEmpty(cmdline)) {
1796 // print out vtx channel settings
1797 for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
1798 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1799 printf("vtx %u %u %u %u %u %u\r\n",
1801 cac->auxChannelIndex,
1802 cac->band,
1803 cac->channel,
1804 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
1805 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
1808 } else {
1809 ptr = cmdline;
1810 i = atoi(ptr++);
1811 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
1812 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1813 uint8_t validArgumentCount = 0;
1814 ptr = strchr(ptr, ' ');
1815 if (ptr) {
1816 val = atoi(++ptr);
1817 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1818 cac->auxChannelIndex = val;
1819 validArgumentCount++;
1822 ptr = strchr(ptr, ' ');
1823 if (ptr) {
1824 val = atoi(++ptr);
1825 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
1826 cac->band = val;
1827 validArgumentCount++;
1830 ptr = strchr(ptr, ' ');
1831 if (ptr) {
1832 val = atoi(++ptr);
1833 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
1834 cac->channel = val;
1835 validArgumentCount++;
1838 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
1840 if (validArgumentCount != 5) {
1841 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
1843 } else {
1844 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
1848 #endif
1850 static void dumpValues(uint16_t valueSection)
1852 uint32_t i;
1853 const clivalue_t *value;
1854 for (i = 0; i < VALUE_COUNT; i++) {
1855 value = &valueTable[i];
1857 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1858 continue;
1861 cliPrintf("set %s = ", valueTable[i].name);
1862 cliPrintVar(value, 0);
1863 cliPrint("\r\n");
1867 typedef enum {
1868 DUMP_MASTER = (1 << 0),
1869 DUMP_PROFILE = (1 << 1),
1870 DUMP_RATES = (1 << 2),
1871 DUMP_ALL = (1 << 3),
1872 } dumpFlags_e;
1875 static const char* const sectionBreak = "\r\n";
1877 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1879 static void cliDump(char *cmdline)
1881 unsigned int i;
1882 char buf[16];
1883 uint32_t mask;
1885 #ifndef USE_QUAD_MIXER_ONLY
1886 float thr, roll, pitch, yaw;
1887 #endif
1889 uint8_t dumpMask = DUMP_MASTER;
1890 if (strcasecmp(cmdline, "master") == 0) {
1891 dumpMask = DUMP_MASTER; // only
1893 if (strcasecmp(cmdline, "profile") == 0) {
1894 dumpMask = DUMP_PROFILE; // only
1896 if (strcasecmp(cmdline, "rates") == 0) {
1897 dumpMask = DUMP_RATES;
1900 if (strcasecmp(cmdline, "all") == 0) {
1901 dumpMask = DUMP_ALL; // All profiles and rates
1904 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
1906 cliPrint("\r\n# version\r\n");
1907 cliVersion(NULL);
1909 cliPrint("\r\n# dump master\r\n");
1910 cliPrint("\r\n# mixer\r\n");
1912 #ifndef USE_QUAD_MIXER_ONLY
1913 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1915 cliPrintf("mmix reset\r\n");
1917 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1918 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1919 break;
1920 thr = masterConfig.customMotorMixer[i].throttle;
1921 roll = masterConfig.customMotorMixer[i].roll;
1922 pitch = masterConfig.customMotorMixer[i].pitch;
1923 yaw = masterConfig.customMotorMixer[i].yaw;
1924 cliPrintf("mmix %d", i);
1925 if (thr < 0)
1926 cliWrite(' ');
1927 cliPrintf("%s", ftoa(thr, buf));
1928 if (roll < 0)
1929 cliWrite(' ');
1930 cliPrintf("%s", ftoa(roll, buf));
1931 if (pitch < 0)
1932 cliWrite(' ');
1933 cliPrintf("%s", ftoa(pitch, buf));
1934 if (yaw < 0)
1935 cliWrite(' ');
1936 cliPrintf("%s\r\n", ftoa(yaw, buf));
1939 #ifdef USE_SERVOS
1940 // print custom servo mixer if exists
1941 cliPrintf("smix reset\r\n");
1943 for (i = 0; i < MAX_SERVO_RULES; i++) {
1945 if (masterConfig.customServoMixer[i].rate == 0)
1946 break;
1948 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1950 masterConfig.customServoMixer[i].targetChannel,
1951 masterConfig.customServoMixer[i].inputSource,
1952 masterConfig.customServoMixer[i].rate,
1953 masterConfig.customServoMixer[i].speed,
1954 masterConfig.customServoMixer[i].min,
1955 masterConfig.customServoMixer[i].max,
1956 masterConfig.customServoMixer[i].box
1960 #endif
1961 #endif
1963 cliPrint("\r\n\r\n# feature\r\n");
1965 mask = featureMask();
1966 for (i = 0; ; i++) { // disable all feature first
1967 if (featureNames[i] == NULL)
1968 break;
1969 cliPrintf("feature -%s\r\n", featureNames[i]);
1971 for (i = 0; ; i++) { // reenable what we want.
1972 if (featureNames[i] == NULL)
1973 break;
1974 if (mask & (1 << i))
1975 cliPrintf("feature %s\r\n", featureNames[i]);
1979 #ifdef BEEPER
1980 cliPrint("\r\n\r\n# beeper\r\n");
1982 uint8_t beeperCount = beeperTableEntryCount();
1983 mask = getBeeperOffMask();
1984 for (int i = 0; i < (beeperCount-2); i++) {
1985 if (mask & (1 << i))
1986 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
1987 else
1988 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
1990 #endif
1993 cliPrint("\r\n\r\n# map\r\n");
1995 for (i = 0; i < 8; i++)
1996 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1997 buf[i] = '\0';
1998 cliPrintf("map %s\r\n", buf);
2000 cliPrint("\r\n\r\n# serial\r\n");
2001 cliSerial("");
2003 #ifdef LED_STRIP
2004 cliPrint("\r\n\r\n# led\r\n");
2005 cliLed("");
2007 cliPrint("\r\n\r\n# color\r\n");
2008 cliColor("");
2009 #endif
2011 cliPrint("\r\n# aux\r\n");
2013 cliAux("");
2015 cliPrint("\r\n# adjrange\r\n");
2017 cliAdjustmentRange("");
2019 cliPrintf("\r\n# rxrange\r\n");
2021 cliRxRange("");
2023 #ifdef USE_SERVOS
2024 cliPrint("\r\n# servo\r\n");
2026 cliServo("");
2028 // print servo directions
2029 unsigned int channel;
2031 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2032 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2033 if (servoDirection(i, channel) < 0) {
2034 cliPrintf("smix reverse %d %d r\r\n", i , channel);
2038 #endif
2040 #ifdef VTX
2041 cliPrint("\r\n# vtx\r\n");
2043 cliVtx("");
2044 #endif
2046 printSectionBreak();
2047 dumpValues(MASTER_VALUE);
2049 cliPrint("\r\n# rxfail\r\n");
2050 cliRxFail("");
2052 if (dumpMask & DUMP_ALL) {
2053 uint8_t activeProfile = masterConfig.current_profile_index;
2054 uint8_t currentRateIndex = currentProfile->activeRateProfile;
2055 uint8_t profileCount;
2056 uint8_t rateCount;
2057 for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
2058 cliDumpProfile(profileCount);
2059 for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
2060 cliDumpRateProfile(rateCount);
2063 cliPrint("\r\n# restore original profile / rateprofile selection\r\n");
2065 changeProfile(activeProfile);
2066 cliProfile("");
2067 printSectionBreak();
2069 changeControlRateProfile(currentRateIndex);
2070 cliRateProfile("");
2072 cliPrint("\r\n# save configuration\r\nsave\r\n");
2073 } else {
2074 cliDumpProfile(masterConfig.current_profile_index);
2075 cliDumpRateProfile(currentProfile->activeRateProfile);
2079 if (dumpMask & DUMP_PROFILE) {
2080 cliDumpProfile(masterConfig.current_profile_index);
2083 if (dumpMask & DUMP_RATES) {
2084 cliDumpRateProfile(currentProfile->activeRateProfile);
2089 void cliDumpProfile(uint8_t profileIndex) {
2090 if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
2091 return;
2093 changeProfile(profileIndex);
2094 cliPrint("\r\n# profile\r\n");
2095 cliProfile("");
2096 cliPrintf("############################# PROFILE VALUES ####################################\r\n");
2098 printSectionBreak();
2099 dumpValues(PROFILE_VALUE);
2101 cliRateProfile("");
2104 void cliDumpRateProfile(uint8_t rateProfileIndex) {
2105 if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
2106 return;
2108 changeControlRateProfile(rateProfileIndex);
2109 cliPrint("\r\n# rateprofile\r\n");
2110 cliRateProfile("");
2111 printSectionBreak();
2113 dumpValues(PROFILE_RATE_VALUE);
2116 void cliEnter(serialPort_t *serialPort)
2118 cliMode = 1;
2119 cliPort = serialPort;
2120 setPrintfSerialPort(cliPort);
2121 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
2122 (bufWrite_t)serialWriteBufShim, serialPort);
2124 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2125 cliPrompt();
2126 ENABLE_ARMING_FLAG(PREVENT_ARMING);
2129 static void cliExit(char *cmdline)
2131 UNUSED(cmdline);
2133 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2134 bufWriterFlush(cliWriter);
2136 *cliBuffer = '\0';
2137 bufferIndex = 0;
2138 cliMode = 0;
2139 // incase a motor was left running during motortest, clear it here
2140 mixerResetDisarmedMotors();
2141 cliReboot();
2143 cliWriter = NULL;
2146 static void cliFeature(char *cmdline)
2148 uint32_t i;
2149 uint32_t len;
2150 uint32_t mask;
2152 len = strlen(cmdline);
2153 mask = featureMask();
2155 if (len == 0) {
2156 cliPrint("Enabled: ");
2157 for (i = 0; ; i++) {
2158 if (featureNames[i] == NULL)
2159 break;
2160 if (mask & (1 << i))
2161 cliPrintf("%s ", featureNames[i]);
2163 cliPrint("\r\n");
2164 } else if (strncasecmp(cmdline, "list", len) == 0) {
2165 cliPrint("Available: ");
2166 for (i = 0; ; i++) {
2167 if (featureNames[i] == NULL)
2168 break;
2169 cliPrintf("%s ", featureNames[i]);
2171 cliPrint("\r\n");
2172 return;
2173 } else {
2174 bool remove = false;
2175 if (cmdline[0] == '-') {
2176 // remove feature
2177 remove = true;
2178 cmdline++; // skip over -
2179 len--;
2182 for (i = 0; ; i++) {
2183 if (featureNames[i] == NULL) {
2184 cliPrint("Invalid name\r\n");
2185 break;
2188 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2190 mask = 1 << i;
2191 #ifndef GPS
2192 if (mask & FEATURE_GPS) {
2193 cliPrint("unavailable\r\n");
2194 break;
2196 #endif
2197 #ifndef SONAR
2198 if (mask & FEATURE_SONAR) {
2199 cliPrint("unavailable\r\n");
2200 break;
2202 #endif
2203 if (remove) {
2204 featureClear(mask);
2205 cliPrint("Disabled");
2206 } else {
2207 featureSet(mask);
2208 cliPrint("Enabled");
2210 cliPrintf(" %s\r\n", featureNames[i]);
2211 break;
2217 #ifdef BEEPER
2218 static void cliBeeper(char *cmdline)
2220 uint32_t i;
2221 uint32_t len = strlen(cmdline);;
2222 uint8_t beeperCount = beeperTableEntryCount();
2223 uint32_t mask = getBeeperOffMask();
2225 if (len == 0) {
2226 cliPrintf("Disabled:");
2227 for (int i = 0; ; i++) {
2228 if (i == beeperCount-2){
2229 if (mask == 0)
2230 cliPrint(" none");
2231 break;
2233 if (mask & (1 << i))
2234 cliPrintf(" %s", beeperNameForTableIndex(i));
2236 cliPrint("\r\n");
2237 } else if (strncasecmp(cmdline, "list", len) == 0) {
2238 cliPrint("Available:");
2239 for (i = 0; i < beeperCount; i++)
2240 cliPrintf(" %s", beeperNameForTableIndex(i));
2241 cliPrint("\r\n");
2242 return;
2243 } else {
2244 bool remove = false;
2245 if (cmdline[0] == '-') {
2246 remove = true; // this is for beeper OFF condition
2247 cmdline++;
2248 len--;
2251 for (i = 0; ; i++) {
2252 if (i == beeperCount) {
2253 cliPrint("Invalid name\r\n");
2254 break;
2256 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
2257 if (remove) { // beeper off
2258 if (i == BEEPER_ALL-1)
2259 beeperOffSetAll(beeperCount-2);
2260 else
2261 if (i == BEEPER_PREFERENCE-1)
2262 setBeeperOffMask(getPreferredBeeperOffMask());
2263 else {
2264 mask = 1 << i;
2265 beeperOffSet(mask);
2267 cliPrint("Disabled");
2269 else { // beeper on
2270 if (i == BEEPER_ALL-1)
2271 beeperOffClearAll();
2272 else
2273 if (i == BEEPER_PREFERENCE-1)
2274 setPreferredBeeperOffMask(getBeeperOffMask());
2275 else {
2276 mask = 1 << i;
2277 beeperOffClear(mask);
2279 cliPrint("Enabled");
2281 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
2282 break;
2287 #endif
2290 #ifdef GPS
2291 static void cliGpsPassthrough(char *cmdline)
2293 UNUSED(cmdline);
2295 gpsEnablePassthrough(cliPort);
2297 #endif
2299 static void cliHelp(char *cmdline)
2301 uint32_t i = 0;
2303 UNUSED(cmdline);
2305 for (i = 0; i < CMD_COUNT; i++) {
2306 cliPrint(cmdTable[i].name);
2307 #ifndef SKIP_CLI_COMMAND_HELP
2308 if (cmdTable[i].description) {
2309 cliPrintf(" - %s", cmdTable[i].description);
2311 if (cmdTable[i].args) {
2312 cliPrintf("\r\n\t%s", cmdTable[i].args);
2314 #endif
2315 cliPrint("\r\n");
2319 static void cliMap(char *cmdline)
2321 uint32_t len;
2322 uint32_t i;
2323 char out[9];
2325 len = strlen(cmdline);
2327 if (len == 8) {
2328 // uppercase it
2329 for (i = 0; i < 8; i++)
2330 cmdline[i] = toupper((unsigned char)cmdline[i]);
2331 for (i = 0; i < 8; i++) {
2332 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2333 continue;
2334 cliShowParseError();
2335 return;
2337 parseRcChannels(cmdline, &masterConfig.rxConfig);
2339 cliPrint("Map: ");
2340 for (i = 0; i < 8; i++)
2341 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2342 out[i] = '\0';
2343 cliPrintf("%s\r\n", out);
2346 #ifndef USE_QUAD_MIXER_ONLY
2347 static void cliMixer(char *cmdline)
2349 int i;
2350 int len;
2352 len = strlen(cmdline);
2354 if (len == 0) {
2355 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2356 return;
2357 } else if (strncasecmp(cmdline, "list", len) == 0) {
2358 cliPrint("Available mixers: ");
2359 for (i = 0; ; i++) {
2360 if (mixerNames[i] == NULL)
2361 break;
2362 cliPrintf("%s ", mixerNames[i]);
2364 cliPrint("\r\n");
2365 return;
2368 for (i = 0; ; i++) {
2369 if (mixerNames[i] == NULL) {
2370 cliPrint("Invalid name\r\n");
2371 return;
2373 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2374 masterConfig.mixerMode = i + 1;
2375 break;
2379 cliMixer("");
2381 #endif
2383 static void cliMotor(char *cmdline)
2385 int motor_index = 0;
2386 int motor_value = 0;
2387 int index = 0;
2388 char *pch = NULL;
2389 char *saveptr;
2391 if (isEmpty(cmdline)) {
2392 cliShowParseError();
2393 return;
2396 pch = strtok_r(cmdline, " ", &saveptr);
2397 while (pch != NULL) {
2398 switch (index) {
2399 case 0:
2400 motor_index = atoi(pch);
2401 break;
2402 case 1:
2403 motor_value = atoi(pch);
2404 break;
2406 index++;
2407 pch = strtok_r(NULL, " ", &saveptr);
2410 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2411 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2412 return;
2415 if (index == 2) {
2416 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2417 cliShowArgumentRangeError("value", 1000, 2000);
2418 return;
2419 } else {
2420 motor_disarmed[motor_index] = motor_value;
2424 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2427 static void cliPlaySound(char *cmdline)
2429 #if FLASH_SIZE <= 64
2430 UNUSED(cmdline);
2431 #else
2432 int i;
2433 const char *name;
2434 static int lastSoundIdx = -1;
2436 if (isEmpty(cmdline)) {
2437 i = lastSoundIdx + 1; //next sound index
2438 if ((name=beeperNameForTableIndex(i)) == NULL) {
2439 while (true) { //no name for index; try next one
2440 if (++i >= beeperTableEntryCount())
2441 i = 0; //if end then wrap around to first entry
2442 if ((name=beeperNameForTableIndex(i)) != NULL)
2443 break; //if name OK then play sound below
2444 if (i == lastSoundIdx + 1) { //prevent infinite loop
2445 cliPrintf("Error playing sound\r\n");
2446 return;
2450 } else { //index value was given
2451 i = atoi(cmdline);
2452 if ((name=beeperNameForTableIndex(i)) == NULL) {
2453 cliPrintf("No sound for index %d\r\n", i);
2454 return;
2457 lastSoundIdx = i;
2458 beeperSilence();
2459 cliPrintf("Playing sound %d: %s\r\n", i, name);
2460 beeper(beeperModeForTableIndex(i));
2461 #endif
2464 static void cliProfile(char *cmdline)
2466 int i;
2468 if (isEmpty(cmdline)) {
2469 cliPrintf("profile %d\r\n", getCurrentProfile());
2470 return;
2471 } else {
2472 i = atoi(cmdline);
2473 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2474 masterConfig.current_profile_index = i;
2475 writeEEPROM();
2476 readEEPROM();
2477 cliProfile("");
2482 static void cliRateProfile(char *cmdline) {
2483 int i;
2485 if (isEmpty(cmdline)) {
2486 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2487 return;
2488 } else {
2489 i = atoi(cmdline);
2490 if (i >= 0 && i < MAX_RATEPROFILES) {
2491 changeControlRateProfile(i);
2492 cliRateProfile("");
2497 static void cliReboot(void) {
2498 cliPrint("\r\nRebooting");
2499 bufWriterFlush(cliWriter);
2500 waitForSerialPortToFinishTransmitting(cliPort);
2501 stopMotors();
2502 handleOneshotFeatureChangeOnRestart();
2503 systemReset();
2506 static void cliSave(char *cmdline)
2508 UNUSED(cmdline);
2510 cliPrint("Saving");
2511 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2512 writeEEPROM();
2513 cliReboot();
2516 static void cliDefaults(char *cmdline)
2518 UNUSED(cmdline);
2520 cliPrint("Resetting to defaults");
2521 resetEEPROM();
2522 cliReboot();
2525 static void cliPrint(const char *str)
2527 while (*str)
2528 bufWriterAppend(cliWriter, *str++);
2531 static void cliPutp(void *p, char ch)
2533 bufWriterAppend(p, ch);
2536 static void cliPrintf(const char *fmt, ...)
2538 va_list va;
2539 va_start(va, fmt);
2540 tfp_format(cliWriter, cliPutp, fmt, va);
2541 va_end(va);
2544 static void cliWrite(uint8_t ch)
2546 bufWriterAppend(cliWriter, ch);
2549 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2551 int32_t value = 0;
2552 char buf[8];
2554 void *ptr = var->ptr;
2555 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2556 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2559 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2560 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2563 switch (var->type & VALUE_TYPE_MASK) {
2564 case VAR_UINT8:
2565 value = *(uint8_t *)ptr;
2566 break;
2568 case VAR_INT8:
2569 value = *(int8_t *)ptr;
2570 break;
2572 case VAR_UINT16:
2573 value = *(uint16_t *)ptr;
2574 break;
2576 case VAR_INT16:
2577 value = *(int16_t *)ptr;
2578 break;
2580 case VAR_UINT32:
2581 value = *(uint32_t *)ptr;
2582 break;
2584 case VAR_FLOAT:
2585 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2586 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2587 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2588 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2590 return; // return from case for float only
2593 switch(var->type & VALUE_MODE_MASK) {
2594 case MODE_DIRECT:
2595 cliPrintf("%d", value);
2596 if (full) {
2597 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2599 break;
2600 case MODE_LOOKUP:
2601 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2602 break;
2605 static void cliPrintVarRange(const clivalue_t *var)
2607 switch (var->type & VALUE_MODE_MASK) {
2608 case (MODE_DIRECT): {
2609 cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max);
2611 break;
2612 case (MODE_LOOKUP): {
2613 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
2614 cliPrint("Allowed values:");
2615 uint8_t i;
2616 for (i = 0; i < tableEntry->valueCount ; i++) {
2617 if (i > 0)
2618 cliPrint(",");
2619 cliPrintf(" %s", tableEntry->values[i]);
2621 cliPrint("\n");
2623 break;
2626 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2628 void *ptr = var->ptr;
2629 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2630 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2632 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2633 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2636 switch (var->type & VALUE_TYPE_MASK) {
2637 case VAR_UINT8:
2638 case VAR_INT8:
2639 *(int8_t *)ptr = value.int_value;
2640 break;
2642 case VAR_UINT16:
2643 case VAR_INT16:
2644 *(int16_t *)ptr = value.int_value;
2645 break;
2647 case VAR_UINT32:
2648 *(uint32_t *)ptr = value.int_value;
2649 break;
2651 case VAR_FLOAT:
2652 *(float *)ptr = (float)value.float_value;
2653 break;
2657 static void cliSet(char *cmdline)
2659 uint32_t i;
2660 uint32_t len;
2661 const clivalue_t *val;
2662 char *eqptr = NULL;
2664 len = strlen(cmdline);
2666 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2667 cliPrint("Current settings: \r\n");
2668 for (i = 0; i < VALUE_COUNT; i++) {
2669 val = &valueTable[i];
2670 cliPrintf("%s = ", valueTable[i].name);
2671 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2672 cliPrint("\r\n");
2674 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2675 // has equals
2677 char *lastNonSpaceCharacter = eqptr;
2678 while (*(lastNonSpaceCharacter - 1) == ' ') {
2679 lastNonSpaceCharacter--;
2681 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2683 // skip the '=' and any ' ' characters
2684 eqptr++;
2685 while (*(eqptr) == ' ') {
2686 eqptr++;
2689 for (i = 0; i < VALUE_COUNT; i++) {
2690 val = &valueTable[i];
2691 // ensure exact match when setting to prevent setting variables with shorter names
2692 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2694 bool changeValue = false;
2695 int_float_value_t tmp;
2696 switch (valueTable[i].type & VALUE_MODE_MASK) {
2697 case MODE_DIRECT: {
2698 int32_t value = 0;
2699 float valuef = 0;
2701 value = atoi(eqptr);
2702 valuef = fastA2F(eqptr);
2704 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2706 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2707 tmp.float_value = valuef;
2708 else
2709 tmp.int_value = value;
2711 changeValue = true;
2714 break;
2715 case MODE_LOOKUP: {
2716 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2717 bool matched = false;
2718 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2719 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2721 if (matched) {
2722 tmp.int_value = tableValueIndex;
2723 changeValue = true;
2727 break;
2730 if (changeValue) {
2731 cliSetVar(val, tmp);
2733 cliPrintf("%s set to ", valueTable[i].name);
2734 cliPrintVar(val, 0);
2735 } else {
2736 cliPrint("Invalid value\r\n");
2737 cliPrintVarRange(val);
2740 return;
2743 cliPrint("Invalid name\r\n");
2744 } else {
2745 // no equals, check for matching variables.
2746 cliGet(cmdline);
2750 static void cliGet(char *cmdline)
2752 uint32_t i;
2753 const clivalue_t *val;
2754 int matchedCommands = 0;
2756 for (i = 0; i < VALUE_COUNT; i++) {
2757 if (strstr(valueTable[i].name, cmdline)) {
2758 val = &valueTable[i];
2759 cliPrintf("%s = ", valueTable[i].name);
2760 cliPrintVar(val, 0);
2761 cliPrint("\n");
2762 cliPrintVarRange(val);
2763 cliPrint("\r\n");
2765 matchedCommands++;
2770 if (matchedCommands) {
2771 return;
2774 cliPrint("Invalid name\r\n");
2777 static void cliStatus(char *cmdline)
2779 UNUSED(cmdline);
2781 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2782 millis() / 1000,
2783 vbat,
2784 batteryCellCount,
2785 getBatteryStateString(),
2786 constrain(averageSystemLoadPercent, 0, 100)
2789 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2791 #ifndef CJMCU
2792 uint8_t i;
2793 uint32_t mask;
2794 uint32_t detectedSensorsMask = sensorsMask();
2796 for (i = 0; ; i++) {
2798 if (sensorTypeNames[i] == NULL)
2799 break;
2801 mask = (1 << i);
2802 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2803 const char *sensorHardware;
2804 uint8_t sensorHardwareIndex = detectedSensors[i];
2805 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2807 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2809 if (mask == SENSOR_ACC && acc.revisionCode) {
2810 cliPrintf(".%c", acc.revisionCode);
2814 #endif
2815 cliPrint("\r\n");
2817 #ifdef USE_I2C
2818 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2819 #else
2820 uint16_t i2cErrorCounter = 0;
2821 #endif
2823 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2826 #ifndef SKIP_TASK_STATISTICS
2827 static void cliTasks(char *cmdline)
2829 UNUSED(cmdline);
2831 cfTaskId_e taskId;
2832 cfTaskInfo_t taskInfo;
2834 cliPrintf("Task list:\r\n");
2835 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2836 getTaskInfo(taskId, &taskInfo);
2837 if (taskInfo.isEnabled) {
2838 uint16_t taskFrequency;
2839 uint16_t subTaskFrequency;
2841 uint32_t taskTotalTime = taskInfo.totalExecutionTime / 1000;
2843 if (taskId == TASK_GYROPID) {
2844 subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
2845 if (masterConfig.pid_process_denom > 1) {
2846 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
2847 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2848 } else {
2849 taskFrequency = subTaskFrequency;
2850 cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
2852 } else {
2853 taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
2854 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2857 cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
2859 if (taskTotalTime >= 1000) {
2860 cliPrintf("%dsec", taskTotalTime / 1000);
2861 } else {
2862 cliPrintf("%dms", taskTotalTime);
2865 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
2866 cliPrintf("\r\n", taskTotalTime);
2870 #endif
2872 static void cliVersion(char *cmdline)
2874 UNUSED(cmdline);
2876 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
2877 targetName,
2878 FC_VERSION_STRING,
2879 buildDate,
2880 buildTime,
2881 shortGitRevision
2885 void cliProcess(void)
2887 if (!cliWriter) {
2888 return;
2891 // Be a little bit tricky. Flush the last inputs buffer, if any.
2892 bufWriterFlush(cliWriter);
2894 while (serialRxBytesWaiting(cliPort)) {
2895 uint8_t c = serialRead(cliPort);
2896 if (c == '\t' || c == '?') {
2897 // do tab completion
2898 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2899 uint32_t i = bufferIndex;
2900 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2901 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2902 continue;
2903 if (!pstart)
2904 pstart = cmd;
2905 pend = cmd;
2907 if (pstart) { /* Buffer matches one or more commands */
2908 for (; ; bufferIndex++) {
2909 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2910 break;
2911 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2912 /* Unambiguous -- append a space */
2913 cliBuffer[bufferIndex++] = ' ';
2914 cliBuffer[bufferIndex] = '\0';
2915 break;
2917 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2920 if (!bufferIndex || pstart != pend) {
2921 /* Print list of ambiguous matches */
2922 cliPrint("\r\033[K");
2923 for (cmd = pstart; cmd <= pend; cmd++) {
2924 cliPrint(cmd->name);
2925 cliWrite('\t');
2927 cliPrompt();
2928 i = 0; /* Redraw prompt */
2930 for (; i < bufferIndex; i++)
2931 cliWrite(cliBuffer[i]);
2932 } else if (!bufferIndex && c == 4) { // CTRL-D
2933 cliExit(cliBuffer);
2934 return;
2935 } else if (c == 12) { // NewPage / CTRL-L
2936 // clear screen
2937 cliPrint("\033[2J\033[1;1H");
2938 cliPrompt();
2939 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2940 // enter pressed
2941 cliPrint("\r\n");
2943 // Strip comment starting with # from line
2944 char *p = cliBuffer;
2945 p = strchr(p, '#');
2946 if (NULL != p) {
2947 bufferIndex = (uint32_t)(p - cliBuffer);
2950 // Strip trailing whitespace
2951 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2952 bufferIndex--;
2955 // Process non-empty lines
2956 if (bufferIndex > 0) {
2957 cliBuffer[bufferIndex] = 0; // null terminate
2959 const clicmd_t *cmd;
2960 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2961 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2962 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2963 break;
2965 if(cmd < cmdTable + CMD_COUNT)
2966 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2967 else
2968 cliPrint("Unknown command, try 'help'");
2969 bufferIndex = 0;
2972 memset(cliBuffer, 0, sizeof(cliBuffer));
2974 // 'exit' will reset this flag, so we don't need to print prompt again
2975 if (!cliMode)
2976 return;
2978 cliPrompt();
2979 } else if (c == 127) {
2980 // backspace
2981 if (bufferIndex) {
2982 cliBuffer[--bufferIndex] = 0;
2983 cliPrint("\010 \010");
2985 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2986 if (!bufferIndex && c == ' ')
2987 continue; // Ignore leading spaces
2988 cliBuffer[bufferIndex++] = c;
2989 cliWrite(c);
2994 void cliInit(serialConfig_t *serialConfig)
2996 UNUSED(serialConfig);
2998 #endif