Fix data type for gyro lowpass // Defaults
[betaflight.git] / src / main / io / serial_cli.c
blob3f0bb134dc003bebb66d1edb31218addbe6943e4
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"
30 #include "build_config.h"
32 #include "common/axis.h"
33 #include "common/maths.h"
34 #include "common/color.h"
35 #include "common/typeconversion.h"
37 #include "drivers/system.h"
39 #include "drivers/sensor.h"
40 #include "drivers/accgyro.h"
41 #include "drivers/compass.h"
43 #include "drivers/serial.h"
44 #include "drivers/bus_i2c.h"
45 #include "drivers/gpio.h"
46 #include "drivers/timer.h"
47 #include "drivers/pwm_rx.h"
48 #include "drivers/sdcard.h"
49 #include "drivers/gyro_sync.h"
51 #include "drivers/buf_writer.h"
53 #include "io/escservo.h"
54 #include "io/gps.h"
55 #include "io/gimbal.h"
56 #include "io/rc_controls.h"
57 #include "io/serial.h"
58 #include "io/ledstrip.h"
59 #include "io/flashfs.h"
60 #include "io/beeper.h"
61 #include "io/asyncfatfs/asyncfatfs.h"
63 #include "rx/rx.h"
64 #include "rx/spektrum.h"
66 #include "sensors/battery.h"
67 #include "sensors/boardalignment.h"
68 #include "sensors/sensors.h"
69 #include "sensors/acceleration.h"
70 #include "sensors/gyro.h"
71 #include "sensors/compass.h"
72 #include "sensors/barometer.h"
74 #include "flight/pid.h"
75 #include "flight/imu.h"
76 #include "flight/mixer.h"
77 #include "flight/navigation.h"
78 #include "flight/failsafe.h"
80 #include "telemetry/telemetry.h"
81 #include "telemetry/frsky.h"
83 #include "config/runtime_config.h"
84 #include "config/config.h"
85 #include "config/config_profile.h"
86 #include "config/config_master.h"
88 #include "common/printf.h"
90 #include "serial_cli.h"
92 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
93 // signal that we're in cli mode
94 uint8_t cliMode = 0;
96 #ifdef USE_CLI
98 extern uint16_t cycleTime; // FIXME dependency on mw.c
100 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
102 static serialPort_t *cliPort;
103 static bufWriter_t *cliWriter;
104 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
106 static void cliAux(char *cmdline);
107 static void cliRxFail(char *cmdline);
108 static void cliAdjustmentRange(char *cmdline);
109 static void cliMotorMix(char *cmdline);
110 static void cliDefaults(char *cmdline);
111 static void cliDump(char *cmdLine);
112 void cliDumpProfile(uint8_t profileIndex);
113 void cliDumpRateProfile(uint8_t rateProfileIndex) ;
114 static void cliExit(char *cmdline);
115 static void cliFeature(char *cmdline);
116 static void cliMotor(char *cmdline);
117 static void cliPlaySound(char *cmdline);
118 static void cliProfile(char *cmdline);
119 static void cliRateProfile(char *cmdline);
120 static void cliReboot(void);
121 static void cliSave(char *cmdline);
122 static void cliSerial(char *cmdline);
123 #ifndef SKIP_SERIAL_PASSTHROUGH
124 static void cliSerialPassthrough(char *cmdline);
125 #endif
127 #ifdef USE_SERVOS
128 static void cliServo(char *cmdline);
129 static void cliServoMix(char *cmdline);
130 #endif
132 static void cliSet(char *cmdline);
133 static void cliGet(char *cmdline);
134 static void cliStatus(char *cmdline);
135 #ifndef SKIP_TASK_STATISTICS
136 static void cliTasks(char *cmdline);
137 #endif
138 static void cliVersion(char *cmdline);
139 static void cliRxRange(char *cmdline);
141 #ifdef GPS
142 static void cliGpsPassthrough(char *cmdline);
143 #endif
145 static void cliHelp(char *cmdline);
146 static void cliMap(char *cmdline);
148 #ifdef LED_STRIP
149 static void cliLed(char *cmdline);
150 static void cliColor(char *cmdline);
151 #endif
153 #ifndef USE_QUAD_MIXER_ONLY
154 static void cliMixer(char *cmdline);
155 #endif
157 #ifdef USE_FLASHFS
158 static void cliFlashInfo(char *cmdline);
159 static void cliFlashErase(char *cmdline);
160 #ifdef USE_FLASH_TOOLS
161 static void cliFlashWrite(char *cmdline);
162 static void cliFlashRead(char *cmdline);
163 #endif
164 #endif
166 #ifdef USE_SDCARD
167 static void cliSdInfo(char *cmdline);
168 #endif
170 #ifdef BEEPER
171 static void cliBeeper(char *cmdline);
172 #endif
174 // buffer
175 static char cliBuffer[48];
176 static uint32_t bufferIndex = 0;
178 #ifndef USE_QUAD_MIXER_ONLY
179 // sync this with mixerMode_e
180 static const char * const mixerNames[] = {
181 "TRI", "QUADP", "QUADX", "BI",
182 "GIMBAL", "Y6", "HEX6",
183 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
184 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
185 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
186 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
188 #endif
190 // sync this with features_e
191 static const char * const featureNames[] = {
192 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
193 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
194 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
195 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
196 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", NULL
199 // sync this with rxFailsafeChannelMode_e
200 static const char rxFailsafeModeCharacters[] = "ahs";
202 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
203 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
204 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
207 #ifndef CJMCU
208 // sync this with sensors_e
209 static const char * const sensorTypeNames[] = {
210 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
213 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
215 static const char * const sensorHardwareNames[4][11] = {
216 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
217 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
218 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
219 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
221 #endif
223 typedef struct {
224 const char *name;
225 #ifndef SKIP_CLI_COMMAND_HELP
226 const char *description;
227 const char *args;
228 #endif
229 void (*func)(char *cmdline);
230 } clicmd_t;
232 #ifndef SKIP_CLI_COMMAND_HELP
233 #define CLI_COMMAND_DEF(name, description, args, method) \
235 name , \
236 description , \
237 args , \
238 method \
240 #else
241 #define CLI_COMMAND_DEF(name, description, args, method) \
243 name, \
244 method \
246 #endif
248 // should be sorted a..z for bsearch()
249 const clicmd_t cmdTable[] = {
250 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
251 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
252 #ifdef LED_STRIP
253 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
254 #endif
255 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
256 CLI_COMMAND_DEF("dump", "dump configuration",
257 "[master|profile]", cliDump),
258 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
259 CLI_COMMAND_DEF("feature", "configure features",
260 "list\r\n"
261 "\t<+|->[name]", cliFeature),
262 #ifdef USE_FLASHFS
263 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
264 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
265 #ifdef USE_FLASH_TOOLS
266 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
267 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
268 #endif
269 #endif
270 CLI_COMMAND_DEF("get", "get variable value",
271 "[name]", cliGet),
272 #ifdef GPS
273 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
274 #endif
275 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
276 #ifdef LED_STRIP
277 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
278 #endif
279 CLI_COMMAND_DEF("map", "configure rc channel order",
280 "[<map>]", cliMap),
281 #ifndef USE_QUAD_MIXER_ONLY
282 CLI_COMMAND_DEF("mixer", "configure mixer",
283 "list\r\n"
284 "\t<name>", cliMixer),
285 #endif
286 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
287 CLI_COMMAND_DEF("motor", "get/set motor",
288 "<index> [<value>]", cliMotor),
289 CLI_COMMAND_DEF("play_sound", NULL,
290 "[<index>]\r\n", cliPlaySound),
291 CLI_COMMAND_DEF("profile", "change profile",
292 "[<index>]", cliProfile),
293 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
294 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
295 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
296 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
297 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
298 #ifndef SKIP_SERIAL_PASSTHROUGH
299 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
300 "<id> [baud] [mode] : passthrough to serial",
301 cliSerialPassthrough),
302 #endif
303 #ifdef USE_SERVOS
304 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
305 #endif
306 CLI_COMMAND_DEF("set", "change setting",
307 "[<name>=<value>]", cliSet),
308 #ifdef USE_SERVOS
309 CLI_COMMAND_DEF("smix", "servo mixer",
310 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
311 "\treset\r\n"
312 "\tload <mixer>\r\n"
313 "\treverse <servo> <source> r|n", cliServoMix),
314 #endif
315 #ifdef USE_SDCARD
316 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
317 #endif
318 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
319 #ifndef SKIP_TASK_STATISTICS
320 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
321 #endif
322 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
323 #ifdef BEEPER
324 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
325 "\t<+|->[name]", cliBeeper),
326 #endif
328 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
330 static const char * const lookupTableOffOn[] = {
331 "OFF", "ON"
334 static const char * const lookupTableUnit[] = {
335 "IMPERIAL", "METRIC"
338 static const char * const lookupTableAlignment[] = {
339 "DEFAULT",
340 "CW0",
341 "CW90",
342 "CW180",
343 "CW270",
344 "CW0FLIP",
345 "CW90FLIP",
346 "CW180FLIP",
347 "CW270FLIP"
350 #ifdef GPS
351 static const char * const lookupTableGPSProvider[] = {
352 "NMEA", "UBLOX"
355 static const char * const lookupTableGPSSBASMode[] = {
356 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
358 #endif
360 static const char * const lookupTableCurrentSensor[] = {
361 "NONE", "ADC", "VIRTUAL"
364 static const char * const lookupTableGimbalMode[] = {
365 "NORMAL", "MIXTILT"
368 static const char * const lookupTableBlackboxDevice[] = {
369 "SERIAL", "SPIFLASH", "SDCARD"
373 static const char * const lookupTablePidController[] = {
374 "UNUSED", "MWREWRITE", "LUX"
377 static const char * const lookupTableSerialRX[] = {
378 "SPEK1024",
379 "SPEK2048",
380 "SBUS",
381 "SUMD",
382 "SUMH",
383 "XB-B",
384 "XB-B-RJ01",
385 "IBUS",
386 "JETIEXBUS"
389 static const char * const lookupTableGyroLpf[] = {
390 "OFF",
391 "188HZ",
392 "98HZ",
393 "42HZ",
394 "20HZ",
395 "10HZ",
396 "5HZ",
397 "EXPERIMENTAL"
400 static const char * const lookupTableAccHardware[] = {
401 "AUTO",
402 "NONE",
403 "ADXL345",
404 "MPU6050",
405 "MMA8452",
406 "BMA280",
407 "LSM303DLHC",
408 "MPU6000",
409 "MPU6500",
410 "FAKE"
413 static const char * const lookupTableBaroHardware[] = {
414 "AUTO",
415 "NONE",
416 "BMP085",
417 "MS5611",
418 "BMP280"
421 static const char * const lookupTableMagHardware[] = {
422 "AUTO",
423 "NONE",
424 "HMC5883",
425 "AK8975",
426 "AK8963"
429 static const char * const lookupTableDebug[] = {
430 "NONE",
431 "CYCLETIME",
432 "BATTERY",
433 "GYRO",
434 "ACCELEROMETER",
435 "MIXER",
436 "AIRMODE"
439 static const char * const lookupTableSuperExpoYaw[] = {
440 "OFF", "ON", "ALWAYS"
443 typedef struct lookupTableEntry_s {
444 const char * const *values;
445 const uint8_t valueCount;
446 } lookupTableEntry_t;
448 typedef enum {
449 TABLE_OFF_ON = 0,
450 TABLE_UNIT,
451 TABLE_ALIGNMENT,
452 #ifdef GPS
453 TABLE_GPS_PROVIDER,
454 TABLE_GPS_SBAS_MODE,
455 #endif
456 #ifdef BLACKBOX
457 TABLE_BLACKBOX_DEVICE,
458 #endif
459 TABLE_CURRENT_SENSOR,
460 TABLE_GIMBAL_MODE,
461 TABLE_PID_CONTROLLER,
462 TABLE_SERIAL_RX,
463 TABLE_GYRO_LPF,
464 TABLE_ACC_HARDWARE,
465 TABLE_BARO_HARDWARE,
466 TABLE_MAG_HARDWARE,
467 TABLE_DEBUG,
468 TABLE_SUPEREXPO_YAW,
469 } lookupTableIndex_e;
471 static const lookupTableEntry_t lookupTables[] = {
472 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
473 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
474 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
475 #ifdef GPS
476 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
477 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
478 #endif
479 #ifdef BLACKBOX
480 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
481 #endif
482 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
483 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
484 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
485 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
486 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
487 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
488 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
489 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
490 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
491 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }
494 #define VALUE_TYPE_OFFSET 0
495 #define VALUE_SECTION_OFFSET 4
496 #define VALUE_MODE_OFFSET 6
498 typedef enum {
499 // value type
500 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
501 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
502 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
503 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
504 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
505 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
507 // value section
508 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
509 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
510 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
511 // value mode
512 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
513 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
514 } cliValueFlag_e;
516 #define VALUE_TYPE_MASK (0x0F)
517 #define VALUE_SECTION_MASK (0x30)
518 #define VALUE_MODE_MASK (0xC0)
520 typedef struct cliMinMaxConfig_s {
521 const int32_t min;
522 const int32_t max;
523 } cliMinMaxConfig_t;
525 typedef struct cliLookupTableConfig_s {
526 const lookupTableIndex_e tableIndex;
527 } cliLookupTableConfig_t;
529 typedef union {
530 cliLookupTableConfig_t lookup;
531 cliMinMaxConfig_t minmax;
533 } cliValueConfig_t;
535 typedef struct {
536 const char *name;
537 const uint8_t type; // see cliValueFlag_e
538 void *ptr;
539 const cliValueConfig_t config;
540 } clivalue_t;
542 const clivalue_t valueTable[] = {
543 // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
545 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
546 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
547 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
548 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
549 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
550 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
551 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
552 { "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_OFF_ON } },
553 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
554 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
555 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
557 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
558 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
559 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
560 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
562 { "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
563 { "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,
564 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
565 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
567 { "use_oneshot42", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_oneshot42, .config.lookup = { TABLE_OFF_ON } },
568 { "use_multishot", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_multiShot, .config.lookup = { TABLE_OFF_ON } },
569 #ifdef CC3D
570 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
571 #endif
572 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 300, 32000 } },
573 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
575 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
576 { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
577 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
578 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
580 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
582 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
584 #ifdef GPS
585 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
586 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
587 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
588 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
590 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
591 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
592 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
593 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
594 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
595 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
596 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
597 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
598 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
599 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
600 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
601 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
602 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
603 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
604 #endif
605 #ifdef GTUNE
606 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
607 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
608 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
609 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
610 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
611 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
612 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
613 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
614 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
615 #endif
617 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
618 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
619 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
620 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
622 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
623 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
624 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
625 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
626 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
627 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
628 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
629 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
630 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
632 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
633 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
634 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
635 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
636 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
637 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
638 { "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
639 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
640 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
641 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
642 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
644 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
645 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
646 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
648 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
649 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
650 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
652 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
654 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
655 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
656 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
657 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
658 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
659 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
661 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
662 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
663 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
664 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
666 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
667 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
669 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
671 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
672 { "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH } },
673 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
674 #ifdef USE_SERVOS
675 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
676 { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
677 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
678 #endif
680 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
681 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
682 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
683 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
684 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
685 { "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 } },
686 { "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 } },
687 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
688 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
689 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
690 { "super_expo_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactor, .config.minmax = {1, 100 } },
691 { "super_expo_factor_yaw", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.superExpoFactorYaw, .config.minmax = {1, 100 } },
692 { "super_expo_yaw", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.superExpoYawMode, .config.lookup = { TABLE_SUPEREXPO_YAW } },
694 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
695 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
696 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
697 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
698 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
699 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
701 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
702 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
704 #ifdef USE_SERVOS
705 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
706 #endif
708 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
709 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
710 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
711 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
712 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
713 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
714 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
716 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
717 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
718 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
719 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
720 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
722 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
723 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
724 { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
725 { "dynamic_pterm", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dynamic_pterm, .config.lookup = { TABLE_OFF_ON } },
726 { "iterm_always_reset", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.rollPitchItermResetAlways, .config.lookup = { TABLE_OFF_ON } },
727 { "iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermResetRate, .config.minmax = {50, 1000 } },
728 { "yaw_iterm_reset_degrees", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermResetRate, .config.minmax = {25, 1000 } },
729 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
730 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
732 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
734 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
735 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
736 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
737 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
738 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
739 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
740 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
741 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
742 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
744 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
745 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
746 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
748 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
749 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
750 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
752 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
753 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
754 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
756 #ifdef BLACKBOX
757 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
758 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
759 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
760 #endif
762 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
763 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
764 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
767 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
770 typedef union {
771 int32_t int_value;
772 float float_value;
773 } int_float_value_t;
775 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
776 static void cliPrintVar(const clivalue_t *var, uint32_t full);
777 static void cliPrintVarRange(const clivalue_t *var);
778 static void cliPrint(const char *str);
779 static void cliPrintf(const char *fmt, ...);
780 static void cliWrite(uint8_t ch);
782 static void cliPrompt(void)
784 cliPrint("\r\n# ");
785 bufWriterFlush(cliWriter);
788 static void cliShowParseError(void)
790 cliPrint("Parse error\r\n");
793 static void cliShowArgumentRangeError(char *name, int min, int max)
795 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
798 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
800 int val;
802 for (int argIndex = 0; argIndex < 2; argIndex++) {
803 ptr = strchr(ptr, ' ');
804 if (ptr) {
805 val = atoi(++ptr);
806 val = CHANNEL_VALUE_TO_STEP(val);
807 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
808 if (argIndex == 0) {
809 range->startStep = val;
810 } else {
811 range->endStep = val;
813 (*validArgumentCount)++;
818 return ptr;
821 // Check if a string's length is zero
822 static bool isEmpty(const char *string)
824 return *string == '\0';
827 static void cliRxFail(char *cmdline)
829 uint8_t channel;
830 char buf[3];
832 if (isEmpty(cmdline)) {
833 // print out rxConfig failsafe settings
834 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
835 cliRxFail(itoa(channel, buf, 10));
837 } else {
838 char *ptr = cmdline;
839 channel = atoi(ptr++);
840 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
842 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
844 uint16_t value;
845 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
846 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
847 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
849 ptr = strchr(ptr, ' ');
850 if (ptr) {
851 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
852 if (p) {
853 uint8_t requestedMode = p - rxFailsafeModeCharacters;
854 mode = rxFailsafeModesTable[type][requestedMode];
855 } else {
856 mode = RX_FAILSAFE_MODE_INVALID;
858 if (mode == RX_FAILSAFE_MODE_INVALID) {
859 cliShowParseError();
860 return;
863 requireValue = mode == RX_FAILSAFE_MODE_SET;
865 ptr = strchr(ptr, ' ');
866 if (ptr) {
867 if (!requireValue) {
868 cliShowParseError();
869 return;
871 value = atoi(++ptr);
872 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
873 if (value > MAX_RXFAIL_RANGE_STEP) {
874 cliPrint("Value out of range\r\n");
875 return;
878 channelFailsafeConfiguration->step = value;
879 } else if (requireValue) {
880 cliShowParseError();
881 return;
883 channelFailsafeConfiguration->mode = mode;
887 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
889 // triple use of cliPrintf below
890 // 1. acknowledge interpretation on command,
891 // 2. query current setting on single item,
892 // 3. recursive use for full list.
894 if (requireValue) {
895 cliPrintf("rxfail %u %c %d\r\n",
896 channel,
897 modeCharacter,
898 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
900 } else {
901 cliPrintf("rxfail %u %c\r\n",
902 channel,
903 modeCharacter
906 } else {
907 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
912 static void cliAux(char *cmdline)
914 int i, val = 0;
915 char *ptr;
917 if (isEmpty(cmdline)) {
918 // print out aux channel settings
919 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
920 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
921 cliPrintf("aux %u %u %u %u %u\r\n",
923 mac->modeId,
924 mac->auxChannelIndex,
925 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
926 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
929 } else {
930 ptr = cmdline;
931 i = atoi(ptr++);
932 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
933 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
934 uint8_t validArgumentCount = 0;
935 ptr = strchr(ptr, ' ');
936 if (ptr) {
937 val = atoi(++ptr);
938 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
939 mac->modeId = val;
940 validArgumentCount++;
943 ptr = strchr(ptr, ' ');
944 if (ptr) {
945 val = atoi(++ptr);
946 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
947 mac->auxChannelIndex = val;
948 validArgumentCount++;
951 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
953 if (validArgumentCount != 4) {
954 memset(mac, 0, sizeof(modeActivationCondition_t));
956 } else {
957 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
962 static void cliSerial(char *cmdline)
964 int i, val;
965 char *ptr;
967 if (isEmpty(cmdline)) {
968 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
969 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
970 continue;
972 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
973 masterConfig.serialConfig.portConfigs[i].identifier,
974 masterConfig.serialConfig.portConfigs[i].functionMask,
975 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
976 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
977 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
978 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
981 return;
984 serialPortConfig_t portConfig;
985 memset(&portConfig, 0 , sizeof(portConfig));
987 serialPortConfig_t *currentConfig;
989 uint8_t validArgumentCount = 0;
991 ptr = cmdline;
993 val = atoi(ptr++);
994 currentConfig = serialFindPortConfiguration(val);
995 if (currentConfig) {
996 portConfig.identifier = val;
997 validArgumentCount++;
1000 ptr = strchr(ptr, ' ');
1001 if (ptr) {
1002 val = atoi(++ptr);
1003 portConfig.functionMask = val & 0xFFFF;
1004 validArgumentCount++;
1007 for (i = 0; i < 4; i ++) {
1008 ptr = strchr(ptr, ' ');
1009 if (!ptr) {
1010 break;
1013 val = atoi(++ptr);
1015 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1016 if (baudRates[baudRateIndex] != (uint32_t) val) {
1017 break;
1020 switch(i) {
1021 case 0:
1022 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1023 continue;
1025 portConfig.msp_baudrateIndex = baudRateIndex;
1026 break;
1027 case 1:
1028 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1029 continue;
1031 portConfig.gps_baudrateIndex = baudRateIndex;
1032 break;
1033 case 2:
1034 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1035 continue;
1037 portConfig.telemetry_baudrateIndex = baudRateIndex;
1038 break;
1039 case 3:
1040 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1041 continue;
1043 portConfig.blackbox_baudrateIndex = baudRateIndex;
1044 break;
1047 validArgumentCount++;
1050 if (validArgumentCount < 6) {
1051 cliShowParseError();
1052 return;
1055 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1059 #ifndef SKIP_SERIAL_PASSTHROUGH
1060 static void cliSerialPassthrough(char *cmdline)
1062 if (isEmpty(cmdline)) {
1063 cliShowParseError();
1064 return;
1067 int id = -1;
1068 uint32_t baud = 0;
1069 unsigned mode = 0;
1070 char* tok = strtok(cmdline, " ");
1071 int index = 0;
1073 while (tok != NULL) {
1074 switch(index) {
1075 case 0:
1076 id = atoi(tok);
1077 break;
1078 case 1:
1079 baud = atoi(tok);
1080 break;
1081 case 2:
1082 if (strstr(tok, "rx") || strstr(tok, "RX"))
1083 mode |= MODE_RX;
1084 if (strstr(tok, "tx") || strstr(tok, "TX"))
1085 mode |= MODE_TX;
1086 break;
1088 index++;
1089 tok = strtok(NULL, " ");
1092 serialPort_t *passThroughPort;
1093 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1094 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1095 if (!baud) {
1096 printf("Port %d is not open, you must specify baud\r\n", id);
1097 return;
1099 if (!mode)
1100 mode = MODE_RXTX;
1102 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1103 baud, mode,
1104 SERIAL_NOT_INVERTED);
1105 if (!passThroughPort) {
1106 printf("Port %d could not be opened\r\n", id);
1107 return;
1109 printf("Port %d opened, baud=%d\r\n", id, baud);
1110 } else {
1111 passThroughPort = passThroughPortUsage->serialPort;
1112 // If the user supplied a mode, override the port's mode, otherwise
1113 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1114 printf("Port %d already open\r\n", id);
1115 if (mode && passThroughPort->mode != mode) {
1116 printf("Adjusting mode from configured value %d to %d\r\n",
1117 passThroughPort->mode, mode);
1118 serialSetMode(passThroughPort, mode);
1122 printf("Relaying data to device on port %d, Reset your board to exit "
1123 "serial passthrough mode.\r\n");
1125 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1127 #endif
1129 static void cliAdjustmentRange(char *cmdline)
1131 int i, val = 0;
1132 char *ptr;
1134 if (isEmpty(cmdline)) {
1135 // print out adjustment ranges channel settings
1136 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1137 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1138 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1140 ar->adjustmentIndex,
1141 ar->auxChannelIndex,
1142 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1143 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1144 ar->adjustmentFunction,
1145 ar->auxSwitchChannelIndex
1148 } else {
1149 ptr = cmdline;
1150 i = atoi(ptr++);
1151 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1152 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1153 uint8_t validArgumentCount = 0;
1155 ptr = strchr(ptr, ' ');
1156 if (ptr) {
1157 val = atoi(++ptr);
1158 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1159 ar->adjustmentIndex = val;
1160 validArgumentCount++;
1163 ptr = strchr(ptr, ' ');
1164 if (ptr) {
1165 val = atoi(++ptr);
1166 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1167 ar->auxChannelIndex = val;
1168 validArgumentCount++;
1172 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1174 ptr = strchr(ptr, ' ');
1175 if (ptr) {
1176 val = atoi(++ptr);
1177 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1178 ar->adjustmentFunction = val;
1179 validArgumentCount++;
1182 ptr = strchr(ptr, ' ');
1183 if (ptr) {
1184 val = atoi(++ptr);
1185 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1186 ar->auxSwitchChannelIndex = val;
1187 validArgumentCount++;
1191 if (validArgumentCount != 6) {
1192 memset(ar, 0, sizeof(adjustmentRange_t));
1193 cliShowParseError();
1195 } else {
1196 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1201 static void cliMotorMix(char *cmdline)
1203 #ifdef USE_QUAD_MIXER_ONLY
1204 UNUSED(cmdline);
1205 #else
1206 int i, check = 0;
1207 int num_motors = 0;
1208 uint8_t len;
1209 char buf[16];
1210 char *ptr;
1212 if (isEmpty(cmdline)) {
1213 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1214 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1215 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1216 break;
1217 num_motors++;
1218 cliPrintf("#%d:\t", i);
1219 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1220 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1221 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1222 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1224 return;
1225 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1226 // erase custom mixer
1227 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1228 masterConfig.customMotorMixer[i].throttle = 0.0f;
1229 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1230 ptr = strchr(cmdline, ' ');
1231 if (ptr) {
1232 len = strlen(++ptr);
1233 for (i = 0; ; i++) {
1234 if (mixerNames[i] == NULL) {
1235 cliPrint("Invalid name\r\n");
1236 break;
1238 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1239 mixerLoadMix(i, masterConfig.customMotorMixer);
1240 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1241 cliMotorMix("");
1242 break;
1246 } else {
1247 ptr = cmdline;
1248 i = atoi(ptr); // get motor number
1249 if (i < MAX_SUPPORTED_MOTORS) {
1250 ptr = strchr(ptr, ' ');
1251 if (ptr) {
1252 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1253 check++;
1255 ptr = strchr(ptr, ' ');
1256 if (ptr) {
1257 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1258 check++;
1260 ptr = strchr(ptr, ' ');
1261 if (ptr) {
1262 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1263 check++;
1265 ptr = strchr(ptr, ' ');
1266 if (ptr) {
1267 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1268 check++;
1270 if (check != 4) {
1271 cliShowParseError();
1272 } else {
1273 cliMotorMix("");
1275 } else {
1276 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1279 #endif
1282 static void cliRxRange(char *cmdline)
1284 int i, validArgumentCount = 0;
1285 char *ptr;
1287 if (isEmpty(cmdline)) {
1288 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1289 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1290 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1292 } else if (strcasecmp(cmdline, "reset") == 0) {
1293 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1294 } else {
1295 ptr = cmdline;
1296 i = atoi(ptr);
1297 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1298 int rangeMin, rangeMax;
1300 ptr = strchr(ptr, ' ');
1301 if (ptr) {
1302 rangeMin = atoi(++ptr);
1303 validArgumentCount++;
1306 ptr = strchr(ptr, ' ');
1307 if (ptr) {
1308 rangeMax = atoi(++ptr);
1309 validArgumentCount++;
1312 if (validArgumentCount != 2) {
1313 cliShowParseError();
1314 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1315 cliShowParseError();
1316 } else {
1317 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1318 channelRangeConfiguration->min = rangeMin;
1319 channelRangeConfiguration->max = rangeMax;
1321 } else {
1322 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1327 #ifdef LED_STRIP
1328 static void cliLed(char *cmdline)
1330 int i;
1331 char *ptr;
1332 char ledConfigBuffer[20];
1334 if (isEmpty(cmdline)) {
1335 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1336 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1337 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1339 } else {
1340 ptr = cmdline;
1341 i = atoi(ptr);
1342 if (i < MAX_LED_STRIP_LENGTH) {
1343 ptr = strchr(cmdline, ' ');
1344 if (!parseLedStripConfig(i, ++ptr)) {
1345 cliShowParseError();
1347 } else {
1348 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1353 static void cliColor(char *cmdline)
1355 int i;
1356 char *ptr;
1358 if (isEmpty(cmdline)) {
1359 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1360 cliPrintf("color %u %d,%u,%u\r\n",
1362 masterConfig.colors[i].h,
1363 masterConfig.colors[i].s,
1364 masterConfig.colors[i].v
1367 } else {
1368 ptr = cmdline;
1369 i = atoi(ptr);
1370 if (i < CONFIGURABLE_COLOR_COUNT) {
1371 ptr = strchr(cmdline, ' ');
1372 if (!parseColor(i, ++ptr)) {
1373 cliShowParseError();
1375 } else {
1376 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1380 #endif
1382 #ifdef USE_SERVOS
1383 static void cliServo(char *cmdline)
1385 enum { SERVO_ARGUMENT_COUNT = 8 };
1386 int16_t arguments[SERVO_ARGUMENT_COUNT];
1388 servoParam_t *servo;
1390 int i;
1391 char *ptr;
1393 if (isEmpty(cmdline)) {
1394 // print out servo settings
1395 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1396 servo = &masterConfig.servoConf[i];
1398 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1400 servo->min,
1401 servo->max,
1402 servo->middle,
1403 servo->angleAtMin,
1404 servo->angleAtMax,
1405 servo->rate,
1406 servo->forwardFromChannel
1409 } else {
1410 int validArgumentCount = 0;
1412 ptr = cmdline;
1414 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1416 // If command line doesn't fit the format, don't modify the config
1417 while (*ptr) {
1418 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1419 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1420 cliShowParseError();
1421 return;
1424 arguments[validArgumentCount++] = atoi(ptr);
1426 do {
1427 ptr++;
1428 } while (*ptr >= '0' && *ptr <= '9');
1429 } else if (*ptr == ' ') {
1430 ptr++;
1431 } else {
1432 cliShowParseError();
1433 return;
1437 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1439 i = arguments[INDEX];
1441 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1442 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1443 cliShowParseError();
1444 return;
1447 servo = &masterConfig.servoConf[i];
1449 if (
1450 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1451 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1452 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1453 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1454 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1455 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1456 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1457 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1459 cliShowParseError();
1460 return;
1463 servo->min = arguments[1];
1464 servo->max = arguments[2];
1465 servo->middle = arguments[3];
1466 servo->angleAtMin = arguments[4];
1467 servo->angleAtMax = arguments[5];
1468 servo->rate = arguments[6];
1469 servo->forwardFromChannel = arguments[7];
1472 #endif
1474 #ifdef USE_SERVOS
1475 static void cliServoMix(char *cmdline)
1477 int i;
1478 uint8_t len;
1479 char *ptr;
1480 int args[8], check = 0;
1481 len = strlen(cmdline);
1483 if (len == 0) {
1485 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1487 for (i = 0; i < MAX_SERVO_RULES; i++) {
1488 if (masterConfig.customServoMixer[i].rate == 0)
1489 break;
1491 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1493 masterConfig.customServoMixer[i].targetChannel,
1494 masterConfig.customServoMixer[i].inputSource,
1495 masterConfig.customServoMixer[i].rate,
1496 masterConfig.customServoMixer[i].speed,
1497 masterConfig.customServoMixer[i].min,
1498 masterConfig.customServoMixer[i].max,
1499 masterConfig.customServoMixer[i].box
1502 cliPrintf("\r\n");
1503 return;
1504 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1505 // erase custom mixer
1506 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1507 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1508 masterConfig.servoConf[i].reversedSources = 0;
1510 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1511 ptr = strchr(cmdline, ' ');
1512 if (ptr) {
1513 len = strlen(++ptr);
1514 for (i = 0; ; i++) {
1515 if (mixerNames[i] == NULL) {
1516 cliPrintf("Invalid name\r\n");
1517 break;
1519 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1520 servoMixerLoadMix(i, masterConfig.customServoMixer);
1521 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1522 cliServoMix("");
1523 break;
1527 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1528 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1529 int servoIndex, inputSource;
1530 ptr = strchr(cmdline, ' ');
1532 len = strlen(ptr);
1533 if (len == 0) {
1534 cliPrintf("s");
1535 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1536 cliPrintf("\ti%d", inputSource);
1537 cliPrintf("\r\n");
1539 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1540 cliPrintf("%d", servoIndex);
1541 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1542 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1543 cliPrintf("\r\n");
1545 return;
1548 ptr = strtok(ptr, " ");
1549 while (ptr != NULL && check < ARGS_COUNT - 1) {
1550 args[check++] = atoi(ptr);
1551 ptr = strtok(NULL, " ");
1554 if (ptr == NULL || check != ARGS_COUNT - 1) {
1555 cliShowParseError();
1556 return;
1559 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1560 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1561 && (*ptr == 'r' || *ptr == 'n')) {
1562 if (*ptr == 'r')
1563 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1564 else
1565 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1566 } else
1567 cliShowParseError();
1569 cliServoMix("reverse");
1570 } else {
1571 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1572 ptr = strtok(cmdline, " ");
1573 while (ptr != NULL && check < ARGS_COUNT) {
1574 args[check++] = atoi(ptr);
1575 ptr = strtok(NULL, " ");
1578 if (ptr != NULL || check != ARGS_COUNT) {
1579 cliShowParseError();
1580 return;
1583 i = args[RULE];
1584 if (i >= 0 && i < MAX_SERVO_RULES &&
1585 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1586 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1587 args[RATE] >= -100 && args[RATE] <= 100 &&
1588 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1589 args[MIN] >= 0 && args[MIN] <= 100 &&
1590 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1591 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1592 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1593 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1594 masterConfig.customServoMixer[i].rate = args[RATE];
1595 masterConfig.customServoMixer[i].speed = args[SPEED];
1596 masterConfig.customServoMixer[i].min = args[MIN];
1597 masterConfig.customServoMixer[i].max = args[MAX];
1598 masterConfig.customServoMixer[i].box = args[BOX];
1599 cliServoMix("");
1600 } else {
1601 cliShowParseError();
1605 #endif
1607 #ifdef USE_SDCARD
1609 static void cliWriteBytes(const uint8_t *buffer, int count)
1611 while (count > 0) {
1612 cliWrite(*buffer);
1613 buffer++;
1614 count--;
1618 static void cliSdInfo(char *cmdline) {
1619 UNUSED(cmdline);
1621 cliPrint("SD card: ");
1623 if (!sdcard_isInserted()) {
1624 cliPrint("None inserted\r\n");
1625 return;
1628 if (!sdcard_isInitialized()) {
1629 cliPrint("Startup failed\r\n");
1630 return;
1633 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1635 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1636 metadata->manufacturerID,
1637 metadata->numBlocks / 2, /* One block is half a kB */
1638 metadata->productionMonth,
1639 metadata->productionYear,
1640 metadata->productRevisionMajor,
1641 metadata->productRevisionMinor
1644 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1646 cliPrint("'\r\n" "Filesystem: ");
1648 switch (afatfs_getFilesystemState()) {
1649 case AFATFS_FILESYSTEM_STATE_READY:
1650 cliPrint("Ready");
1651 break;
1652 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1653 cliPrint("Initializing");
1654 break;
1655 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1656 case AFATFS_FILESYSTEM_STATE_FATAL:
1657 cliPrint("Fatal");
1659 switch (afatfs_getLastError()) {
1660 case AFATFS_ERROR_BAD_MBR:
1661 cliPrint(" - no FAT MBR partitions");
1662 break;
1663 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1664 cliPrint(" - bad FAT header");
1665 break;
1666 case AFATFS_ERROR_GENERIC:
1667 case AFATFS_ERROR_NONE:
1668 ; // Nothing more detailed to print
1669 break;
1672 cliPrint("\r\n");
1673 break;
1677 #endif
1679 #ifdef USE_FLASHFS
1681 static void cliFlashInfo(char *cmdline)
1683 const flashGeometry_t *layout = flashfsGetGeometry();
1685 UNUSED(cmdline);
1687 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1688 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1691 static void cliFlashErase(char *cmdline)
1693 UNUSED(cmdline);
1695 cliPrintf("Erasing...\r\n");
1696 flashfsEraseCompletely();
1698 while (!flashfsIsReady()) {
1699 delay(100);
1702 cliPrintf("Done.\r\n");
1705 #ifdef USE_FLASH_TOOLS
1707 static void cliFlashWrite(char *cmdline)
1709 uint32_t address = atoi(cmdline);
1710 char *text = strchr(cmdline, ' ');
1712 if (!text) {
1713 cliShowParseError();
1714 } else {
1715 flashfsSeekAbs(address);
1716 flashfsWrite((uint8_t*)text, strlen(text), true);
1717 flashfsFlushSync();
1719 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1723 static void cliFlashRead(char *cmdline)
1725 uint32_t address = atoi(cmdline);
1726 uint32_t length;
1727 int i;
1729 uint8_t buffer[32];
1731 char *nextArg = strchr(cmdline, ' ');
1733 if (!nextArg) {
1734 cliShowParseError();
1735 } else {
1736 length = atoi(nextArg);
1738 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1740 while (length > 0) {
1741 int bytesRead;
1743 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1745 for (i = 0; i < bytesRead; i++) {
1746 cliWrite(buffer[i]);
1749 length -= bytesRead;
1750 address += bytesRead;
1752 if (bytesRead == 0) {
1753 //Assume we reached the end of the volume or something fatal happened
1754 break;
1757 cliPrintf("\r\n");
1761 #endif
1762 #endif
1764 static void dumpValues(uint16_t valueSection)
1766 uint32_t i;
1767 const clivalue_t *value;
1768 for (i = 0; i < VALUE_COUNT; i++) {
1769 value = &valueTable[i];
1771 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1772 continue;
1775 cliPrintf("set %s = ", valueTable[i].name);
1776 cliPrintVar(value, 0);
1777 cliPrint("\r\n");
1781 typedef enum {
1782 DUMP_MASTER = (1 << 0),
1783 DUMP_PROFILE = (1 << 1),
1784 DUMP_RATES = (1 << 2),
1785 DUMP_ALL = (1 << 3),
1786 } dumpFlags_e;
1789 static const char* const sectionBreak = "\r\n";
1791 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1793 static void cliDump(char *cmdline)
1795 unsigned int i;
1796 char buf[16];
1797 uint32_t mask;
1799 #ifndef USE_QUAD_MIXER_ONLY
1800 float thr, roll, pitch, yaw;
1801 #endif
1803 uint8_t dumpMask = DUMP_MASTER;
1804 if (strcasecmp(cmdline, "master") == 0) {
1805 dumpMask = DUMP_MASTER; // only
1807 if (strcasecmp(cmdline, "profile") == 0) {
1808 dumpMask = DUMP_PROFILE; // only
1810 if (strcasecmp(cmdline, "rates") == 0) {
1811 dumpMask = DUMP_RATES;
1814 if (strcasecmp(cmdline, "all") == 0) {
1815 dumpMask = DUMP_ALL; // All profiles and rates
1818 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
1820 cliPrint("\r\n# version\r\n");
1821 cliVersion(NULL);
1823 cliPrint("\r\n# dump master\r\n");
1824 cliPrint("\r\n# mixer\r\n");
1826 #ifndef USE_QUAD_MIXER_ONLY
1827 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1829 cliPrintf("mmix reset\r\n");
1831 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1832 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1833 break;
1834 thr = masterConfig.customMotorMixer[i].throttle;
1835 roll = masterConfig.customMotorMixer[i].roll;
1836 pitch = masterConfig.customMotorMixer[i].pitch;
1837 yaw = masterConfig.customMotorMixer[i].yaw;
1838 cliPrintf("mmix %d", i);
1839 if (thr < 0)
1840 cliWrite(' ');
1841 cliPrintf("%s", ftoa(thr, buf));
1842 if (roll < 0)
1843 cliWrite(' ');
1844 cliPrintf("%s", ftoa(roll, buf));
1845 if (pitch < 0)
1846 cliWrite(' ');
1847 cliPrintf("%s", ftoa(pitch, buf));
1848 if (yaw < 0)
1849 cliWrite(' ');
1850 cliPrintf("%s\r\n", ftoa(yaw, buf));
1853 #ifdef USE_SERVOS
1854 // print custom servo mixer if exists
1855 cliPrintf("smix reset\r\n");
1857 for (i = 0; i < MAX_SERVO_RULES; i++) {
1859 if (masterConfig.customServoMixer[i].rate == 0)
1860 break;
1862 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1864 masterConfig.customServoMixer[i].targetChannel,
1865 masterConfig.customServoMixer[i].inputSource,
1866 masterConfig.customServoMixer[i].rate,
1867 masterConfig.customServoMixer[i].speed,
1868 masterConfig.customServoMixer[i].min,
1869 masterConfig.customServoMixer[i].max,
1870 masterConfig.customServoMixer[i].box
1874 #endif
1875 #endif
1877 cliPrint("\r\n\r\n# feature\r\n");
1879 mask = featureMask();
1880 for (i = 0; ; i++) { // disable all feature first
1881 if (featureNames[i] == NULL)
1882 break;
1883 cliPrintf("feature -%s\r\n", featureNames[i]);
1885 for (i = 0; ; i++) { // reenable what we want.
1886 if (featureNames[i] == NULL)
1887 break;
1888 if (mask & (1 << i))
1889 cliPrintf("feature %s\r\n", featureNames[i]);
1893 #ifdef BEEPER
1894 cliPrint("\r\n\r\n# beeper\r\n");
1896 uint8_t beeperCount = beeperTableEntryCount();
1897 mask = getBeeperOffMask();
1898 for (int i = 0; i < (beeperCount-2); i++) {
1899 if (mask & (1 << i))
1900 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
1901 else
1902 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
1904 #endif
1907 cliPrint("\r\n\r\n# map\r\n");
1909 for (i = 0; i < 8; i++)
1910 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1911 buf[i] = '\0';
1912 cliPrintf("map %s\r\n", buf);
1914 cliPrint("\r\n\r\n# serial\r\n");
1915 cliSerial("");
1917 #ifdef LED_STRIP
1918 cliPrint("\r\n\r\n# led\r\n");
1919 cliLed("");
1921 cliPrint("\r\n\r\n# color\r\n");
1922 cliColor("");
1923 #endif
1925 cliPrint("\r\n# aux\r\n");
1927 cliAux("");
1929 cliPrint("\r\n# adjrange\r\n");
1931 cliAdjustmentRange("");
1933 cliPrintf("\r\n# rxrange\r\n");
1935 cliRxRange("");
1937 #ifdef USE_SERVOS
1938 cliPrint("\r\n# servo\r\n");
1940 cliServo("");
1942 // print servo directions
1943 unsigned int channel;
1945 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1946 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
1947 if (servoDirection(i, channel) < 0) {
1948 cliPrintf("smix reverse %d %d r\r\n", i , channel);
1952 #endif
1954 printSectionBreak();
1955 dumpValues(MASTER_VALUE);
1957 cliPrint("\r\n# rxfail\r\n");
1958 cliRxFail("");
1960 if (dumpMask & DUMP_ALL) {
1961 uint8_t activeProfile = masterConfig.current_profile_index;
1962 uint8_t currentRateIndex = currentProfile->activeRateProfile;
1963 uint8_t profileCount;
1964 uint8_t rateCount;
1965 for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
1966 cliDumpProfile(profileCount);
1967 for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
1968 cliDumpRateProfile(rateCount);
1971 changeProfile(activeProfile);
1972 changeControlRateProfile(currentRateIndex);
1973 } else {
1974 cliDumpProfile(masterConfig.current_profile_index);
1975 cliDumpRateProfile(currentProfile->activeRateProfile);
1979 if (dumpMask & DUMP_PROFILE) {
1980 cliDumpProfile(masterConfig.current_profile_index);
1983 if (dumpMask & DUMP_RATES) {
1984 cliDumpRateProfile(currentProfile->activeRateProfile);
1989 void cliDumpProfile(uint8_t profileIndex) {
1990 if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
1991 return;
1993 changeProfile(profileIndex);
1994 cliPrint("\r\n# profile\r\n");
1995 cliProfile("");
1996 cliPrintf("############################# PROFILE VALUES ####################################\r\n");
1997 cliProfile("");
1998 printSectionBreak();
1999 dumpValues(PROFILE_VALUE);
2001 cliRateProfile("");
2003 void cliDumpRateProfile(uint8_t rateProfileIndex) {
2004 if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
2005 return;
2007 changeControlRateProfile(rateProfileIndex);
2008 cliPrint("\r\n# rateprofile\r\n");
2009 cliRateProfile("");
2010 printSectionBreak();
2012 dumpValues(PROFILE_RATE_VALUE);
2015 void cliEnter(serialPort_t *serialPort)
2017 cliMode = 1;
2018 cliPort = serialPort;
2019 setPrintfSerialPort(cliPort);
2020 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
2021 (bufWrite_t)serialWriteBufShim, serialPort);
2023 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2024 cliPrompt();
2025 ENABLE_ARMING_FLAG(PREVENT_ARMING);
2028 static void cliExit(char *cmdline)
2030 UNUSED(cmdline);
2032 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2033 bufWriterFlush(cliWriter);
2035 *cliBuffer = '\0';
2036 bufferIndex = 0;
2037 cliMode = 0;
2038 // incase a motor was left running during motortest, clear it here
2039 mixerResetDisarmedMotors();
2040 cliReboot();
2042 cliWriter = NULL;
2045 static void cliFeature(char *cmdline)
2047 uint32_t i;
2048 uint32_t len;
2049 uint32_t mask;
2051 len = strlen(cmdline);
2052 mask = featureMask();
2054 if (len == 0) {
2055 cliPrint("Enabled: ");
2056 for (i = 0; ; i++) {
2057 if (featureNames[i] == NULL)
2058 break;
2059 if (mask & (1 << i))
2060 cliPrintf("%s ", featureNames[i]);
2062 cliPrint("\r\n");
2063 } else if (strncasecmp(cmdline, "list", len) == 0) {
2064 cliPrint("Available: ");
2065 for (i = 0; ; i++) {
2066 if (featureNames[i] == NULL)
2067 break;
2068 cliPrintf("%s ", featureNames[i]);
2070 cliPrint("\r\n");
2071 return;
2072 } else {
2073 bool remove = false;
2074 if (cmdline[0] == '-') {
2075 // remove feature
2076 remove = true;
2077 cmdline++; // skip over -
2078 len--;
2081 for (i = 0; ; i++) {
2082 if (featureNames[i] == NULL) {
2083 cliPrint("Invalid name\r\n");
2084 break;
2087 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2089 mask = 1 << i;
2090 #ifndef GPS
2091 if (mask & FEATURE_GPS) {
2092 cliPrint("unavailable\r\n");
2093 break;
2095 #endif
2096 #ifndef SONAR
2097 if (mask & FEATURE_SONAR) {
2098 cliPrint("unavailable\r\n");
2099 break;
2101 #endif
2102 if (remove) {
2103 featureClear(mask);
2104 cliPrint("Disabled");
2105 } else {
2106 featureSet(mask);
2107 cliPrint("Enabled");
2109 cliPrintf(" %s\r\n", featureNames[i]);
2110 break;
2116 #ifdef BEEPER
2117 static void cliBeeper(char *cmdline)
2119 uint32_t i;
2120 uint32_t len = strlen(cmdline);;
2121 uint8_t beeperCount = beeperTableEntryCount();
2122 uint32_t mask = getBeeperOffMask();
2124 if (len == 0) {
2125 cliPrintf("Disabled:");
2126 for (int i = 0; ; i++) {
2127 if (i == beeperCount-2){
2128 if (mask == 0)
2129 cliPrint(" none");
2130 break;
2132 if (mask & (1 << i))
2133 cliPrintf(" %s", beeperNameForTableIndex(i));
2135 cliPrint("\r\n");
2136 } else if (strncasecmp(cmdline, "list", len) == 0) {
2137 cliPrint("Available:");
2138 for (i = 0; i < beeperCount; i++)
2139 cliPrintf(" %s", beeperNameForTableIndex(i));
2140 cliPrint("\r\n");
2141 return;
2142 } else {
2143 bool remove = false;
2144 if (cmdline[0] == '-') {
2145 remove = true; // this is for beeper OFF condition
2146 cmdline++;
2147 len--;
2150 for (i = 0; ; i++) {
2151 if (i == beeperCount) {
2152 cliPrint("Invalid name\r\n");
2153 break;
2155 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
2156 if (remove) { // beeper off
2157 if (i == BEEPER_ALL-1)
2158 beeperOffSetAll(beeperCount-2);
2159 else
2160 if (i == BEEPER_PREFERENCE-1)
2161 setBeeperOffMask(getPreferedBeeperOffMask());
2162 else {
2163 mask = 1 << i;
2164 beeperOffSet(mask);
2166 cliPrint("Disabled");
2168 else { // beeper on
2169 if (i == BEEPER_ALL-1)
2170 beeperOffClearAll();
2171 else
2172 if (i == BEEPER_PREFERENCE-1)
2173 setPreferedBeeperOffMask(getBeeperOffMask());
2174 else {
2175 mask = 1 << i;
2176 beeperOffClear(mask);
2178 cliPrint("Enabled");
2180 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
2181 break;
2186 #endif
2189 #ifdef GPS
2190 static void cliGpsPassthrough(char *cmdline)
2192 UNUSED(cmdline);
2194 gpsEnablePassthrough(cliPort);
2196 #endif
2198 static void cliHelp(char *cmdline)
2200 uint32_t i = 0;
2202 UNUSED(cmdline);
2204 for (i = 0; i < CMD_COUNT; i++) {
2205 cliPrint(cmdTable[i].name);
2206 #ifndef SKIP_CLI_COMMAND_HELP
2207 if (cmdTable[i].description) {
2208 cliPrintf(" - %s", cmdTable[i].description);
2210 if (cmdTable[i].args) {
2211 cliPrintf("\r\n\t%s", cmdTable[i].args);
2213 #endif
2214 cliPrint("\r\n");
2218 static void cliMap(char *cmdline)
2220 uint32_t len;
2221 uint32_t i;
2222 char out[9];
2224 len = strlen(cmdline);
2226 if (len == 8) {
2227 // uppercase it
2228 for (i = 0; i < 8; i++)
2229 cmdline[i] = toupper((unsigned char)cmdline[i]);
2230 for (i = 0; i < 8; i++) {
2231 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2232 continue;
2233 cliShowParseError();
2234 return;
2236 parseRcChannels(cmdline, &masterConfig.rxConfig);
2238 cliPrint("Map: ");
2239 for (i = 0; i < 8; i++)
2240 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2241 out[i] = '\0';
2242 cliPrintf("%s\r\n", out);
2245 #ifndef USE_QUAD_MIXER_ONLY
2246 static void cliMixer(char *cmdline)
2248 int i;
2249 int len;
2251 len = strlen(cmdline);
2253 if (len == 0) {
2254 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2255 return;
2256 } else if (strncasecmp(cmdline, "list", len) == 0) {
2257 cliPrint("Available mixers: ");
2258 for (i = 0; ; i++) {
2259 if (mixerNames[i] == NULL)
2260 break;
2261 cliPrintf("%s ", mixerNames[i]);
2263 cliPrint("\r\n");
2264 return;
2267 for (i = 0; ; i++) {
2268 if (mixerNames[i] == NULL) {
2269 cliPrint("Invalid name\r\n");
2270 return;
2272 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2273 masterConfig.mixerMode = i + 1;
2274 break;
2278 cliMixer("");
2280 #endif
2282 static void cliMotor(char *cmdline)
2284 int motor_index = 0;
2285 int motor_value = 0;
2286 int index = 0;
2287 char *pch = NULL;
2288 char *saveptr;
2290 if (isEmpty(cmdline)) {
2291 cliShowParseError();
2292 return;
2295 pch = strtok_r(cmdline, " ", &saveptr);
2296 while (pch != NULL) {
2297 switch (index) {
2298 case 0:
2299 motor_index = atoi(pch);
2300 break;
2301 case 1:
2302 motor_value = atoi(pch);
2303 break;
2305 index++;
2306 pch = strtok_r(NULL, " ", &saveptr);
2309 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2310 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2311 return;
2314 if (index == 2) {
2315 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2316 cliShowArgumentRangeError("value", 1000, 2000);
2317 return;
2318 } else {
2319 motor_disarmed[motor_index] = motor_value;
2323 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2326 static void cliPlaySound(char *cmdline)
2328 #if FLASH_SIZE <= 64
2329 UNUSED(cmdline);
2330 #else
2331 int i;
2332 const char *name;
2333 static int lastSoundIdx = -1;
2335 if (isEmpty(cmdline)) {
2336 i = lastSoundIdx + 1; //next sound index
2337 if ((name=beeperNameForTableIndex(i)) == NULL) {
2338 while (true) { //no name for index; try next one
2339 if (++i >= beeperTableEntryCount())
2340 i = 0; //if end then wrap around to first entry
2341 if ((name=beeperNameForTableIndex(i)) != NULL)
2342 break; //if name OK then play sound below
2343 if (i == lastSoundIdx + 1) { //prevent infinite loop
2344 cliPrintf("Error playing sound\r\n");
2345 return;
2349 } else { //index value was given
2350 i = atoi(cmdline);
2351 if ((name=beeperNameForTableIndex(i)) == NULL) {
2352 cliPrintf("No sound for index %d\r\n", i);
2353 return;
2356 lastSoundIdx = i;
2357 beeperSilence();
2358 cliPrintf("Playing sound %d: %s\r\n", i, name);
2359 beeper(beeperModeForTableIndex(i));
2360 #endif
2363 static void cliProfile(char *cmdline)
2365 int i;
2367 if (isEmpty(cmdline)) {
2368 cliPrintf("profile %d\r\n", getCurrentProfile());
2369 return;
2370 } else {
2371 i = atoi(cmdline);
2372 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2373 masterConfig.current_profile_index = i;
2374 writeEEPROM();
2375 readEEPROM();
2376 cliProfile("");
2381 static void cliRateProfile(char *cmdline) {
2382 int i;
2384 if (isEmpty(cmdline)) {
2385 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2386 return;
2387 } else {
2388 i = atoi(cmdline);
2389 if (i >= 0 && i < MAX_RATEPROFILES) {
2390 changeControlRateProfile(i);
2391 cliRateProfile("");
2396 static void cliReboot(void) {
2397 cliPrint("\r\nRebooting");
2398 bufWriterFlush(cliWriter);
2399 waitForSerialPortToFinishTransmitting(cliPort);
2400 stopMotors();
2401 handleOneshotFeatureChangeOnRestart();
2402 systemReset();
2405 static void cliSave(char *cmdline)
2407 UNUSED(cmdline);
2409 cliPrint("Saving");
2410 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2411 writeEEPROM();
2412 cliReboot();
2415 static void cliDefaults(char *cmdline)
2417 UNUSED(cmdline);
2419 cliPrint("Resetting to defaults");
2420 resetEEPROM();
2421 cliReboot();
2424 static void cliPrint(const char *str)
2426 while (*str)
2427 bufWriterAppend(cliWriter, *str++);
2430 static void cliPutp(void *p, char ch)
2432 bufWriterAppend(p, ch);
2435 static void cliPrintf(const char *fmt, ...)
2437 va_list va;
2438 va_start(va, fmt);
2439 tfp_format(cliWriter, cliPutp, fmt, va);
2440 va_end(va);
2443 static void cliWrite(uint8_t ch)
2445 bufWriterAppend(cliWriter, ch);
2448 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2450 int32_t value = 0;
2451 char buf[8];
2453 void *ptr = var->ptr;
2454 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2455 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2458 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2459 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2462 switch (var->type & VALUE_TYPE_MASK) {
2463 case VAR_UINT8:
2464 value = *(uint8_t *)ptr;
2465 break;
2467 case VAR_INT8:
2468 value = *(int8_t *)ptr;
2469 break;
2471 case VAR_UINT16:
2472 value = *(uint16_t *)ptr;
2473 break;
2475 case VAR_INT16:
2476 value = *(int16_t *)ptr;
2477 break;
2479 case VAR_UINT32:
2480 value = *(uint32_t *)ptr;
2481 break;
2483 case VAR_FLOAT:
2484 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2485 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2486 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2487 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2489 return; // return from case for float only
2492 switch(var->type & VALUE_MODE_MASK) {
2493 case MODE_DIRECT:
2494 cliPrintf("%d", value);
2495 if (full) {
2496 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2498 break;
2499 case MODE_LOOKUP:
2500 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2501 break;
2504 static void cliPrintVarRange(const clivalue_t *var)
2506 switch (var->type & VALUE_MODE_MASK) {
2507 case (MODE_DIRECT): {
2508 cliPrintf("Allowed range: %d - %d\n", var->config.minmax.min, var->config.minmax.max);
2510 break;
2511 case (MODE_LOOKUP): {
2512 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
2513 cliPrint("Allowed values:");
2514 uint8_t i;
2515 for (i = 0; i < tableEntry->valueCount ; i++) {
2516 if (i > 0)
2517 cliPrint(",");
2518 cliPrintf(" %s", tableEntry->values[i]);
2520 cliPrint("\n");
2522 break;
2525 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2527 void *ptr = var->ptr;
2528 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2529 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2531 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2532 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2535 switch (var->type & VALUE_TYPE_MASK) {
2536 case VAR_UINT8:
2537 case VAR_INT8:
2538 *(int8_t *)ptr = value.int_value;
2539 break;
2541 case VAR_UINT16:
2542 case VAR_INT16:
2543 *(int16_t *)ptr = value.int_value;
2544 break;
2546 case VAR_UINT32:
2547 *(uint32_t *)ptr = value.int_value;
2548 break;
2550 case VAR_FLOAT:
2551 *(float *)ptr = (float)value.float_value;
2552 break;
2556 static void cliSet(char *cmdline)
2558 uint32_t i;
2559 uint32_t len;
2560 const clivalue_t *val;
2561 char *eqptr = NULL;
2563 len = strlen(cmdline);
2565 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2566 cliPrint("Current settings: \r\n");
2567 for (i = 0; i < VALUE_COUNT; i++) {
2568 val = &valueTable[i];
2569 cliPrintf("%s = ", valueTable[i].name);
2570 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2571 cliPrint("\r\n");
2573 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2574 // has equals
2576 char *lastNonSpaceCharacter = eqptr;
2577 while (*(lastNonSpaceCharacter - 1) == ' ') {
2578 lastNonSpaceCharacter--;
2580 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2582 // skip the '=' and any ' ' characters
2583 eqptr++;
2584 while (*(eqptr) == ' ') {
2585 eqptr++;
2588 for (i = 0; i < VALUE_COUNT; i++) {
2589 val = &valueTable[i];
2590 // ensure exact match when setting to prevent setting variables with shorter names
2591 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2593 bool changeValue = false;
2594 int_float_value_t tmp;
2595 switch (valueTable[i].type & VALUE_MODE_MASK) {
2596 case MODE_DIRECT: {
2597 int32_t value = 0;
2598 float valuef = 0;
2600 value = atoi(eqptr);
2601 valuef = fastA2F(eqptr);
2603 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2605 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2606 tmp.float_value = valuef;
2607 else
2608 tmp.int_value = value;
2610 changeValue = true;
2613 break;
2614 case MODE_LOOKUP: {
2615 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2616 bool matched = false;
2617 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2618 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2620 if (matched) {
2621 tmp.int_value = tableValueIndex;
2622 changeValue = true;
2626 break;
2629 if (changeValue) {
2630 cliSetVar(val, tmp);
2632 cliPrintf("%s set to ", valueTable[i].name);
2633 cliPrintVar(val, 0);
2634 } else {
2635 cliPrint("Invalid value\r\n");
2636 cliPrintVarRange(val);
2639 return;
2642 cliPrint("Invalid name\r\n");
2643 } else {
2644 // no equals, check for matching variables.
2645 cliGet(cmdline);
2649 static void cliGet(char *cmdline)
2651 uint32_t i;
2652 const clivalue_t *val;
2653 int matchedCommands = 0;
2655 for (i = 0; i < VALUE_COUNT; i++) {
2656 if (strstr(valueTable[i].name, cmdline)) {
2657 val = &valueTable[i];
2658 cliPrintf("%s = ", valueTable[i].name);
2659 cliPrintVar(val, 0);
2660 cliPrint("\n");
2661 cliPrintVarRange(val);
2662 cliPrint("\r\n");
2664 matchedCommands++;
2669 if (matchedCommands) {
2670 return;
2673 cliPrint("Invalid name\r\n");
2676 static void cliStatus(char *cmdline)
2678 UNUSED(cmdline);
2680 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2681 millis() / 1000,
2682 vbat,
2683 batteryCellCount,
2684 getBatteryStateString(),
2685 constrain(averageSystemLoadPercent, 0, 100)
2688 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2690 #ifndef CJMCU
2691 uint8_t i;
2692 uint32_t mask;
2693 uint32_t detectedSensorsMask = sensorsMask();
2695 for (i = 0; ; i++) {
2697 if (sensorTypeNames[i] == NULL)
2698 break;
2700 mask = (1 << i);
2701 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2702 const char *sensorHardware;
2703 uint8_t sensorHardwareIndex = detectedSensors[i];
2704 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2706 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2708 if (mask == SENSOR_ACC && acc.revisionCode) {
2709 cliPrintf(".%c", acc.revisionCode);
2713 #endif
2714 cliPrint("\r\n");
2716 #ifdef USE_I2C
2717 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2718 #else
2719 uint16_t i2cErrorCounter = 0;
2720 #endif
2722 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2725 #ifndef SKIP_TASK_STATISTICS
2726 static void cliTasks(char *cmdline)
2728 UNUSED(cmdline);
2730 cfTaskId_e taskId;
2731 cfTaskInfo_t taskInfo;
2733 cliPrintf("Task list:\r\n");
2734 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2735 getTaskInfo(taskId, &taskInfo);
2736 if (taskInfo.isEnabled) {
2737 uint16_t taskFrequency;
2738 uint16_t subTaskFrequency;
2740 uint32_t taskTotalTime = taskInfo.totalExecutionTime / 1000;
2742 if (taskId == TASK_GYROPID) {
2743 subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
2744 if (masterConfig.pid_process_denom > 1) {
2745 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
2746 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2747 } else {
2748 taskFrequency = subTaskFrequency;
2749 cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
2751 } else {
2752 taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
2753 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2756 cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
2758 if (taskTotalTime >= 1000) {
2759 cliPrintf("%dsec", taskTotalTime / 1000);
2760 } else {
2761 cliPrintf("%dms", taskTotalTime);
2764 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
2765 cliPrintf("\r\n", taskTotalTime);
2769 #endif
2771 static void cliVersion(char *cmdline)
2773 UNUSED(cmdline);
2775 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
2776 targetName,
2777 FC_VERSION_STRING,
2778 buildDate,
2779 buildTime,
2780 shortGitRevision
2784 void cliProcess(void)
2786 if (!cliWriter) {
2787 return;
2790 // Be a little bit tricky. Flush the last inputs buffer, if any.
2791 bufWriterFlush(cliWriter);
2793 while (serialRxBytesWaiting(cliPort)) {
2794 uint8_t c = serialRead(cliPort);
2795 if (c == '\t' || c == '?') {
2796 // do tab completion
2797 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2798 uint32_t i = bufferIndex;
2799 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2800 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2801 continue;
2802 if (!pstart)
2803 pstart = cmd;
2804 pend = cmd;
2806 if (pstart) { /* Buffer matches one or more commands */
2807 for (; ; bufferIndex++) {
2808 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2809 break;
2810 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2811 /* Unambiguous -- append a space */
2812 cliBuffer[bufferIndex++] = ' ';
2813 cliBuffer[bufferIndex] = '\0';
2814 break;
2816 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2819 if (!bufferIndex || pstart != pend) {
2820 /* Print list of ambiguous matches */
2821 cliPrint("\r\033[K");
2822 for (cmd = pstart; cmd <= pend; cmd++) {
2823 cliPrint(cmd->name);
2824 cliWrite('\t');
2826 cliPrompt();
2827 i = 0; /* Redraw prompt */
2829 for (; i < bufferIndex; i++)
2830 cliWrite(cliBuffer[i]);
2831 } else if (!bufferIndex && c == 4) { // CTRL-D
2832 cliExit(cliBuffer);
2833 return;
2834 } else if (c == 12) { // NewPage / CTRL-L
2835 // clear screen
2836 cliPrint("\033[2J\033[1;1H");
2837 cliPrompt();
2838 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2839 // enter pressed
2840 cliPrint("\r\n");
2842 // Strip comment starting with # from line
2843 char *p = cliBuffer;
2844 p = strchr(p, '#');
2845 if (NULL != p) {
2846 bufferIndex = (uint32_t)(p - cliBuffer);
2849 // Strip trailing whitespace
2850 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2851 bufferIndex--;
2854 // Process non-empty lines
2855 if (bufferIndex > 0) {
2856 cliBuffer[bufferIndex] = 0; // null terminate
2858 const clicmd_t *cmd;
2859 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2860 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2861 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2862 break;
2864 if(cmd < cmdTable + CMD_COUNT)
2865 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2866 else
2867 cliPrint("Unknown command, try 'help'");
2868 bufferIndex = 0;
2871 memset(cliBuffer, 0, sizeof(cliBuffer));
2873 // 'exit' will reset this flag, so we don't need to print prompt again
2874 if (!cliMode)
2875 return;
2877 cliPrompt();
2878 } else if (c == 127) {
2879 // backspace
2880 if (bufferIndex) {
2881 cliBuffer[--bufferIndex] = 0;
2882 cliPrint("\010 \010");
2884 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2885 if (!bufferIndex && c == ' ')
2886 continue; // Ignore leading spaces
2887 cliBuffer[bufferIndex++] = c;
2888 cliWrite(c);
2893 void cliInit(serialConfig_t *serialConfig)
2895 UNUSED(serialConfig);
2897 #endif