Add roll pitch velocity
[betaflight.git] / src / main / io / serial_cli.c
blob15de6036297b0f2ff6daad15b1c7e6370097673d
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 "version.h"
28 #include "debug.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/io.h"
47 #include "drivers/io_impl.h"
48 #include "drivers/timer.h"
49 #include "drivers/pwm_rx.h"
50 #include "drivers/sdcard.h"
52 #include "drivers/buf_writer.h"
54 #include "io/escservo.h"
55 #include "io/gps.h"
56 #include "io/gimbal.h"
57 #include "io/rc_controls.h"
58 #include "io/serial.h"
59 #include "io/ledstrip.h"
60 #include "io/flashfs.h"
61 #include "io/beeper.h"
62 #include "io/asyncfatfs/asyncfatfs.h"
63 #include "io/osd.h"
64 #include "io/vtx.h"
66 #include "rx/rx.h"
67 #include "rx/spektrum.h"
69 #include "sensors/battery.h"
70 #include "sensors/boardalignment.h"
71 #include "sensors/sensors.h"
72 #include "sensors/acceleration.h"
73 #include "sensors/gyro.h"
74 #include "sensors/compass.h"
75 #include "sensors/barometer.h"
77 #include "flight/pid.h"
78 #include "flight/imu.h"
79 #include "flight/mixer.h"
80 #include "flight/navigation.h"
81 #include "flight/failsafe.h"
83 #include "telemetry/telemetry.h"
84 #include "telemetry/frsky.h"
86 #include "config/runtime_config.h"
87 #include "config/config.h"
88 #include "config/config_profile.h"
89 #include "config/config_master.h"
91 #include "common/printf.h"
93 #include "io/serial_cli.h"
94 #include "scheduler/scheduler.h"
96 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
97 // signal that we're in cli mode
98 uint8_t cliMode = 0;
100 #ifdef USE_CLI
102 extern uint16_t cycleTime; // FIXME dependency on mw.c
104 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
106 static serialPort_t *cliPort;
107 static bufWriter_t *cliWriter;
108 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
110 static void cliAux(char *cmdline);
111 static void cliRxFail(char *cmdline);
112 static void cliAdjustmentRange(char *cmdline);
113 static void cliMotorMix(char *cmdline);
114 static void cliDefaults(char *cmdline);
115 void cliDfu(char *cmdLine);
116 static void cliDump(char *cmdLine);
117 void cliDumpProfile(uint8_t profileIndex);
118 void cliDumpRateProfile(uint8_t rateProfileIndex) ;
119 static void cliExit(char *cmdline);
120 static void cliFeature(char *cmdline);
121 static void cliMotor(char *cmdline);
122 static void cliName(char *cmdline);
123 static void cliPlaySound(char *cmdline);
124 static void cliProfile(char *cmdline);
125 static void cliRateProfile(char *cmdline);
126 static void cliReboot(void);
127 static void cliRebootEx(bool bootLoader);
128 static void cliSave(char *cmdline);
129 static void cliSerial(char *cmdline);
130 #ifndef SKIP_SERIAL_PASSTHROUGH
131 static void cliSerialPassthrough(char *cmdline);
132 #endif
134 #ifdef USE_SERVOS
135 static void cliServo(char *cmdline);
136 static void cliServoMix(char *cmdline);
137 #endif
139 static void cliSet(char *cmdline);
140 static void cliGet(char *cmdline);
141 static void cliStatus(char *cmdline);
142 #ifndef SKIP_TASK_STATISTICS
143 static void cliTasks(char *cmdline);
144 #endif
145 static void cliVersion(char *cmdline);
146 static void cliRxRange(char *cmdline);
147 #if (FLASH_SIZE > 64)
148 static void cliResource(char *cmdline);
149 #endif
150 #ifdef GPS
151 static void cliGpsPassthrough(char *cmdline);
152 #endif
154 static void cliHelp(char *cmdline);
155 static void cliMap(char *cmdline);
157 #ifdef LED_STRIP
158 static void cliLed(char *cmdline);
159 static void cliColor(char *cmdline);
160 static void cliModeColor(char *cmdline);
161 #endif
163 #ifndef USE_QUAD_MIXER_ONLY
164 static void cliMixer(char *cmdline);
165 #endif
167 #ifdef USE_FLASHFS
168 static void cliFlashInfo(char *cmdline);
169 static void cliFlashErase(char *cmdline);
170 #ifdef USE_FLASH_TOOLS
171 static void cliFlashWrite(char *cmdline);
172 static void cliFlashRead(char *cmdline);
173 #endif
174 #endif
176 #ifdef VTX
177 static void cliVtx(char *cmdline);
178 #endif
180 #ifdef USE_SDCARD
181 static void cliSdInfo(char *cmdline);
182 #endif
184 #ifdef BEEPER
185 static void cliBeeper(char *cmdline);
186 #endif
188 // buffer
189 static char cliBuffer[48];
190 static uint32_t bufferIndex = 0;
192 #ifndef USE_QUAD_MIXER_ONLY
193 // sync this with mixerMode_e
194 static const char * const mixerNames[] = {
195 "TRI", "QUADP", "QUADX", "BI",
196 "GIMBAL", "Y6", "HEX6",
197 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
198 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
199 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
200 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
202 #endif
204 // sync this with features_e
205 static const char * const featureNames[] = {
206 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
207 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
208 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
209 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
210 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES", NULL
213 // sync this with rxFailsafeChannelMode_e
214 static const char rxFailsafeModeCharacters[] = "ahs";
216 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
217 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
218 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
221 #if (FLASH_SIZE > 64)
222 // sync this with sensors_e
223 static const char * const sensorTypeNames[] = {
224 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
227 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
229 static const char * const sensorHardwareNames[4][11] = {
230 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE", NULL },
231 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
232 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
233 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
235 #endif
237 typedef struct {
238 const char *name;
239 #ifndef SKIP_CLI_COMMAND_HELP
240 const char *description;
241 const char *args;
242 #endif
243 void (*func)(char *cmdline);
244 } clicmd_t;
246 #ifndef SKIP_CLI_COMMAND_HELP
247 #define CLI_COMMAND_DEF(name, description, args, method) \
249 name , \
250 description , \
251 args , \
252 method \
254 #else
255 #define CLI_COMMAND_DEF(name, description, args, method) \
257 name, \
258 method \
260 #endif
262 // should be sorted a..z for bsearch()
263 const clicmd_t cmdTable[] = {
264 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
265 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
266 #ifdef LED_STRIP
267 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
268 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
269 #endif
270 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
271 CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
272 CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump),
273 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
274 CLI_COMMAND_DEF("feature", "configure features",
275 "list\r\n"
276 "\t<+|->[name]", cliFeature),
277 #ifdef USE_FLASHFS
278 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
279 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
280 #ifdef USE_FLASH_TOOLS
281 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
282 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
283 #endif
284 #endif
285 CLI_COMMAND_DEF("get", "get variable value",
286 "[name]", cliGet),
287 #ifdef GPS
288 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
289 #endif
290 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
291 #ifdef LED_STRIP
292 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
293 #endif
294 CLI_COMMAND_DEF("map", "configure rc channel order",
295 "[<map>]", cliMap),
296 #ifndef USE_QUAD_MIXER_ONLY
297 CLI_COMMAND_DEF("mixer", "configure mixer",
298 "list\r\n"
299 "\t<name>", cliMixer),
300 #endif
301 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
302 CLI_COMMAND_DEF("motor", "get/set motor",
303 "<index> [<value>]", cliMotor),
304 CLI_COMMAND_DEF("play_sound", NULL,
305 "[<index>]\r\n", cliPlaySound),
306 CLI_COMMAND_DEF("profile", "change profile",
307 "[<index>]", cliProfile),
308 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
309 #if (FLASH_SIZE > 64)
310 CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
311 #endif
312 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
313 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
314 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
315 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
316 #ifndef SKIP_SERIAL_PASSTHROUGH
317 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
318 "<id> [baud] [mode] : passthrough to serial",
319 cliSerialPassthrough),
320 #endif
321 #ifdef USE_SERVOS
322 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
323 #endif
324 CLI_COMMAND_DEF("set", "change setting",
325 "[<name>=<value>]", cliSet),
326 #ifdef USE_SERVOS
327 CLI_COMMAND_DEF("smix", "servo mixer",
328 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
329 "\treset\r\n"
330 "\tload <mixer>\r\n"
331 "\treverse <servo> <source> r|n", cliServoMix),
332 #endif
333 #ifdef USE_SDCARD
334 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
335 #endif
336 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
337 #ifndef SKIP_TASK_STATISTICS
338 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
339 #endif
340 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
341 #ifdef BEEPER
342 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
343 "\t<+|->[name]", cliBeeper),
344 #endif
345 #ifdef VTX
346 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
347 #endif
348 CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName),
350 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
352 static const char * const lookupTableOffOn[] = {
353 "OFF", "ON"
356 static const char * const lookupTableUnit[] = {
357 "IMPERIAL", "METRIC"
360 static const char * const lookupTableAlignment[] = {
361 "DEFAULT",
362 "CW0",
363 "CW90",
364 "CW180",
365 "CW270",
366 "CW0FLIP",
367 "CW90FLIP",
368 "CW180FLIP",
369 "CW270FLIP"
372 #ifdef GPS
373 static const char * const lookupTableGPSProvider[] = {
374 "NMEA", "UBLOX"
377 static const char * const lookupTableGPSSBASMode[] = {
378 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
380 #endif
382 static const char * const lookupTableCurrentSensor[] = {
383 "NONE", "ADC", "VIRTUAL"
386 #ifdef USE_SERVOS
387 static const char * const lookupTableGimbalMode[] = {
388 "NORMAL", "MIXTILT"
390 #endif
392 #ifdef BLACKBOX
393 static const char * const lookupTableBlackboxDevice[] = {
394 "SERIAL", "SPIFLASH", "SDCARD"
396 #endif
398 static const char * const lookupTablePidController[] = {
399 "LEGACY", "BETAFLIGHT"
402 #ifdef SERIAL_RX
403 static const char * const lookupTableSerialRX[] = {
404 "SPEK1024",
405 "SPEK2048",
406 "SBUS",
407 "SUMD",
408 "SUMH",
409 "XB-B",
410 "XB-B-RJ01",
411 "IBUS",
412 "JETIEXBUS"
414 #endif
416 static const char * const lookupTableGyroLpf[] = {
417 "OFF",
418 "188HZ",
419 "98HZ",
420 "42HZ",
421 "20HZ",
422 "10HZ",
423 "5HZ",
424 "EXPERIMENTAL"
427 static const char * const lookupTableAccHardware[] = {
428 "AUTO",
429 "NONE",
430 "ADXL345",
431 "MPU6050",
432 "MMA8452",
433 "BMA280",
434 "LSM303DLHC",
435 "MPU6000",
436 "MPU6500",
437 "FAKE"
440 #ifdef BARO
441 static const char * const lookupTableBaroHardware[] = {
442 "AUTO",
443 "NONE",
444 "BMP085",
445 "MS5611",
446 "BMP280"
448 #endif
450 #ifdef MAG
451 static const char * const lookupTableMagHardware[] = {
452 "AUTO",
453 "NONE",
454 "HMC5883",
455 "AK8975",
456 "AK8963"
458 #endif
460 static const char * const lookupTableDebug[DEBUG_COUNT] = {
461 "NONE",
462 "CYCLETIME",
463 "BATTERY",
464 "GYRO",
465 "ACCELEROMETER",
466 "MIXER",
467 "AIRMODE",
468 "PIDLOOP",
469 "NOTCH",
470 "RC_SMOOTHING",
471 "VELOCITY",
472 "DFILTER",
475 #ifdef OSD
476 static const char * const lookupTableOsdType[] = {
477 "AUTO",
478 "PAL",
479 "NTSC"
481 #endif
483 static const char * const lookupTableSuperExpoYaw[] = {
484 "OFF", "ON", "ALWAYS"
487 static const char * const lookupTablePwmProtocol[] = {
488 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
491 static const char * const lookupTableDeltaMethod[] = {
492 "ERROR", "MEASUREMENT"
495 static const char * const lookupTableRcSmoothing[] = {
496 "OFF", "DEFAULT", "AUTO", "MANUAL"
499 static const char * const lookupTableLowpassType[] = {
500 "NORMAL", "HIGH"
503 typedef struct lookupTableEntry_s {
504 const char * const *values;
505 const uint8_t valueCount;
506 } lookupTableEntry_t;
508 typedef enum {
509 TABLE_OFF_ON = 0,
510 TABLE_UNIT,
511 TABLE_ALIGNMENT,
512 #ifdef GPS
513 TABLE_GPS_PROVIDER,
514 TABLE_GPS_SBAS_MODE,
515 #endif
516 #ifdef BLACKBOX
517 TABLE_BLACKBOX_DEVICE,
518 #endif
519 TABLE_CURRENT_SENSOR,
520 #ifdef USE_SERVOS
521 TABLE_GIMBAL_MODE,
522 #endif
523 TABLE_PID_CONTROLLER,
524 #ifdef SERIAL_RX
525 TABLE_SERIAL_RX,
526 #endif
527 TABLE_GYRO_LPF,
528 TABLE_ACC_HARDWARE,
529 #ifdef BARO
530 TABLE_BARO_HARDWARE,
531 #endif
532 #ifdef MAG
533 TABLE_MAG_HARDWARE,
534 #endif
535 TABLE_DEBUG,
536 TABLE_SUPEREXPO_YAW,
537 TABLE_MOTOR_PWM_PROTOCOL,
538 TABLE_DELTA_METHOD,
539 TABLE_RC_SMOOTHING,
540 TABLE_LOWPASS_TYPE,
541 #ifdef OSD
542 TABLE_OSD,
543 #endif
544 } lookupTableIndex_e;
546 static const lookupTableEntry_t lookupTables[] = {
547 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
548 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
549 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
550 #ifdef GPS
551 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
552 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
553 #endif
554 #ifdef BLACKBOX
555 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
556 #endif
557 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
558 #ifdef USE_SERVOS
559 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
560 #endif
561 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
562 #ifdef SERIAL_RX
563 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
564 #endif
565 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
566 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
567 #ifdef BARO
568 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
569 #endif
570 #ifdef MAG
571 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
572 #endif
573 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
574 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
575 { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
576 { lookupTableDeltaMethod, sizeof(lookupTableDeltaMethod) / sizeof(char *) },
577 { lookupTableRcSmoothing, sizeof(lookupTableRcSmoothing) / sizeof(char *) },
578 { lookupTableLowpassType, sizeof(lookupTableLowpassType) / sizeof(char *) },
579 #ifdef OSD
580 { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
581 #endif
584 #define VALUE_TYPE_OFFSET 0
585 #define VALUE_SECTION_OFFSET 4
586 #define VALUE_MODE_OFFSET 6
588 typedef enum {
589 // value type
590 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
591 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
592 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
593 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
594 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
595 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
597 // value section
598 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
599 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
600 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
601 // value mode
602 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
603 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
604 } cliValueFlag_e;
606 #define VALUE_TYPE_MASK (0x0F)
607 #define VALUE_SECTION_MASK (0x30)
608 #define VALUE_MODE_MASK (0xC0)
610 typedef struct cliMinMaxConfig_s {
611 const int32_t min;
612 const int32_t max;
613 } cliMinMaxConfig_t;
615 typedef struct cliLookupTableConfig_s {
616 const lookupTableIndex_e tableIndex;
617 } cliLookupTableConfig_t;
619 typedef union {
620 cliLookupTableConfig_t lookup;
621 cliMinMaxConfig_t minmax;
622 } cliValueConfig_t;
624 typedef struct {
625 const char *name;
626 const uint8_t type; // see cliValueFlag_e
627 void *ptr;
628 const cliValueConfig_t config;
629 } clivalue_t;
631 const clivalue_t valueTable[] = {
632 // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
633 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
634 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
635 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
636 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
637 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
638 { "rc_smoothing", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_RC_SMOOTHING } },
639 { "rc_smooth_interval_ms", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothInterval, .config.minmax = { 1, 50 } },
640 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
641 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
642 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
643 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
644 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
646 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
647 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
648 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
649 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
651 { "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
652 { "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,
653 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
654 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
656 #ifdef CC3D
657 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
658 #endif
659 { "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
660 { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
661 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } },
662 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
664 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
665 { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
666 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
667 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
669 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
671 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
673 #ifdef GPS
674 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
675 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
676 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
677 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
679 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
680 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
681 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
682 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
683 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
684 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
685 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
686 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
687 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
688 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
689 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
690 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
691 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
692 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
693 #endif
694 #ifdef GTUNE
695 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
696 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
697 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
698 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
699 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
700 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
701 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
702 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
703 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
704 #endif
706 #ifdef SERIAL_RX
707 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
708 #endif
709 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
710 #ifdef SPEKTRUM_BIND
711 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
712 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
713 #endif
715 #ifdef TELEMETRY
716 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
717 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
718 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
719 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
720 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
721 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
722 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
723 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
724 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
725 #endif
727 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
728 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
729 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
730 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
731 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
732 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
733 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
734 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
735 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
736 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
738 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
739 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
740 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
742 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
743 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
744 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
746 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
747 { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
748 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
749 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
750 { "gyro_lowpass_level", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_soft_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
751 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
752 { "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
753 { "gyro_notch_cutoff", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_cutoff, .config.minmax = { 1, 500 } },
754 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
755 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
756 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
758 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
759 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
760 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
761 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
763 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
764 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
766 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
768 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
769 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
770 #ifdef USE_SERVOS
771 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
772 { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
773 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
774 #endif
776 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 300 } },
777 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawRate8, .config.minmax = { 0, 300 } },
778 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
779 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
780 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
781 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
782 { "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 } },
783 { "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 } },
784 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
785 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
786 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
787 { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } },
789 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
790 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
791 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
792 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
793 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
794 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
796 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
797 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
799 #ifdef USE_SERVOS
800 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
801 #endif
803 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
804 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
805 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
806 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
807 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
808 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
809 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
811 #ifdef BARO
812 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
813 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
814 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
815 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
816 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
817 #endif
819 #ifdef MAG
820 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
821 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
822 #endif
823 { "dterm_lowpass_level", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.dterm_filter_type, .config.lookup = { TABLE_LOWPASS_TYPE } },
824 { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
825 { "dterm_notch_hz", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_hz, .config.minmax = { 0, 500 } },
826 { "dterm_notch_cutoff", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_notch_cutoff, .config.minmax = { 1, 500 } },
827 { "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
828 { "zero_throttle_stabilisation",VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.zeroThrottleStabilisation, .config.lookup = { TABLE_OFF_ON } },
829 { "pid_tolerance_band", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBand, .config.minmax = {0, 200 } },
830 { "tolerance_band_reduction", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBandReduction, .config.minmax = {0, 100 } },
831 { "zero_cross_allowance", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.zeroCrossAllowanceCount, .config.minmax = {0, 50 } },
832 { "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
833 { "pterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.ptermSetpointWeight, .config.minmax = {30, 100 } },
834 { "dterm_setpoint_weight", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dtermSetpointWeight, .config.minmax = {0, 300 } },
835 { "max_yaw_acceleration", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidMaxVelocityYaw, .config.minmax = {0, 1000 } },
836 { "max_acceleration", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidMaxVelocityRollPitch, .config.minmax = {0, 1000 } },
838 { "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
839 { "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
840 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
841 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
843 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
845 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
846 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
847 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
848 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
849 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
850 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
851 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
852 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
853 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
855 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
856 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
857 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
859 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
860 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
861 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
863 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
864 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
865 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
867 #ifdef BLACKBOX
868 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
869 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
870 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
871 #endif
873 #ifdef VTX
874 { "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } },
875 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } },
876 { "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } },
877 { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
878 #endif
880 #ifdef MAG
881 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
882 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
883 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
884 #endif
885 #ifdef LED_STRIP
886 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
887 #endif
888 #ifdef USE_RTC6705
889 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
890 { "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
891 #endif
892 #ifdef OSD
893 { "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
894 { "osd_main_voltage_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { -480, 480 } },
895 { "osd_rssi_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { -480, 480 } },
896 { "osd_timer_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_TIMER], .config.minmax = { -480, 480 } },
897 { "osd_throttle_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { -480, 480 } },
898 { "osd_cpu_load_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], .config.minmax = { -480, 480 } },
899 { "osd_vtx_channel_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { -480, 480 } },
900 { "osd_voltage_warning_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING], .config.minmax = { -480, 480 } },
901 { "osd_armed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARMED], .config.minmax = { -480, 480 } },
902 { "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } },
903 { "osd_artificial_horizon", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { -1, 0 } },
904 { "osd_horizon_sidebars", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], .config.minmax = { -1, 0 } },
905 { "osd_current_draw_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], .config.minmax = { -480, 480 } },
906 { "osd_mah_drawn_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], .config.minmax = { -480, 480 } },
907 { "osd_craft_name_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], .config.minmax = { -480, 480 } },
908 #endif
911 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
914 typedef union {
915 int32_t int_value;
916 float float_value;
917 } int_float_value_t;
919 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
920 static void cliPrintVar(const clivalue_t *var, uint32_t full);
921 static void cliPrintVarRange(const clivalue_t *var);
922 static void cliPrint(const char *str);
923 static void cliPrintf(const char *fmt, ...);
924 static void cliWrite(uint8_t ch);
926 static void cliPrompt(void)
928 cliPrint("\r\n# ");
929 bufWriterFlush(cliWriter);
932 static void cliShowParseError(void)
934 cliPrint("Parse error\r\n");
937 static void cliShowArgumentRangeError(char *name, int min, int max)
939 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
942 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
944 int val;
946 for (int argIndex = 0; argIndex < 2; argIndex++) {
947 ptr = strchr(ptr, ' ');
948 if (ptr) {
949 val = atoi(++ptr);
950 val = CHANNEL_VALUE_TO_STEP(val);
951 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
952 if (argIndex == 0) {
953 range->startStep = val;
954 } else {
955 range->endStep = val;
957 (*validArgumentCount)++;
962 return ptr;
965 // Check if a string's length is zero
966 static bool isEmpty(const char *string)
968 return *string == '\0';
971 static void cliRxFail(char *cmdline)
973 uint8_t channel;
974 char buf[3];
976 if (isEmpty(cmdline)) {
977 // print out rxConfig failsafe settings
978 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
979 cliRxFail(itoa(channel, buf, 10));
981 } else {
982 char *ptr = cmdline;
983 channel = atoi(ptr++);
984 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
986 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
988 uint16_t value;
989 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
990 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
991 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
993 ptr = strchr(ptr, ' ');
994 if (ptr) {
995 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
996 if (p) {
997 uint8_t requestedMode = p - rxFailsafeModeCharacters;
998 mode = rxFailsafeModesTable[type][requestedMode];
999 } else {
1000 mode = RX_FAILSAFE_MODE_INVALID;
1002 if (mode == RX_FAILSAFE_MODE_INVALID) {
1003 cliShowParseError();
1004 return;
1007 requireValue = mode == RX_FAILSAFE_MODE_SET;
1009 ptr = strchr(ptr, ' ');
1010 if (ptr) {
1011 if (!requireValue) {
1012 cliShowParseError();
1013 return;
1015 value = atoi(++ptr);
1016 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
1017 if (value > MAX_RXFAIL_RANGE_STEP) {
1018 cliPrint("Value out of range\r\n");
1019 return;
1022 channelFailsafeConfiguration->step = value;
1023 } else if (requireValue) {
1024 cliShowParseError();
1025 return;
1027 channelFailsafeConfiguration->mode = mode;
1031 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
1033 // triple use of cliPrintf below
1034 // 1. acknowledge interpretation on command,
1035 // 2. query current setting on single item,
1036 // 3. recursive use for full list.
1038 if (requireValue) {
1039 cliPrintf("rxfail %u %c %d\r\n",
1040 channel,
1041 modeCharacter,
1042 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
1044 } else {
1045 cliPrintf("rxfail %u %c\r\n",
1046 channel,
1047 modeCharacter
1050 } else {
1051 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
1056 static void cliAux(char *cmdline)
1058 int i, val = 0;
1059 char *ptr;
1061 if (isEmpty(cmdline)) {
1062 // print out aux channel settings
1063 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
1064 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1065 cliPrintf("aux %u %u %u %u %u\r\n",
1067 mac->modeId,
1068 mac->auxChannelIndex,
1069 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
1070 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
1073 } else {
1074 ptr = cmdline;
1075 i = atoi(ptr++);
1076 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
1077 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1078 uint8_t validArgumentCount = 0;
1079 ptr = strchr(ptr, ' ');
1080 if (ptr) {
1081 val = atoi(++ptr);
1082 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
1083 mac->modeId = val;
1084 validArgumentCount++;
1087 ptr = strchr(ptr, ' ');
1088 if (ptr) {
1089 val = atoi(++ptr);
1090 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1091 mac->auxChannelIndex = val;
1092 validArgumentCount++;
1095 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
1097 if (validArgumentCount != 4) {
1098 memset(mac, 0, sizeof(modeActivationCondition_t));
1100 } else {
1101 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
1106 static void cliSerial(char *cmdline)
1108 int i, val;
1109 char *ptr;
1111 if (isEmpty(cmdline)) {
1112 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
1113 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
1114 continue;
1116 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
1117 masterConfig.serialConfig.portConfigs[i].identifier,
1118 masterConfig.serialConfig.portConfigs[i].functionMask,
1119 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
1120 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
1121 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
1122 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
1125 return;
1128 serialPortConfig_t portConfig;
1129 memset(&portConfig, 0 , sizeof(portConfig));
1131 serialPortConfig_t *currentConfig;
1133 uint8_t validArgumentCount = 0;
1135 ptr = cmdline;
1137 val = atoi(ptr++);
1138 currentConfig = serialFindPortConfiguration(val);
1139 if (currentConfig) {
1140 portConfig.identifier = val;
1141 validArgumentCount++;
1144 ptr = strchr(ptr, ' ');
1145 if (ptr) {
1146 val = atoi(++ptr);
1147 portConfig.functionMask = val & 0xFFFF;
1148 validArgumentCount++;
1151 for (i = 0; i < 4; i ++) {
1152 ptr = strchr(ptr, ' ');
1153 if (!ptr) {
1154 break;
1157 val = atoi(++ptr);
1159 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1160 if (baudRates[baudRateIndex] != (uint32_t) val) {
1161 break;
1164 switch(i) {
1165 case 0:
1166 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1167 continue;
1169 portConfig.msp_baudrateIndex = baudRateIndex;
1170 break;
1171 case 1:
1172 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1173 continue;
1175 portConfig.gps_baudrateIndex = baudRateIndex;
1176 break;
1177 case 2:
1178 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1179 continue;
1181 portConfig.telemetry_baudrateIndex = baudRateIndex;
1182 break;
1183 case 3:
1184 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1185 continue;
1187 portConfig.blackbox_baudrateIndex = baudRateIndex;
1188 break;
1191 validArgumentCount++;
1194 if (validArgumentCount < 6) {
1195 cliShowParseError();
1196 return;
1199 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1203 #ifndef SKIP_SERIAL_PASSTHROUGH
1204 static void cliSerialPassthrough(char *cmdline)
1206 if (isEmpty(cmdline)) {
1207 cliShowParseError();
1208 return;
1211 int id = -1;
1212 uint32_t baud = 0;
1213 unsigned mode = 0;
1214 char* tok = strtok(cmdline, " ");
1215 int index = 0;
1217 while (tok != NULL) {
1218 switch(index) {
1219 case 0:
1220 id = atoi(tok);
1221 break;
1222 case 1:
1223 baud = atoi(tok);
1224 break;
1225 case 2:
1226 if (strstr(tok, "rx") || strstr(tok, "RX"))
1227 mode |= MODE_RX;
1228 if (strstr(tok, "tx") || strstr(tok, "TX"))
1229 mode |= MODE_TX;
1230 break;
1232 index++;
1233 tok = strtok(NULL, " ");
1236 serialPort_t *passThroughPort;
1237 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1238 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1239 if (!baud) {
1240 printf("Port %d is not open, you must specify baud\r\n", id);
1241 return;
1243 if (!mode)
1244 mode = MODE_RXTX;
1246 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1247 baud, mode,
1248 SERIAL_NOT_INVERTED);
1249 if (!passThroughPort) {
1250 printf("Port %d could not be opened\r\n", id);
1251 return;
1253 printf("Port %d opened, baud=%d\r\n", id, baud);
1254 } else {
1255 passThroughPort = passThroughPortUsage->serialPort;
1256 // If the user supplied a mode, override the port's mode, otherwise
1257 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1258 printf("Port %d already open\r\n", id);
1259 if (mode && passThroughPort->mode != mode) {
1260 printf("Adjusting mode from configured value %d to %d\r\n",
1261 passThroughPort->mode, mode);
1262 serialSetMode(passThroughPort, mode);
1266 printf("Relaying data to device on port %d, Reset your board to exit "
1267 "serial passthrough mode.\r\n");
1269 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1271 #endif
1273 static void cliAdjustmentRange(char *cmdline)
1275 int i, val = 0;
1276 char *ptr;
1278 if (isEmpty(cmdline)) {
1279 // print out adjustment ranges channel settings
1280 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1281 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1282 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1284 ar->adjustmentIndex,
1285 ar->auxChannelIndex,
1286 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1287 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1288 ar->adjustmentFunction,
1289 ar->auxSwitchChannelIndex
1292 } else {
1293 ptr = cmdline;
1294 i = atoi(ptr++);
1295 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1296 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1297 uint8_t validArgumentCount = 0;
1299 ptr = strchr(ptr, ' ');
1300 if (ptr) {
1301 val = atoi(++ptr);
1302 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1303 ar->adjustmentIndex = val;
1304 validArgumentCount++;
1307 ptr = strchr(ptr, ' ');
1308 if (ptr) {
1309 val = atoi(++ptr);
1310 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1311 ar->auxChannelIndex = val;
1312 validArgumentCount++;
1316 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1318 ptr = strchr(ptr, ' ');
1319 if (ptr) {
1320 val = atoi(++ptr);
1321 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1322 ar->adjustmentFunction = val;
1323 validArgumentCount++;
1326 ptr = strchr(ptr, ' ');
1327 if (ptr) {
1328 val = atoi(++ptr);
1329 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1330 ar->auxSwitchChannelIndex = val;
1331 validArgumentCount++;
1335 if (validArgumentCount != 6) {
1336 memset(ar, 0, sizeof(adjustmentRange_t));
1337 cliShowParseError();
1339 } else {
1340 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1345 static void cliMotorMix(char *cmdline)
1347 #ifdef USE_QUAD_MIXER_ONLY
1348 UNUSED(cmdline);
1349 #else
1350 int i, check = 0;
1351 int num_motors = 0;
1352 uint8_t len;
1353 char buf[16];
1354 char *ptr;
1356 if (isEmpty(cmdline)) {
1357 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1358 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1359 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1360 break;
1361 num_motors++;
1362 cliPrintf("#%d:\t", i);
1363 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1364 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1365 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1366 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1368 return;
1369 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1370 // erase custom mixer
1371 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1372 masterConfig.customMotorMixer[i].throttle = 0.0f;
1373 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1374 ptr = strchr(cmdline, ' ');
1375 if (ptr) {
1376 len = strlen(++ptr);
1377 for (i = 0; ; i++) {
1378 if (mixerNames[i] == NULL) {
1379 cliPrint("Invalid name\r\n");
1380 break;
1382 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1383 mixerLoadMix(i, masterConfig.customMotorMixer);
1384 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1385 cliMotorMix("");
1386 break;
1390 } else {
1391 ptr = cmdline;
1392 i = atoi(ptr); // get motor number
1393 if (i < MAX_SUPPORTED_MOTORS) {
1394 ptr = strchr(ptr, ' ');
1395 if (ptr) {
1396 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1397 check++;
1399 ptr = strchr(ptr, ' ');
1400 if (ptr) {
1401 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1402 check++;
1404 ptr = strchr(ptr, ' ');
1405 if (ptr) {
1406 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1407 check++;
1409 ptr = strchr(ptr, ' ');
1410 if (ptr) {
1411 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1412 check++;
1414 if (check != 4) {
1415 cliShowParseError();
1416 } else {
1417 cliMotorMix("");
1419 } else {
1420 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1423 #endif
1426 static void cliRxRange(char *cmdline)
1428 int i, validArgumentCount = 0;
1429 char *ptr;
1431 if (isEmpty(cmdline)) {
1432 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1433 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1434 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1436 } else if (strcasecmp(cmdline, "reset") == 0) {
1437 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1438 } else {
1439 ptr = cmdline;
1440 i = atoi(ptr);
1441 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1442 int rangeMin, rangeMax;
1444 ptr = strchr(ptr, ' ');
1445 if (ptr) {
1446 rangeMin = atoi(++ptr);
1447 validArgumentCount++;
1450 ptr = strchr(ptr, ' ');
1451 if (ptr) {
1452 rangeMax = atoi(++ptr);
1453 validArgumentCount++;
1456 if (validArgumentCount != 2) {
1457 cliShowParseError();
1458 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1459 cliShowParseError();
1460 } else {
1461 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1462 channelRangeConfiguration->min = rangeMin;
1463 channelRangeConfiguration->max = rangeMax;
1465 } else {
1466 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1471 #ifdef LED_STRIP
1472 static void cliLed(char *cmdline)
1474 int i;
1475 char *ptr;
1476 char ledConfigBuffer[20];
1478 if (isEmpty(cmdline)) {
1479 for (i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
1480 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1481 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1483 } else {
1484 ptr = cmdline;
1485 i = atoi(ptr);
1486 if (i < LED_MAX_STRIP_LENGTH) {
1487 ptr = strchr(cmdline, ' ');
1488 if (!parseLedStripConfig(i, ++ptr)) {
1489 cliShowParseError();
1491 } else {
1492 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH - 1);
1497 static void cliColor(char *cmdline)
1499 int i;
1500 char *ptr;
1502 if (isEmpty(cmdline)) {
1503 for (i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
1504 cliPrintf("color %u %d,%u,%u\r\n",
1506 masterConfig.colors[i].h,
1507 masterConfig.colors[i].s,
1508 masterConfig.colors[i].v
1511 } else {
1512 ptr = cmdline;
1513 i = atoi(ptr);
1514 if (i < LED_CONFIGURABLE_COLOR_COUNT) {
1515 ptr = strchr(cmdline, ' ');
1516 if (!parseColor(i, ++ptr)) {
1517 cliShowParseError();
1519 } else {
1520 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT - 1);
1525 static void cliModeColor(char *cmdline)
1527 if (isEmpty(cmdline)) {
1528 for (int i = 0; i < LED_MODE_COUNT; i++) {
1529 for (int j = 0; j < LED_DIRECTION_COUNT; j++) {
1530 int colorIndex = modeColors[i].color[j];
1531 cliPrintf("mode_color %u %u %u\r\n", i, j, colorIndex);
1535 for (int j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
1536 int colorIndex = specialColors.color[j];
1537 cliPrintf("mode_color %u %u %u\r\n", LED_SPECIAL, j, colorIndex);
1539 } else {
1540 enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
1541 int args[ARGS_COUNT];
1542 int argNo = 0;
1543 char* ptr = strtok(cmdline, " ");
1544 while (ptr && argNo < ARGS_COUNT) {
1545 args[argNo++] = atoi(ptr);
1546 ptr = strtok(NULL, " ");
1549 if (ptr != NULL || argNo != ARGS_COUNT) {
1550 cliShowParseError();
1551 return;
1554 int modeIdx = args[MODE];
1555 int funIdx = args[FUNCTION];
1556 int color = args[COLOR];
1557 if(!setModeColor(modeIdx, funIdx, color)) {
1558 cliShowParseError();
1559 return;
1561 // values are validated
1562 cliPrintf("mode_color %u %u %u\r\n", modeIdx, funIdx, color);
1565 #endif
1567 #ifdef USE_SERVOS
1568 static void cliServo(char *cmdline)
1570 enum { SERVO_ARGUMENT_COUNT = 8 };
1571 int16_t arguments[SERVO_ARGUMENT_COUNT];
1573 servoParam_t *servo;
1575 int i;
1576 char *ptr;
1578 if (isEmpty(cmdline)) {
1579 // print out servo settings
1580 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1581 servo = &masterConfig.servoConf[i];
1583 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1585 servo->min,
1586 servo->max,
1587 servo->middle,
1588 servo->angleAtMin,
1589 servo->angleAtMax,
1590 servo->rate,
1591 servo->forwardFromChannel
1594 } else {
1595 int validArgumentCount = 0;
1597 ptr = cmdline;
1599 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1601 // If command line doesn't fit the format, don't modify the config
1602 while (*ptr) {
1603 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1604 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1605 cliShowParseError();
1606 return;
1609 arguments[validArgumentCount++] = atoi(ptr);
1611 do {
1612 ptr++;
1613 } while (*ptr >= '0' && *ptr <= '9');
1614 } else if (*ptr == ' ') {
1615 ptr++;
1616 } else {
1617 cliShowParseError();
1618 return;
1622 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1624 i = arguments[INDEX];
1626 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1627 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1628 cliShowParseError();
1629 return;
1632 servo = &masterConfig.servoConf[i];
1634 if (
1635 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1636 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1637 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1638 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1639 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1640 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1641 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1642 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1644 cliShowParseError();
1645 return;
1648 servo->min = arguments[1];
1649 servo->max = arguments[2];
1650 servo->middle = arguments[3];
1651 servo->angleAtMin = arguments[4];
1652 servo->angleAtMax = arguments[5];
1653 servo->rate = arguments[6];
1654 servo->forwardFromChannel = arguments[7];
1657 #endif
1659 #ifdef USE_SERVOS
1660 static void cliServoMix(char *cmdline)
1662 int i;
1663 uint8_t len;
1664 char *ptr;
1665 int args[8], check = 0;
1666 len = strlen(cmdline);
1668 if (len == 0) {
1670 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1672 for (i = 0; i < MAX_SERVO_RULES; i++) {
1673 if (masterConfig.customServoMixer[i].rate == 0)
1674 break;
1676 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1678 masterConfig.customServoMixer[i].targetChannel,
1679 masterConfig.customServoMixer[i].inputSource,
1680 masterConfig.customServoMixer[i].rate,
1681 masterConfig.customServoMixer[i].speed,
1682 masterConfig.customServoMixer[i].min,
1683 masterConfig.customServoMixer[i].max,
1684 masterConfig.customServoMixer[i].box
1687 cliPrintf("\r\n");
1688 return;
1689 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1690 // erase custom mixer
1691 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1692 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1693 masterConfig.servoConf[i].reversedSources = 0;
1695 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1696 ptr = strchr(cmdline, ' ');
1697 if (ptr) {
1698 len = strlen(++ptr);
1699 for (i = 0; ; i++) {
1700 if (mixerNames[i] == NULL) {
1701 cliPrintf("Invalid name\r\n");
1702 break;
1704 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1705 servoMixerLoadMix(i, masterConfig.customServoMixer);
1706 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1707 cliServoMix("");
1708 break;
1712 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1713 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1714 int servoIndex, inputSource;
1715 ptr = strchr(cmdline, ' ');
1717 len = strlen(ptr);
1718 if (len == 0) {
1719 cliPrintf("s");
1720 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1721 cliPrintf("\ti%d", inputSource);
1722 cliPrintf("\r\n");
1724 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1725 cliPrintf("%d", servoIndex);
1726 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1727 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1728 cliPrintf("\r\n");
1730 return;
1733 ptr = strtok(ptr, " ");
1734 while (ptr != NULL && check < ARGS_COUNT - 1) {
1735 args[check++] = atoi(ptr);
1736 ptr = strtok(NULL, " ");
1739 if (ptr == NULL || check != ARGS_COUNT - 1) {
1740 cliShowParseError();
1741 return;
1744 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1745 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1746 && (*ptr == 'r' || *ptr == 'n')) {
1747 if (*ptr == 'r')
1748 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1749 else
1750 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1751 } else
1752 cliShowParseError();
1754 cliServoMix("reverse");
1755 } else {
1756 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1757 ptr = strtok(cmdline, " ");
1758 while (ptr != NULL && check < ARGS_COUNT) {
1759 args[check++] = atoi(ptr);
1760 ptr = strtok(NULL, " ");
1763 if (ptr != NULL || check != ARGS_COUNT) {
1764 cliShowParseError();
1765 return;
1768 i = args[RULE];
1769 if (i >= 0 && i < MAX_SERVO_RULES &&
1770 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1771 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1772 args[RATE] >= -100 && args[RATE] <= 100 &&
1773 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1774 args[MIN] >= 0 && args[MIN] <= 100 &&
1775 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1776 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1777 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1778 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1779 masterConfig.customServoMixer[i].rate = args[RATE];
1780 masterConfig.customServoMixer[i].speed = args[SPEED];
1781 masterConfig.customServoMixer[i].min = args[MIN];
1782 masterConfig.customServoMixer[i].max = args[MAX];
1783 masterConfig.customServoMixer[i].box = args[BOX];
1784 cliServoMix("");
1785 } else {
1786 cliShowParseError();
1790 #endif
1792 #ifdef USE_SDCARD
1794 static void cliWriteBytes(const uint8_t *buffer, int count)
1796 while (count > 0) {
1797 cliWrite(*buffer);
1798 buffer++;
1799 count--;
1803 static void cliSdInfo(char *cmdline) {
1804 UNUSED(cmdline);
1806 cliPrint("SD card: ");
1808 if (!sdcard_isInserted()) {
1809 cliPrint("None inserted\r\n");
1810 return;
1813 if (!sdcard_isInitialized()) {
1814 cliPrint("Startup failed\r\n");
1815 return;
1818 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1820 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1821 metadata->manufacturerID,
1822 metadata->numBlocks / 2, /* One block is half a kB */
1823 metadata->productionMonth,
1824 metadata->productionYear,
1825 metadata->productRevisionMajor,
1826 metadata->productRevisionMinor
1829 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1831 cliPrint("'\r\n" "Filesystem: ");
1833 switch (afatfs_getFilesystemState()) {
1834 case AFATFS_FILESYSTEM_STATE_READY:
1835 cliPrint("Ready");
1836 break;
1837 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1838 cliPrint("Initializing");
1839 break;
1840 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1841 case AFATFS_FILESYSTEM_STATE_FATAL:
1842 cliPrint("Fatal");
1844 switch (afatfs_getLastError()) {
1845 case AFATFS_ERROR_BAD_MBR:
1846 cliPrint(" - no FAT MBR partitions");
1847 break;
1848 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1849 cliPrint(" - bad FAT header");
1850 break;
1851 case AFATFS_ERROR_GENERIC:
1852 case AFATFS_ERROR_NONE:
1853 ; // Nothing more detailed to print
1854 break;
1857 cliPrint("\r\n");
1858 break;
1862 #endif
1864 #ifdef USE_FLASHFS
1866 static void cliFlashInfo(char *cmdline)
1868 const flashGeometry_t *layout = flashfsGetGeometry();
1870 UNUSED(cmdline);
1872 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1873 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1876 static void cliFlashErase(char *cmdline)
1878 UNUSED(cmdline);
1880 cliPrintf("Erasing...\r\n");
1881 flashfsEraseCompletely();
1883 while (!flashfsIsReady()) {
1884 delay(100);
1887 cliPrintf("Done.\r\n");
1890 #ifdef USE_FLASH_TOOLS
1892 static void cliFlashWrite(char *cmdline)
1894 uint32_t address = atoi(cmdline);
1895 char *text = strchr(cmdline, ' ');
1897 if (!text) {
1898 cliShowParseError();
1899 } else {
1900 flashfsSeekAbs(address);
1901 flashfsWrite((uint8_t*)text, strlen(text), true);
1902 flashfsFlushSync();
1904 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1908 static void cliFlashRead(char *cmdline)
1910 uint32_t address = atoi(cmdline);
1911 uint32_t length;
1912 int i;
1914 uint8_t buffer[32];
1916 char *nextArg = strchr(cmdline, ' ');
1918 if (!nextArg) {
1919 cliShowParseError();
1920 } else {
1921 length = atoi(nextArg);
1923 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1925 while (length > 0) {
1926 int bytesRead;
1928 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1930 for (i = 0; i < bytesRead; i++) {
1931 cliWrite(buffer[i]);
1934 length -= bytesRead;
1935 address += bytesRead;
1937 if (bytesRead == 0) {
1938 //Assume we reached the end of the volume or something fatal happened
1939 break;
1942 cliPrintf("\r\n");
1946 #endif
1947 #endif
1949 #ifdef VTX
1950 static void cliVtx(char *cmdline)
1952 int i, val = 0;
1953 char *ptr;
1955 if (isEmpty(cmdline)) {
1956 // print out vtx channel settings
1957 for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
1958 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1959 printf("vtx %u %u %u %u %u %u\r\n",
1961 cac->auxChannelIndex,
1962 cac->band,
1963 cac->channel,
1964 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
1965 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
1968 } else {
1969 ptr = cmdline;
1970 i = atoi(ptr++);
1971 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
1972 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1973 uint8_t validArgumentCount = 0;
1974 ptr = strchr(ptr, ' ');
1975 if (ptr) {
1976 val = atoi(++ptr);
1977 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1978 cac->auxChannelIndex = val;
1979 validArgumentCount++;
1982 ptr = strchr(ptr, ' ');
1983 if (ptr) {
1984 val = atoi(++ptr);
1985 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
1986 cac->band = val;
1987 validArgumentCount++;
1990 ptr = strchr(ptr, ' ');
1991 if (ptr) {
1992 val = atoi(++ptr);
1993 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
1994 cac->channel = val;
1995 validArgumentCount++;
1998 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
2000 if (validArgumentCount != 5) {
2001 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
2003 } else {
2004 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
2008 #endif
2010 static void dumpValues(uint16_t valueSection)
2012 uint32_t i;
2013 const clivalue_t *value;
2014 for (i = 0; i < VALUE_COUNT; i++) {
2015 value = &valueTable[i];
2017 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
2018 continue;
2021 cliPrintf("set %s = ", valueTable[i].name);
2022 cliPrintVar(value, 0);
2023 cliPrint("\r\n");
2027 typedef enum {
2028 DUMP_MASTER = (1 << 0),
2029 DUMP_PROFILE = (1 << 1),
2030 DUMP_RATES = (1 << 2),
2031 DUMP_ALL = (1 << 3),
2032 } dumpFlags_e;
2034 static const char* const sectionBreak = "\r\n";
2036 #define printSectionBreak() cliPrintf((char *)sectionBreak)
2038 static void cliDump(char *cmdline)
2040 unsigned int i;
2041 char buf[16];
2042 uint32_t mask;
2044 #ifndef USE_QUAD_MIXER_ONLY
2045 float thr, roll, pitch, yaw;
2046 #endif
2048 uint8_t dumpMask = DUMP_MASTER;
2049 if (strcasecmp(cmdline, "master") == 0) {
2050 dumpMask = DUMP_MASTER; // only
2052 if (strcasecmp(cmdline, "profile") == 0) {
2053 dumpMask = DUMP_PROFILE; // only
2055 if (strcasecmp(cmdline, "rates") == 0) {
2056 dumpMask = DUMP_RATES;
2059 if (strcasecmp(cmdline, "all") == 0) {
2060 dumpMask = DUMP_ALL; // All profiles and rates
2063 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
2065 cliPrint("\r\n# version\r\n");
2066 cliVersion(NULL);
2068 printSectionBreak();
2069 cliPrint("\r\n# name\r\n");
2070 cliName(NULL);
2072 cliPrint("\r\n# mixer\r\n");
2074 #ifndef USE_QUAD_MIXER_ONLY
2075 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2077 cliPrintf("mmix reset\r\n");
2079 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2080 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
2081 break;
2082 thr = masterConfig.customMotorMixer[i].throttle;
2083 roll = masterConfig.customMotorMixer[i].roll;
2084 pitch = masterConfig.customMotorMixer[i].pitch;
2085 yaw = masterConfig.customMotorMixer[i].yaw;
2086 cliPrintf("mmix %d", i);
2087 if (thr < 0)
2088 cliWrite(' ');
2089 cliPrintf("%s", ftoa(thr, buf));
2090 if (roll < 0)
2091 cliWrite(' ');
2092 cliPrintf("%s", ftoa(roll, buf));
2093 if (pitch < 0)
2094 cliWrite(' ');
2095 cliPrintf("%s", ftoa(pitch, buf));
2096 if (yaw < 0)
2097 cliWrite(' ');
2098 cliPrintf("%s\r\n", ftoa(yaw, buf));
2101 #ifdef USE_SERVOS
2102 // print custom servo mixer if exists
2103 cliPrintf("smix reset\r\n");
2105 for (i = 0; i < MAX_SERVO_RULES; i++) {
2107 if (masterConfig.customServoMixer[i].rate == 0)
2108 break;
2110 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
2112 masterConfig.customServoMixer[i].targetChannel,
2113 masterConfig.customServoMixer[i].inputSource,
2114 masterConfig.customServoMixer[i].rate,
2115 masterConfig.customServoMixer[i].speed,
2116 masterConfig.customServoMixer[i].min,
2117 masterConfig.customServoMixer[i].max,
2118 masterConfig.customServoMixer[i].box
2122 #endif
2123 #endif
2125 cliPrint("\r\n# feature\r\n");
2126 mask = featureMask();
2127 for (i = 0; ; i++) { // disable all feature first
2128 if (featureNames[i] == NULL)
2129 break;
2130 cliPrintf("feature -%s\r\n", featureNames[i]);
2132 for (i = 0; ; i++) { // reenable what we want.
2133 if (featureNames[i] == NULL)
2134 break;
2135 if (mask & (1 << i))
2136 cliPrintf("feature %s\r\n", featureNames[i]);
2139 #ifdef BEEPER
2140 cliPrint("\r\n# beeper\r\n");
2141 uint8_t beeperCount = beeperTableEntryCount();
2142 mask = getBeeperOffMask();
2143 for (int i = 0; i < (beeperCount-2); i++) {
2144 if (mask & (1 << i))
2145 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
2146 else
2147 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
2149 #endif
2151 cliPrint("\r\n# map\r\n");
2152 for (i = 0; i < 8; i++)
2153 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2154 buf[i] = '\0';
2155 cliPrintf("map %s\r\n", buf);
2157 cliPrint("\r\n# serial\r\n");
2158 cliSerial("");
2160 #ifdef LED_STRIP
2161 cliPrint("\r\n# led\r\n");
2162 cliLed("");
2164 cliPrint("\r\n# color\r\n");
2165 cliColor("");
2167 cliPrint("\r\n# mode_color\r\n");
2168 cliModeColor("");
2169 #endif
2171 cliPrint("\r\n# aux\r\n");
2172 cliAux("");
2174 cliPrint("\r\n# adjrange\r\n");
2175 cliAdjustmentRange("");
2177 cliPrintf("\r\n# rxrange\r\n");
2178 cliRxRange("");
2180 #ifdef USE_SERVOS
2181 cliPrint("\r\n# servo\r\n");
2182 cliServo("");
2184 // print servo directions
2185 unsigned int channel;
2187 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2188 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2189 if (servoDirection(i, channel) < 0) {
2190 cliPrintf("smix reverse %d %d r\r\n", i , channel);
2194 #endif
2196 #ifdef VTX
2197 cliPrint("\r\n# vtx\r\n");
2198 cliVtx("");
2199 #endif
2201 cliPrint("\r\n# master\r\n");
2202 dumpValues(MASTER_VALUE);
2204 cliPrint("\r\n# rxfail\r\n");
2205 cliRxFail("");
2207 if (dumpMask & DUMP_ALL) {
2208 uint8_t activeProfile = masterConfig.current_profile_index;
2209 uint8_t profileCount;
2210 for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
2211 cliDumpProfile(profileCount);
2213 uint8_t currentRateIndex = currentProfile->activeRateProfile;
2214 uint8_t rateCount;
2215 for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
2216 cliDumpRateProfile(rateCount);
2218 cliPrint("\r\n# restore original rateprofile selection\r\n");
2219 changeControlRateProfile(currentRateIndex);
2220 cliRateProfile("");
2223 cliPrint("\r\n# restore original profile selection\r\n");
2224 changeProfile(activeProfile);
2225 cliProfile("");
2226 printSectionBreak();
2228 cliPrint("\r\n# save configuration\r\nsave\r\n");
2229 } else {
2230 cliDumpProfile(masterConfig.current_profile_index);
2231 cliDumpRateProfile(currentProfile->activeRateProfile);
2235 if (dumpMask & DUMP_PROFILE) {
2236 cliDumpProfile(masterConfig.current_profile_index);
2239 if (dumpMask & DUMP_RATES) {
2240 cliDumpRateProfile(currentProfile->activeRateProfile);
2244 void cliDumpProfile(uint8_t profileIndex)
2246 if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
2247 return;
2248 changeProfile(profileIndex);
2249 cliPrint("\r\n# profile\r\n");
2250 cliProfile("");
2251 printSectionBreak();
2252 dumpValues(PROFILE_VALUE);
2255 void cliDumpRateProfile(uint8_t rateProfileIndex)
2257 if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
2258 return;
2259 changeControlRateProfile(rateProfileIndex);
2260 cliPrint("\r\n# rateprofile\r\n");
2261 cliRateProfile("");
2262 printSectionBreak();
2263 dumpValues(PROFILE_RATE_VALUE);
2266 void cliEnter(serialPort_t *serialPort)
2268 cliMode = 1;
2269 cliPort = serialPort;
2270 setPrintfSerialPort(cliPort);
2271 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
2272 (bufWrite_t)serialWriteBufShim, serialPort);
2274 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2275 cliPrompt();
2276 ENABLE_ARMING_FLAG(PREVENT_ARMING);
2279 static void cliExit(char *cmdline)
2281 UNUSED(cmdline);
2283 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2284 bufWriterFlush(cliWriter);
2286 *cliBuffer = '\0';
2287 bufferIndex = 0;
2288 cliMode = 0;
2289 // incase a motor was left running during motortest, clear it here
2290 mixerResetDisarmedMotors();
2291 cliReboot();
2293 cliWriter = NULL;
2296 static void cliFeature(char *cmdline)
2298 uint32_t i;
2299 uint32_t len;
2300 uint32_t mask;
2302 len = strlen(cmdline);
2303 mask = featureMask();
2305 if (len == 0) {
2306 cliPrint("Enabled: ");
2307 for (i = 0; ; i++) {
2308 if (featureNames[i] == NULL)
2309 break;
2310 if (mask & (1 << i))
2311 cliPrintf("%s ", featureNames[i]);
2313 cliPrint("\r\n");
2314 } else if (strncasecmp(cmdline, "list", len) == 0) {
2315 cliPrint("Available: ");
2316 for (i = 0; ; i++) {
2317 if (featureNames[i] == NULL)
2318 break;
2319 cliPrintf("%s ", featureNames[i]);
2321 cliPrint("\r\n");
2322 return;
2323 } else {
2324 bool remove = false;
2325 if (cmdline[0] == '-') {
2326 // remove feature
2327 remove = true;
2328 cmdline++; // skip over -
2329 len--;
2332 for (i = 0; ; i++) {
2333 if (featureNames[i] == NULL) {
2334 cliPrint("Invalid name\r\n");
2335 break;
2338 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2340 mask = 1 << i;
2341 #ifndef GPS
2342 if (mask & FEATURE_GPS) {
2343 cliPrint("unavailable\r\n");
2344 break;
2346 #endif
2347 #ifndef SONAR
2348 if (mask & FEATURE_SONAR) {
2349 cliPrint("unavailable\r\n");
2350 break;
2352 #endif
2353 if (remove) {
2354 featureClear(mask);
2355 cliPrint("Disabled");
2356 } else {
2357 featureSet(mask);
2358 cliPrint("Enabled");
2360 cliPrintf(" %s\r\n", featureNames[i]);
2361 break;
2367 #ifdef BEEPER
2368 static void cliBeeper(char *cmdline)
2370 uint32_t i;
2371 uint32_t len = strlen(cmdline);;
2372 uint8_t beeperCount = beeperTableEntryCount();
2373 uint32_t mask = getBeeperOffMask();
2375 if (len == 0) {
2376 cliPrintf("Disabled:");
2377 for (int i = 0; ; i++) {
2378 if (i == beeperCount-2){
2379 if (mask == 0)
2380 cliPrint(" none");
2381 break;
2383 if (mask & (1 << i))
2384 cliPrintf(" %s", beeperNameForTableIndex(i));
2386 cliPrint("\r\n");
2387 } else if (strncasecmp(cmdline, "list", len) == 0) {
2388 cliPrint("Available:");
2389 for (i = 0; i < beeperCount; i++)
2390 cliPrintf(" %s", beeperNameForTableIndex(i));
2391 cliPrint("\r\n");
2392 return;
2393 } else {
2394 bool remove = false;
2395 if (cmdline[0] == '-') {
2396 remove = true; // this is for beeper OFF condition
2397 cmdline++;
2398 len--;
2401 for (i = 0; ; i++) {
2402 if (i == beeperCount) {
2403 cliPrint("Invalid name\r\n");
2404 break;
2406 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
2407 if (remove) { // beeper off
2408 if (i == BEEPER_ALL-1)
2409 beeperOffSetAll(beeperCount-2);
2410 else
2411 if (i == BEEPER_PREFERENCE-1)
2412 setBeeperOffMask(getPreferredBeeperOffMask());
2413 else {
2414 mask = 1 << i;
2415 beeperOffSet(mask);
2417 cliPrint("Disabled");
2419 else { // beeper on
2420 if (i == BEEPER_ALL-1)
2421 beeperOffClearAll();
2422 else
2423 if (i == BEEPER_PREFERENCE-1)
2424 setPreferredBeeperOffMask(getBeeperOffMask());
2425 else {
2426 mask = 1 << i;
2427 beeperOffClear(mask);
2429 cliPrint("Enabled");
2431 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
2432 break;
2437 #endif
2440 #ifdef GPS
2441 static void cliGpsPassthrough(char *cmdline)
2443 UNUSED(cmdline);
2445 gpsEnablePassthrough(cliPort);
2447 #endif
2449 static void cliHelp(char *cmdline)
2451 uint32_t i = 0;
2453 UNUSED(cmdline);
2455 for (i = 0; i < CMD_COUNT; i++) {
2456 cliPrint(cmdTable[i].name);
2457 #ifndef SKIP_CLI_COMMAND_HELP
2458 if (cmdTable[i].description) {
2459 cliPrintf(" - %s", cmdTable[i].description);
2461 if (cmdTable[i].args) {
2462 cliPrintf("\r\n\t%s", cmdTable[i].args);
2464 #endif
2465 cliPrint("\r\n");
2469 static void cliMap(char *cmdline)
2471 uint32_t len;
2472 uint32_t i;
2473 char out[9];
2475 len = strlen(cmdline);
2477 if (len == 8) {
2478 // uppercase it
2479 for (i = 0; i < 8; i++)
2480 cmdline[i] = toupper((unsigned char)cmdline[i]);
2481 for (i = 0; i < 8; i++) {
2482 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2483 continue;
2484 cliShowParseError();
2485 return;
2487 parseRcChannels(cmdline, &masterConfig.rxConfig);
2489 cliPrint("Map: ");
2490 for (i = 0; i < 8; i++)
2491 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2492 out[i] = '\0';
2493 cliPrintf("%s\r\n", out);
2496 #ifndef USE_QUAD_MIXER_ONLY
2497 static void cliMixer(char *cmdline)
2499 int i;
2500 int len;
2502 len = strlen(cmdline);
2504 if (len == 0) {
2505 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2506 return;
2507 } else if (strncasecmp(cmdline, "list", len) == 0) {
2508 cliPrint("Available mixers: ");
2509 for (i = 0; ; i++) {
2510 if (mixerNames[i] == NULL)
2511 break;
2512 cliPrintf("%s ", mixerNames[i]);
2514 cliPrint("\r\n");
2515 return;
2518 for (i = 0; ; i++) {
2519 if (mixerNames[i] == NULL) {
2520 cliPrint("Invalid name\r\n");
2521 return;
2523 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2524 masterConfig.mixerMode = i + 1;
2525 break;
2529 cliMixer("");
2531 #endif
2533 static void cliMotor(char *cmdline)
2535 int motor_index = 0;
2536 int motor_value = 0;
2537 int index = 0;
2538 char *pch = NULL;
2539 char *saveptr;
2541 if (isEmpty(cmdline)) {
2542 cliShowParseError();
2543 return;
2546 pch = strtok_r(cmdline, " ", &saveptr);
2547 while (pch != NULL) {
2548 switch (index) {
2549 case 0:
2550 motor_index = atoi(pch);
2551 break;
2552 case 1:
2553 motor_value = atoi(pch);
2554 break;
2556 index++;
2557 pch = strtok_r(NULL, " ", &saveptr);
2560 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2561 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2562 return;
2565 if (index == 2) {
2566 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2567 cliShowArgumentRangeError("value", 1000, 2000);
2568 return;
2569 } else {
2570 motor_disarmed[motor_index] = motor_value;
2574 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2577 static void cliName(char *cmdline)
2579 uint32_t len = strlen(cmdline);
2580 if (len > 0) {
2581 memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
2582 strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
2584 cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
2586 return;
2589 static void cliPlaySound(char *cmdline)
2591 #if FLASH_SIZE <= 64
2592 UNUSED(cmdline);
2593 #else
2594 int i;
2595 const char *name;
2596 static int lastSoundIdx = -1;
2598 if (isEmpty(cmdline)) {
2599 i = lastSoundIdx + 1; //next sound index
2600 if ((name=beeperNameForTableIndex(i)) == NULL) {
2601 while (true) { //no name for index; try next one
2602 if (++i >= beeperTableEntryCount())
2603 i = 0; //if end then wrap around to first entry
2604 if ((name=beeperNameForTableIndex(i)) != NULL)
2605 break; //if name OK then play sound below
2606 if (i == lastSoundIdx + 1) { //prevent infinite loop
2607 cliPrintf("Error playing sound\r\n");
2608 return;
2612 } else { //index value was given
2613 i = atoi(cmdline);
2614 if ((name=beeperNameForTableIndex(i)) == NULL) {
2615 cliPrintf("No sound for index %d\r\n", i);
2616 return;
2619 lastSoundIdx = i;
2620 beeperSilence();
2621 cliPrintf("Playing sound %d: %s\r\n", i, name);
2622 beeper(beeperModeForTableIndex(i));
2623 #endif
2626 static void cliProfile(char *cmdline)
2628 int i;
2630 if (isEmpty(cmdline)) {
2631 cliPrintf("profile %d\r\n", getCurrentProfile());
2632 return;
2633 } else {
2634 i = atoi(cmdline);
2635 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2636 masterConfig.current_profile_index = i;
2637 writeEEPROM();
2638 readEEPROM();
2639 cliProfile("");
2644 static void cliRateProfile(char *cmdline)
2646 int i;
2648 if (isEmpty(cmdline)) {
2649 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2650 return;
2651 } else {
2652 i = atoi(cmdline);
2653 if (i >= 0 && i < MAX_RATEPROFILES) {
2654 changeControlRateProfile(i);
2655 cliRateProfile("");
2660 static void cliReboot(void)
2662 cliRebootEx(false);
2665 static void cliRebootEx(bool bootLoader)
2667 cliPrint("\r\nRebooting");
2668 bufWriterFlush(cliWriter);
2669 waitForSerialPortToFinishTransmitting(cliPort);
2670 stopPwmAllMotors();
2671 if (bootLoader) {
2672 systemResetToBootloader();
2673 return;
2675 systemReset();
2678 static void cliSave(char *cmdline)
2680 UNUSED(cmdline);
2682 cliPrint("Saving");
2683 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2684 writeEEPROM();
2685 cliReboot();
2688 static void cliDefaults(char *cmdline)
2690 UNUSED(cmdline);
2692 cliPrint("Resetting to defaults");
2693 resetEEPROM();
2694 cliReboot();
2697 static void cliPrint(const char *str)
2699 while (*str)
2700 bufWriterAppend(cliWriter, *str++);
2702 #ifdef USE_SLOW_SERIAL_CLI
2703 delay(1);
2704 #endif
2707 static void cliPutp(void *p, char ch)
2709 bufWriterAppend(p, ch);
2712 static void cliPrintf(const char *fmt, ...)
2714 va_list va;
2715 va_start(va, fmt);
2716 tfp_format(cliWriter, cliPutp, fmt, va);
2717 va_end(va);
2719 #ifdef USE_SLOW_SERIAL_CLI
2720 delay(1);
2721 #endif
2724 static void cliWrite(uint8_t ch)
2726 bufWriterAppend(cliWriter, ch);
2729 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2731 int32_t value = 0;
2732 char buf[8];
2734 void *ptr = var->ptr;
2735 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2736 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2739 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2740 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2743 switch (var->type & VALUE_TYPE_MASK) {
2744 case VAR_UINT8:
2745 value = *(uint8_t *)ptr;
2746 break;
2748 case VAR_INT8:
2749 value = *(int8_t *)ptr;
2750 break;
2752 case VAR_UINT16:
2753 value = *(uint16_t *)ptr;
2754 break;
2756 case VAR_INT16:
2757 value = *(int16_t *)ptr;
2758 break;
2760 case VAR_UINT32:
2761 value = *(uint32_t *)ptr;
2762 break;
2764 case VAR_FLOAT:
2765 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2766 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2767 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2768 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2770 return; // return from case for float only
2773 switch(var->type & VALUE_MODE_MASK) {
2774 case MODE_DIRECT:
2775 cliPrintf("%d", value);
2776 if (full) {
2777 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2779 break;
2780 case MODE_LOOKUP:
2781 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2782 break;
2786 static void cliPrintVarRange(const clivalue_t *var)
2788 switch (var->type & VALUE_MODE_MASK) {
2789 case (MODE_DIRECT): {
2790 cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
2792 break;
2793 case (MODE_LOOKUP): {
2794 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
2795 cliPrint("Allowed values:");
2796 uint8_t i;
2797 for (i = 0; i < tableEntry->valueCount ; i++) {
2798 if (i > 0)
2799 cliPrint(",");
2800 cliPrintf(" %s", tableEntry->values[i]);
2802 cliPrint("\r\n");
2804 break;
2808 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2810 void *ptr = var->ptr;
2811 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2812 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2814 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2815 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2818 switch (var->type & VALUE_TYPE_MASK) {
2819 case VAR_UINT8:
2820 case VAR_INT8:
2821 *(int8_t *)ptr = value.int_value;
2822 break;
2824 case VAR_UINT16:
2825 case VAR_INT16:
2826 *(int16_t *)ptr = value.int_value;
2827 break;
2829 case VAR_UINT32:
2830 *(uint32_t *)ptr = value.int_value;
2831 break;
2833 case VAR_FLOAT:
2834 *(float *)ptr = (float)value.float_value;
2835 break;
2839 static void cliSet(char *cmdline)
2841 uint32_t i;
2842 uint32_t len;
2843 const clivalue_t *val;
2844 char *eqptr = NULL;
2846 len = strlen(cmdline);
2848 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2849 cliPrint("Current settings: \r\n");
2850 for (i = 0; i < VALUE_COUNT; i++) {
2851 val = &valueTable[i];
2852 cliPrintf("%s = ", valueTable[i].name);
2853 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2854 cliPrint("\r\n");
2856 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2857 // has equals
2859 char *lastNonSpaceCharacter = eqptr;
2860 while (*(lastNonSpaceCharacter - 1) == ' ') {
2861 lastNonSpaceCharacter--;
2863 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2865 // skip the '=' and any ' ' characters
2866 eqptr++;
2867 while (*(eqptr) == ' ') {
2868 eqptr++;
2871 for (i = 0; i < VALUE_COUNT; i++) {
2872 val = &valueTable[i];
2873 // ensure exact match when setting to prevent setting variables with shorter names
2874 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2876 bool changeValue = false;
2877 int_float_value_t tmp = { 0 };
2878 switch (valueTable[i].type & VALUE_MODE_MASK) {
2879 case MODE_DIRECT: {
2880 int32_t value = 0;
2881 float valuef = 0;
2883 value = atoi(eqptr);
2884 valuef = fastA2F(eqptr);
2886 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2888 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2889 tmp.float_value = valuef;
2890 else
2891 tmp.int_value = value;
2893 changeValue = true;
2896 break;
2897 case MODE_LOOKUP: {
2898 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2899 bool matched = false;
2900 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2901 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2903 if (matched) {
2904 tmp.int_value = tableValueIndex;
2905 changeValue = true;
2909 break;
2912 if (changeValue) {
2913 cliSetVar(val, tmp);
2915 cliPrintf("%s set to ", valueTable[i].name);
2916 cliPrintVar(val, 0);
2917 } else {
2918 cliPrint("Invalid value\r\n");
2919 cliPrintVarRange(val);
2922 return;
2925 cliPrint("Invalid name\r\n");
2926 } else {
2927 // no equals, check for matching variables.
2928 cliGet(cmdline);
2932 static void cliGet(char *cmdline)
2934 uint32_t i;
2935 const clivalue_t *val;
2936 int matchedCommands = 0;
2938 for (i = 0; i < VALUE_COUNT; i++) {
2939 if (strstr(valueTable[i].name, cmdline)) {
2940 val = &valueTable[i];
2941 cliPrintf("%s = ", valueTable[i].name);
2942 cliPrintVar(val, 0);
2943 cliPrint("\n");
2944 cliPrintVarRange(val);
2945 cliPrint("\r\n");
2947 matchedCommands++;
2952 if (matchedCommands) {
2953 return;
2956 cliPrint("Invalid name\r\n");
2959 static void cliStatus(char *cmdline)
2961 UNUSED(cmdline);
2963 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2964 millis() / 1000,
2965 vbat,
2966 batteryCellCount,
2967 getBatteryStateString(),
2968 constrain(averageSystemLoadPercent, 0, 100)
2971 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2973 #if (FLASH_SIZE > 64)
2974 uint8_t i;
2975 uint32_t mask;
2976 uint32_t detectedSensorsMask = sensorsMask();
2978 for (i = 0; ; i++) {
2980 if (sensorTypeNames[i] == NULL)
2981 break;
2983 mask = (1 << i);
2984 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2985 const char *sensorHardware;
2986 uint8_t sensorHardwareIndex = detectedSensors[i];
2987 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2989 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2991 if (mask == SENSOR_ACC && acc.revisionCode) {
2992 cliPrintf(".%c", acc.revisionCode);
2996 #endif
2997 cliPrint("\r\n");
2999 #ifdef USE_I2C
3000 uint16_t i2cErrorCounter = i2cGetErrorCounter();
3001 #else
3002 uint16_t i2cErrorCounter = 0;
3003 #endif
3005 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
3007 #ifdef USE_SDCARD
3008 cliSdInfo(NULL);
3009 #endif
3012 #ifndef SKIP_TASK_STATISTICS
3013 static void cliTasks(char *cmdline)
3015 UNUSED(cmdline);
3016 int maxLoadSum = 0;
3017 int averageLoadSum = 0;
3019 cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
3020 for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; taskId++) {
3021 cfTaskInfo_t taskInfo;
3022 getTaskInfo(taskId, &taskInfo);
3023 if (taskInfo.isEnabled) {
3024 int taskFrequency;
3025 int subTaskFrequency;
3026 if (taskId == TASK_GYROPID) {
3027 subTaskFrequency = (int)(1000000.0f / ((float)cycleTime));
3028 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
3029 if (masterConfig.pid_process_denom > 1) {
3030 cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
3031 } else {
3032 taskFrequency = subTaskFrequency;
3033 cliPrintf("%02d - (%8s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
3035 } else {
3036 taskFrequency = (int)(1000000.0f / ((float)taskInfo.latestDeltaTime));
3037 cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
3039 const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
3040 const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
3041 if (taskId != TASK_SERIAL) {
3042 maxLoadSum += maxLoad;
3043 averageLoadSum += averageLoad;
3045 cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n",
3046 taskFrequency, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime,
3047 maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
3048 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) {
3049 cliPrintf(" - (%12s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency);
3053 cliPrintf("Total (excluding SERIAL) %22d.%1d%% %4d.%1d%%\r\n", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
3055 #endif
3057 static void cliVersion(char *cmdline)
3059 UNUSED(cmdline);
3061 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
3062 targetName,
3063 FC_VERSION_STRING,
3064 buildDate,
3065 buildTime,
3066 shortGitRevision
3070 void cliProcess(void)
3072 if (!cliWriter) {
3073 return;
3076 // Be a little bit tricky. Flush the last inputs buffer, if any.
3077 bufWriterFlush(cliWriter);
3079 while (serialRxBytesWaiting(cliPort)) {
3080 uint8_t c = serialRead(cliPort);
3081 if (c == '\t' || c == '?') {
3082 // do tab completion
3083 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
3084 uint32_t i = bufferIndex;
3085 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3086 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
3087 continue;
3088 if (!pstart)
3089 pstart = cmd;
3090 pend = cmd;
3092 if (pstart) { /* Buffer matches one or more commands */
3093 for (; ; bufferIndex++) {
3094 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
3095 break;
3096 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
3097 /* Unambiguous -- append a space */
3098 cliBuffer[bufferIndex++] = ' ';
3099 cliBuffer[bufferIndex] = '\0';
3100 break;
3102 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
3105 if (!bufferIndex || pstart != pend) {
3106 /* Print list of ambiguous matches */
3107 cliPrint("\r\033[K");
3108 for (cmd = pstart; cmd <= pend; cmd++) {
3109 cliPrint(cmd->name);
3110 cliWrite('\t');
3112 cliPrompt();
3113 i = 0; /* Redraw prompt */
3115 for (; i < bufferIndex; i++)
3116 cliWrite(cliBuffer[i]);
3117 } else if (!bufferIndex && c == 4) { // CTRL-D
3118 cliExit(cliBuffer);
3119 return;
3120 } else if (c == 12) { // NewPage / CTRL-L
3121 // clear screen
3122 cliPrint("\033[2J\033[1;1H");
3123 cliPrompt();
3124 } else if (bufferIndex && (c == '\n' || c == '\r')) {
3125 // enter pressed
3126 cliPrint("\r\n");
3128 // Strip comment starting with # from line
3129 char *p = cliBuffer;
3130 p = strchr(p, '#');
3131 if (NULL != p) {
3132 bufferIndex = (uint32_t)(p - cliBuffer);
3135 // Strip trailing whitespace
3136 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
3137 bufferIndex--;
3140 // Process non-empty lines
3141 if (bufferIndex > 0) {
3142 cliBuffer[bufferIndex] = 0; // null terminate
3144 const clicmd_t *cmd;
3145 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3146 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
3147 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
3148 break;
3150 if(cmd < cmdTable + CMD_COUNT)
3151 cmd->func(cliBuffer + strlen(cmd->name) + 1);
3152 else
3153 cliPrint("Unknown command, try 'help'");
3154 bufferIndex = 0;
3157 memset(cliBuffer, 0, sizeof(cliBuffer));
3159 // 'exit' will reset this flag, so we don't need to print prompt again
3160 if (!cliMode)
3161 return;
3163 cliPrompt();
3164 } else if (c == 127) {
3165 // backspace
3166 if (bufferIndex) {
3167 cliBuffer[--bufferIndex] = 0;
3168 cliPrint("\010 \010");
3170 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
3171 if (!bufferIndex && c == ' ')
3172 continue; // Ignore leading spaces
3173 cliBuffer[bufferIndex++] = c;
3174 cliWrite(c);
3179 #if (FLASH_SIZE > 64)
3180 static void cliResource(char *cmdline)
3182 UNUSED(cmdline);
3183 cliPrintf("IO:\r\n----------------------\r\n");
3184 for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) {
3185 const char* owner;
3186 owner = ownerNames[ioRecs[i].owner];
3188 const char* resource;
3189 resource = resourceNames[ioRecs[i].resource];
3191 if (ioRecs[i].index > 0) {
3192 cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
3193 } else {
3194 cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
3198 #endif
3200 void cliDfu(char *cmdLine)
3202 UNUSED(cmdLine);
3203 cliPrint("\r\nRestarting in DFU mode");
3204 cliRebootEx(true);
3207 void cliInit(serialConfig_t *serialConfig)
3209 UNUSED(serialConfig);
3211 #endif