delete space to see all rate columns in a row
[betaflight.git] / src / main / io / serial_cli.c
blobb1bf0531632b71da3301af6580a4b8a693320a86
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", "ONESHOT125",
210 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES",
211 "OSD", NULL
214 // sync this with rxFailsafeChannelMode_e
215 static const char rxFailsafeModeCharacters[] = "ahs";
217 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
218 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
219 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
222 #if (FLASH_SIZE > 64)
223 // sync this with sensors_e
224 static const char * const sensorTypeNames[] = {
225 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
228 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
230 static const char * const sensorHardwareNames[4][11] = {
231 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE", NULL },
232 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
233 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
234 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
236 #endif
238 typedef struct {
239 const char *name;
240 #ifndef SKIP_CLI_COMMAND_HELP
241 const char *description;
242 const char *args;
243 #endif
244 void (*func)(char *cmdline);
245 } clicmd_t;
247 #ifndef SKIP_CLI_COMMAND_HELP
248 #define CLI_COMMAND_DEF(name, description, args, method) \
250 name , \
251 description , \
252 args , \
253 method \
255 #else
256 #define CLI_COMMAND_DEF(name, description, args, method) \
258 name, \
259 method \
261 #endif
263 // should be sorted a..z for bsearch()
264 const clicmd_t cmdTable[] = {
265 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
266 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
267 #ifdef LED_STRIP
268 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
269 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
270 #endif
271 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
272 CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
273 CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump),
274 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
275 CLI_COMMAND_DEF("feature", "configure features",
276 "list\r\n"
277 "\t<+|->[name]", cliFeature),
278 #ifdef USE_FLASHFS
279 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
280 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
281 #ifdef USE_FLASH_TOOLS
282 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
283 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
284 #endif
285 #endif
286 CLI_COMMAND_DEF("get", "get variable value",
287 "[name]", cliGet),
288 #ifdef GPS
289 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
290 #endif
291 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
292 #ifdef LED_STRIP
293 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
294 #endif
295 CLI_COMMAND_DEF("map", "configure rc channel order",
296 "[<map>]", cliMap),
297 #ifndef USE_QUAD_MIXER_ONLY
298 CLI_COMMAND_DEF("mixer", "configure mixer",
299 "list\r\n"
300 "\t<name>", cliMixer),
301 #endif
302 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
303 CLI_COMMAND_DEF("motor", "get/set motor",
304 "<index> [<value>]", cliMotor),
305 CLI_COMMAND_DEF("play_sound", NULL,
306 "[<index>]\r\n", cliPlaySound),
307 CLI_COMMAND_DEF("profile", "change profile",
308 "[<index>]", cliProfile),
309 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
310 #if (FLASH_SIZE > 64)
311 CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
312 #endif
313 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
314 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
315 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
316 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
317 #ifndef SKIP_SERIAL_PASSTHROUGH
318 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
319 "<id> [baud] [mode] : passthrough to serial",
320 cliSerialPassthrough),
321 #endif
322 #ifdef USE_SERVOS
323 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
324 #endif
325 CLI_COMMAND_DEF("set", "change setting",
326 "[<name>=<value>]", cliSet),
327 #ifdef USE_SERVOS
328 CLI_COMMAND_DEF("smix", "servo mixer",
329 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
330 "\treset\r\n"
331 "\tload <mixer>\r\n"
332 "\treverse <servo> <source> r|n", cliServoMix),
333 #endif
334 #ifdef USE_SDCARD
335 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
336 #endif
337 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
338 #ifndef SKIP_TASK_STATISTICS
339 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
340 #endif
341 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
342 #ifdef BEEPER
343 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
344 "\t<+|->[name]", cliBeeper),
345 #endif
346 #ifdef VTX
347 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
348 #endif
349 CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName),
351 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
353 static const char * const lookupTableOffOn[] = {
354 "OFF", "ON"
357 static const char * const lookupTableUnit[] = {
358 "IMPERIAL", "METRIC"
361 static const char * const lookupTableAlignment[] = {
362 "DEFAULT",
363 "CW0",
364 "CW90",
365 "CW180",
366 "CW270",
367 "CW0FLIP",
368 "CW90FLIP",
369 "CW180FLIP",
370 "CW270FLIP"
373 #ifdef GPS
374 static const char * const lookupTableGPSProvider[] = {
375 "NMEA", "UBLOX"
378 static const char * const lookupTableGPSSBASMode[] = {
379 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
381 #endif
383 static const char * const lookupTableCurrentSensor[] = {
384 "NONE", "ADC", "VIRTUAL"
387 #ifdef USE_SERVOS
388 static const char * const lookupTableGimbalMode[] = {
389 "NORMAL", "MIXTILT"
391 #endif
393 #ifdef BLACKBOX
394 static const char * const lookupTableBlackboxDevice[] = {
395 "SERIAL", "SPIFLASH", "SDCARD"
397 #endif
399 static const char * const lookupTablePidController[] = {
400 "LEGACY", "BETAFLIGHT"
403 #ifdef SERIAL_RX
404 static const char * const lookupTableSerialRX[] = {
405 "SPEK1024",
406 "SPEK2048",
407 "SBUS",
408 "SUMD",
409 "SUMH",
410 "XB-B",
411 "XB-B-RJ01",
412 "IBUS",
413 "JETIEXBUS"
415 #endif
417 static const char * const lookupTableGyroLpf[] = {
418 "OFF",
419 "188HZ",
420 "98HZ",
421 "42HZ",
422 "20HZ",
423 "10HZ",
424 "5HZ",
425 "EXPERIMENTAL"
428 static const char * const lookupTableAccHardware[] = {
429 "AUTO",
430 "NONE",
431 "ADXL345",
432 "MPU6050",
433 "MMA8452",
434 "BMA280",
435 "LSM303DLHC",
436 "MPU6000",
437 "MPU6500",
438 "FAKE"
441 #ifdef BARO
442 static const char * const lookupTableBaroHardware[] = {
443 "AUTO",
444 "NONE",
445 "BMP085",
446 "MS5611",
447 "BMP280"
449 #endif
451 #ifdef MAG
452 static const char * const lookupTableMagHardware[] = {
453 "AUTO",
454 "NONE",
455 "HMC5883",
456 "AK8975",
457 "AK8963"
459 #endif
461 static const char * const lookupTableDebug[DEBUG_COUNT] = {
462 "NONE",
463 "CYCLETIME",
464 "BATTERY",
465 "GYRO",
466 "ACCELEROMETER",
467 "MIXER",
468 "AIRMODE",
469 "PIDLOOP",
470 "NOTCH",
473 #ifdef OSD
474 static const char * const lookupTableOsdType[] = {
475 "AUTO",
476 "PAL",
477 "NTSC"
479 #endif
481 static const char * const lookupTableSuperExpoYaw[] = {
482 "OFF", "ON", "ALWAYS"
485 static const char * const lookupTablePwmProtocol[] = {
486 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
489 static const char * const lookupDeltaMethod[] = {
490 "ERROR", "MEASUREMENT"
493 typedef struct lookupTableEntry_s {
494 const char * const *values;
495 const uint8_t valueCount;
496 } lookupTableEntry_t;
498 typedef enum {
499 TABLE_OFF_ON = 0,
500 TABLE_UNIT,
501 TABLE_ALIGNMENT,
502 #ifdef GPS
503 TABLE_GPS_PROVIDER,
504 TABLE_GPS_SBAS_MODE,
505 #endif
506 #ifdef BLACKBOX
507 TABLE_BLACKBOX_DEVICE,
508 #endif
509 TABLE_CURRENT_SENSOR,
510 #ifdef USE_SERVOS
511 TABLE_GIMBAL_MODE,
512 #endif
513 TABLE_PID_CONTROLLER,
514 #ifdef SERIAL_RX
515 TABLE_SERIAL_RX,
516 #endif
517 TABLE_GYRO_LPF,
518 TABLE_ACC_HARDWARE,
519 #ifdef BARO
520 TABLE_BARO_HARDWARE,
521 #endif
522 #ifdef MAG
523 TABLE_MAG_HARDWARE,
524 #endif
525 TABLE_DEBUG,
526 TABLE_SUPEREXPO_YAW,
527 TABLE_MOTOR_PWM_PROTOCOL,
528 TABLE_DELTA_METHOD,
529 #ifdef OSD
530 TABLE_OSD,
531 #endif
532 } lookupTableIndex_e;
534 static const lookupTableEntry_t lookupTables[] = {
535 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
536 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
537 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
538 #ifdef GPS
539 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
540 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
541 #endif
542 #ifdef BLACKBOX
543 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
544 #endif
545 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
546 #ifdef USE_SERVOS
547 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
548 #endif
549 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
550 #ifdef SERIAL_RX
551 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
552 #endif
553 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
554 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
555 #ifdef BARO
556 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
557 #endif
558 #ifdef MAG
559 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
560 #endif
561 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
562 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
563 { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
564 { lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) },
565 #ifdef OSD
566 { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
567 #endif
570 #define VALUE_TYPE_OFFSET 0
571 #define VALUE_SECTION_OFFSET 4
572 #define VALUE_MODE_OFFSET 6
574 typedef enum {
575 // value type
576 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
577 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
578 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
579 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
580 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
581 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
583 // value section
584 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
585 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
586 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
587 // value mode
588 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
589 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
590 } cliValueFlag_e;
592 #define VALUE_TYPE_MASK (0x0F)
593 #define VALUE_SECTION_MASK (0x30)
594 #define VALUE_MODE_MASK (0xC0)
596 typedef struct cliMinMaxConfig_s {
597 const int32_t min;
598 const int32_t max;
599 } cliMinMaxConfig_t;
601 typedef struct cliLookupTableConfig_s {
602 const lookupTableIndex_e tableIndex;
603 } cliLookupTableConfig_t;
605 typedef union {
606 cliLookupTableConfig_t lookup;
607 cliMinMaxConfig_t minmax;
608 } cliValueConfig_t;
610 typedef struct {
611 const char *name;
612 const uint8_t type; // see cliValueFlag_e
613 void *ptr;
614 const cliValueConfig_t config;
615 } clivalue_t;
617 const clivalue_t valueTable[] = {
618 // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
619 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
620 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
621 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
622 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
623 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
624 { "rc_smooth_interval_ms", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothInterval, .config.minmax = { 0, 255 } },
625 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
626 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
627 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
628 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
629 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
631 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
632 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
633 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
634 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
636 { "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
637 { "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,
638 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
639 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
641 #ifdef CC3D
642 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
643 #endif
644 { "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
645 { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
646 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } },
647 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
649 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
650 { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
651 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
652 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
654 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
656 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
658 #ifdef GPS
659 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
660 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
661 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
662 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
664 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
665 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
666 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
667 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
668 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
669 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
670 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
671 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
672 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
673 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
674 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
675 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
676 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
677 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
678 #endif
679 #ifdef GTUNE
680 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
681 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
682 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
683 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
684 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
685 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
686 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
687 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
688 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
689 #endif
691 #ifdef SERIAL_RX
692 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
693 #endif
694 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
695 #ifdef SPEKTRUM_BIND
696 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
697 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
698 #endif
700 #ifdef TELEMETRY
701 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
702 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
703 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
704 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
705 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
706 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
707 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
708 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
709 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
710 #endif
712 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
713 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
714 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
715 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
716 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
717 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
718 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
719 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
720 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
721 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
723 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
724 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
725 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
727 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
728 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
729 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
731 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
732 { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
733 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
734 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
735 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
736 { "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
737 { "gyro_notch_q", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_notch_q, .config.minmax = { 1, 100 } },
738 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
739 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
740 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
742 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
743 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
744 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
745 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
747 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
748 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
750 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
752 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
753 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
754 #ifdef USE_SERVOS
755 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
756 { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
757 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
758 #endif
760 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
761 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawRate8, .config.minmax = { 0, 250 } },
762 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
763 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
764 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
765 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
766 { "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 } },
767 { "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 } },
768 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
769 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
770 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
771 { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } },
773 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
774 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
775 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
776 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
777 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
778 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
780 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
781 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
783 #ifdef USE_SERVOS
784 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
785 #endif
787 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
788 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
789 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
790 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
791 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
792 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
793 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
795 #ifdef BARO
796 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
797 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
798 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
799 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
800 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
801 #endif
803 #ifdef MAG
804 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
805 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
806 #endif
807 { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
808 { "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
809 { "zero_throttle_stabilisation",VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.zeroThrottleStabilisation, .config.lookup = { TABLE_OFF_ON } },
810 { "motor_accel_limit_percent", VAR_UINT16 | MASTER_VALUE, &masterConfig.profile[0].pidProfile.accelerationLimitPercent, .config.minmax = { 0, 10000 } },
811 { "pid_tolerance_band", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBand, .config.minmax = {0, 200 } },
812 { "tolerance_band_reduction", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBandReduction, .config.minmax = {0, 100 } },
813 { "zero_cross_allowance", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.zeroCrossAllowanceCount, .config.minmax = {0, 50 } },
814 { "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
816 { "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
817 { "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
818 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
819 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
821 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
823 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
824 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
825 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
826 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
827 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
828 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
829 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
830 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
831 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
833 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
834 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
835 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
837 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
838 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
839 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
841 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
842 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
843 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
845 #ifdef BLACKBOX
846 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
847 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
848 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
849 #endif
851 #ifdef VTX
852 { "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } },
853 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } },
854 { "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } },
855 { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
856 #endif
858 #ifdef MAG
859 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
860 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
861 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
862 #endif
863 #ifdef LED_STRIP
864 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
865 #endif
866 #ifdef USE_RTC6705
867 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
868 { "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
869 #endif
870 #ifdef OSD
871 { "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
872 { "osd_main_voltage_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { -480, 480 } },
873 { "osd_rssi_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { -480, 480 } },
874 { "osd_timer_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_TIMER], .config.minmax = { -480, 480 } },
875 { "osd_throttle_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { -480, 480 } },
876 { "osd_cpu_load_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], .config.minmax = { -480, 480 } },
877 { "osd_vtx_channel_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { -480, 480 } },
878 { "osd_voltage_warning_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING], .config.minmax = { -480, 480 } },
879 { "osd_armed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARMED], .config.minmax = { -480, 480 } },
880 { "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } },
881 { "osd_artificial_horizon", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { -1, 0 } },
882 { "osd_horizon_sidebars", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], .config.minmax = { -1, 0 } },
883 #endif
886 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
889 typedef union {
890 int32_t int_value;
891 float float_value;
892 } int_float_value_t;
894 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
895 static void cliPrintVar(const clivalue_t *var, uint32_t full);
896 static void cliPrintVarRange(const clivalue_t *var);
897 static void cliPrint(const char *str);
898 static void cliPrintf(const char *fmt, ...);
899 static void cliWrite(uint8_t ch);
901 static void cliPrompt(void)
903 cliPrint("\r\n# ");
904 bufWriterFlush(cliWriter);
907 static void cliShowParseError(void)
909 cliPrint("Parse error\r\n");
912 static void cliShowArgumentRangeError(char *name, int min, int max)
914 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
917 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
919 int val;
921 for (int argIndex = 0; argIndex < 2; argIndex++) {
922 ptr = strchr(ptr, ' ');
923 if (ptr) {
924 val = atoi(++ptr);
925 val = CHANNEL_VALUE_TO_STEP(val);
926 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
927 if (argIndex == 0) {
928 range->startStep = val;
929 } else {
930 range->endStep = val;
932 (*validArgumentCount)++;
937 return ptr;
940 // Check if a string's length is zero
941 static bool isEmpty(const char *string)
943 return *string == '\0';
946 static void cliRxFail(char *cmdline)
948 uint8_t channel;
949 char buf[3];
951 if (isEmpty(cmdline)) {
952 // print out rxConfig failsafe settings
953 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
954 cliRxFail(itoa(channel, buf, 10));
956 } else {
957 char *ptr = cmdline;
958 channel = atoi(ptr++);
959 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
961 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
963 uint16_t value;
964 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
965 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
966 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
968 ptr = strchr(ptr, ' ');
969 if (ptr) {
970 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
971 if (p) {
972 uint8_t requestedMode = p - rxFailsafeModeCharacters;
973 mode = rxFailsafeModesTable[type][requestedMode];
974 } else {
975 mode = RX_FAILSAFE_MODE_INVALID;
977 if (mode == RX_FAILSAFE_MODE_INVALID) {
978 cliShowParseError();
979 return;
982 requireValue = mode == RX_FAILSAFE_MODE_SET;
984 ptr = strchr(ptr, ' ');
985 if (ptr) {
986 if (!requireValue) {
987 cliShowParseError();
988 return;
990 value = atoi(++ptr);
991 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
992 if (value > MAX_RXFAIL_RANGE_STEP) {
993 cliPrint("Value out of range\r\n");
994 return;
997 channelFailsafeConfiguration->step = value;
998 } else if (requireValue) {
999 cliShowParseError();
1000 return;
1002 channelFailsafeConfiguration->mode = mode;
1006 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
1008 // triple use of cliPrintf below
1009 // 1. acknowledge interpretation on command,
1010 // 2. query current setting on single item,
1011 // 3. recursive use for full list.
1013 if (requireValue) {
1014 cliPrintf("rxfail %u %c %d\r\n",
1015 channel,
1016 modeCharacter,
1017 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
1019 } else {
1020 cliPrintf("rxfail %u %c\r\n",
1021 channel,
1022 modeCharacter
1025 } else {
1026 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
1031 static void cliAux(char *cmdline)
1033 int i, val = 0;
1034 char *ptr;
1036 if (isEmpty(cmdline)) {
1037 // print out aux channel settings
1038 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
1039 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1040 cliPrintf("aux %u %u %u %u %u\r\n",
1042 mac->modeId,
1043 mac->auxChannelIndex,
1044 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
1045 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
1048 } else {
1049 ptr = cmdline;
1050 i = atoi(ptr++);
1051 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
1052 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1053 uint8_t validArgumentCount = 0;
1054 ptr = strchr(ptr, ' ');
1055 if (ptr) {
1056 val = atoi(++ptr);
1057 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
1058 mac->modeId = val;
1059 validArgumentCount++;
1062 ptr = strchr(ptr, ' ');
1063 if (ptr) {
1064 val = atoi(++ptr);
1065 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1066 mac->auxChannelIndex = val;
1067 validArgumentCount++;
1070 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
1072 if (validArgumentCount != 4) {
1073 memset(mac, 0, sizeof(modeActivationCondition_t));
1075 } else {
1076 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
1081 static void cliSerial(char *cmdline)
1083 int i, val;
1084 char *ptr;
1086 if (isEmpty(cmdline)) {
1087 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
1088 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
1089 continue;
1091 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
1092 masterConfig.serialConfig.portConfigs[i].identifier,
1093 masterConfig.serialConfig.portConfigs[i].functionMask,
1094 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
1095 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
1096 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
1097 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
1100 return;
1103 serialPortConfig_t portConfig;
1104 memset(&portConfig, 0 , sizeof(portConfig));
1106 serialPortConfig_t *currentConfig;
1108 uint8_t validArgumentCount = 0;
1110 ptr = cmdline;
1112 val = atoi(ptr++);
1113 currentConfig = serialFindPortConfiguration(val);
1114 if (currentConfig) {
1115 portConfig.identifier = val;
1116 validArgumentCount++;
1119 ptr = strchr(ptr, ' ');
1120 if (ptr) {
1121 val = atoi(++ptr);
1122 portConfig.functionMask = val & 0xFFFF;
1123 validArgumentCount++;
1126 for (i = 0; i < 4; i ++) {
1127 ptr = strchr(ptr, ' ');
1128 if (!ptr) {
1129 break;
1132 val = atoi(++ptr);
1134 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1135 if (baudRates[baudRateIndex] != (uint32_t) val) {
1136 break;
1139 switch(i) {
1140 case 0:
1141 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1142 continue;
1144 portConfig.msp_baudrateIndex = baudRateIndex;
1145 break;
1146 case 1:
1147 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1148 continue;
1150 portConfig.gps_baudrateIndex = baudRateIndex;
1151 break;
1152 case 2:
1153 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1154 continue;
1156 portConfig.telemetry_baudrateIndex = baudRateIndex;
1157 break;
1158 case 3:
1159 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1160 continue;
1162 portConfig.blackbox_baudrateIndex = baudRateIndex;
1163 break;
1166 validArgumentCount++;
1169 if (validArgumentCount < 6) {
1170 cliShowParseError();
1171 return;
1174 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1178 #ifndef SKIP_SERIAL_PASSTHROUGH
1179 static void cliSerialPassthrough(char *cmdline)
1181 if (isEmpty(cmdline)) {
1182 cliShowParseError();
1183 return;
1186 int id = -1;
1187 uint32_t baud = 0;
1188 unsigned mode = 0;
1189 char* tok = strtok(cmdline, " ");
1190 int index = 0;
1192 while (tok != NULL) {
1193 switch(index) {
1194 case 0:
1195 id = atoi(tok);
1196 break;
1197 case 1:
1198 baud = atoi(tok);
1199 break;
1200 case 2:
1201 if (strstr(tok, "rx") || strstr(tok, "RX"))
1202 mode |= MODE_RX;
1203 if (strstr(tok, "tx") || strstr(tok, "TX"))
1204 mode |= MODE_TX;
1205 break;
1207 index++;
1208 tok = strtok(NULL, " ");
1211 serialPort_t *passThroughPort;
1212 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1213 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1214 if (!baud) {
1215 printf("Port %d is not open, you must specify baud\r\n", id);
1216 return;
1218 if (!mode)
1219 mode = MODE_RXTX;
1221 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1222 baud, mode,
1223 SERIAL_NOT_INVERTED);
1224 if (!passThroughPort) {
1225 printf("Port %d could not be opened\r\n", id);
1226 return;
1228 printf("Port %d opened, baud=%d\r\n", id, baud);
1229 } else {
1230 passThroughPort = passThroughPortUsage->serialPort;
1231 // If the user supplied a mode, override the port's mode, otherwise
1232 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1233 printf("Port %d already open\r\n", id);
1234 if (mode && passThroughPort->mode != mode) {
1235 printf("Adjusting mode from configured value %d to %d\r\n",
1236 passThroughPort->mode, mode);
1237 serialSetMode(passThroughPort, mode);
1241 printf("Relaying data to device on port %d, Reset your board to exit "
1242 "serial passthrough mode.\r\n");
1244 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1246 #endif
1248 static void cliAdjustmentRange(char *cmdline)
1250 int i, val = 0;
1251 char *ptr;
1253 if (isEmpty(cmdline)) {
1254 // print out adjustment ranges channel settings
1255 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1256 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1257 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1259 ar->adjustmentIndex,
1260 ar->auxChannelIndex,
1261 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1262 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1263 ar->adjustmentFunction,
1264 ar->auxSwitchChannelIndex
1267 } else {
1268 ptr = cmdline;
1269 i = atoi(ptr++);
1270 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1271 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1272 uint8_t validArgumentCount = 0;
1274 ptr = strchr(ptr, ' ');
1275 if (ptr) {
1276 val = atoi(++ptr);
1277 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1278 ar->adjustmentIndex = val;
1279 validArgumentCount++;
1282 ptr = strchr(ptr, ' ');
1283 if (ptr) {
1284 val = atoi(++ptr);
1285 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1286 ar->auxChannelIndex = val;
1287 validArgumentCount++;
1291 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1293 ptr = strchr(ptr, ' ');
1294 if (ptr) {
1295 val = atoi(++ptr);
1296 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1297 ar->adjustmentFunction = val;
1298 validArgumentCount++;
1301 ptr = strchr(ptr, ' ');
1302 if (ptr) {
1303 val = atoi(++ptr);
1304 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1305 ar->auxSwitchChannelIndex = val;
1306 validArgumentCount++;
1310 if (validArgumentCount != 6) {
1311 memset(ar, 0, sizeof(adjustmentRange_t));
1312 cliShowParseError();
1314 } else {
1315 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1320 static void cliMotorMix(char *cmdline)
1322 #ifdef USE_QUAD_MIXER_ONLY
1323 UNUSED(cmdline);
1324 #else
1325 int i, check = 0;
1326 int num_motors = 0;
1327 uint8_t len;
1328 char buf[16];
1329 char *ptr;
1331 if (isEmpty(cmdline)) {
1332 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1333 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1334 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1335 break;
1336 num_motors++;
1337 cliPrintf("#%d:\t", i);
1338 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1339 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1340 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1341 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1343 return;
1344 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1345 // erase custom mixer
1346 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1347 masterConfig.customMotorMixer[i].throttle = 0.0f;
1348 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1349 ptr = strchr(cmdline, ' ');
1350 if (ptr) {
1351 len = strlen(++ptr);
1352 for (i = 0; ; i++) {
1353 if (mixerNames[i] == NULL) {
1354 cliPrint("Invalid name\r\n");
1355 break;
1357 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1358 mixerLoadMix(i, masterConfig.customMotorMixer);
1359 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1360 cliMotorMix("");
1361 break;
1365 } else {
1366 ptr = cmdline;
1367 i = atoi(ptr); // get motor number
1368 if (i < MAX_SUPPORTED_MOTORS) {
1369 ptr = strchr(ptr, ' ');
1370 if (ptr) {
1371 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1372 check++;
1374 ptr = strchr(ptr, ' ');
1375 if (ptr) {
1376 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1377 check++;
1379 ptr = strchr(ptr, ' ');
1380 if (ptr) {
1381 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1382 check++;
1384 ptr = strchr(ptr, ' ');
1385 if (ptr) {
1386 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1387 check++;
1389 if (check != 4) {
1390 cliShowParseError();
1391 } else {
1392 cliMotorMix("");
1394 } else {
1395 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1398 #endif
1401 static void cliRxRange(char *cmdline)
1403 int i, validArgumentCount = 0;
1404 char *ptr;
1406 if (isEmpty(cmdline)) {
1407 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1408 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1409 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1411 } else if (strcasecmp(cmdline, "reset") == 0) {
1412 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1413 } else {
1414 ptr = cmdline;
1415 i = atoi(ptr);
1416 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1417 int rangeMin, rangeMax;
1419 ptr = strchr(ptr, ' ');
1420 if (ptr) {
1421 rangeMin = atoi(++ptr);
1422 validArgumentCount++;
1425 ptr = strchr(ptr, ' ');
1426 if (ptr) {
1427 rangeMax = atoi(++ptr);
1428 validArgumentCount++;
1431 if (validArgumentCount != 2) {
1432 cliShowParseError();
1433 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1434 cliShowParseError();
1435 } else {
1436 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1437 channelRangeConfiguration->min = rangeMin;
1438 channelRangeConfiguration->max = rangeMax;
1440 } else {
1441 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1446 #ifdef LED_STRIP
1447 static void cliLed(char *cmdline)
1449 int i;
1450 char *ptr;
1451 char ledConfigBuffer[20];
1453 if (isEmpty(cmdline)) {
1454 for (i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
1455 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1456 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1458 } else {
1459 ptr = cmdline;
1460 i = atoi(ptr);
1461 if (i < LED_MAX_STRIP_LENGTH) {
1462 ptr = strchr(cmdline, ' ');
1463 if (!parseLedStripConfig(i, ++ptr)) {
1464 cliShowParseError();
1466 } else {
1467 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH - 1);
1472 static void cliColor(char *cmdline)
1474 int i;
1475 char *ptr;
1477 if (isEmpty(cmdline)) {
1478 for (i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
1479 cliPrintf("color %u %d,%u,%u\r\n",
1481 masterConfig.colors[i].h,
1482 masterConfig.colors[i].s,
1483 masterConfig.colors[i].v
1486 } else {
1487 ptr = cmdline;
1488 i = atoi(ptr);
1489 if (i < LED_CONFIGURABLE_COLOR_COUNT) {
1490 ptr = strchr(cmdline, ' ');
1491 if (!parseColor(i, ++ptr)) {
1492 cliShowParseError();
1494 } else {
1495 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT - 1);
1500 static void cliModeColor(char *cmdline)
1502 if (isEmpty(cmdline)) {
1503 for (int i = 0; i < LED_MODE_COUNT; i++) {
1504 for (int j = 0; j < LED_DIRECTION_COUNT; j++) {
1505 int colorIndex = modeColors[i].color[j];
1506 cliPrintf("mode_color %u %u %u\r\n", i, j, colorIndex);
1510 for (int j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
1511 int colorIndex = specialColors.color[j];
1512 cliPrintf("mode_color %u %u %u\r\n", LED_SPECIAL, j, colorIndex);
1514 } else {
1515 enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
1516 int args[ARGS_COUNT];
1517 int argNo = 0;
1518 char* ptr = strtok(cmdline, " ");
1519 while (ptr && argNo < ARGS_COUNT) {
1520 args[argNo++] = atoi(ptr);
1521 ptr = strtok(NULL, " ");
1524 if (ptr != NULL || argNo != ARGS_COUNT) {
1525 cliShowParseError();
1526 return;
1529 int modeIdx = args[MODE];
1530 int funIdx = args[FUNCTION];
1531 int color = args[COLOR];
1532 if(!setModeColor(modeIdx, funIdx, color)) {
1533 cliShowParseError();
1534 return;
1536 // values are validated
1537 cliPrintf("mode_color %u %u %u\r\n", modeIdx, funIdx, color);
1540 #endif
1542 #ifdef USE_SERVOS
1543 static void cliServo(char *cmdline)
1545 enum { SERVO_ARGUMENT_COUNT = 8 };
1546 int16_t arguments[SERVO_ARGUMENT_COUNT];
1548 servoParam_t *servo;
1550 int i;
1551 char *ptr;
1553 if (isEmpty(cmdline)) {
1554 // print out servo settings
1555 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1556 servo = &masterConfig.servoConf[i];
1558 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1560 servo->min,
1561 servo->max,
1562 servo->middle,
1563 servo->angleAtMin,
1564 servo->angleAtMax,
1565 servo->rate,
1566 servo->forwardFromChannel
1569 } else {
1570 int validArgumentCount = 0;
1572 ptr = cmdline;
1574 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1576 // If command line doesn't fit the format, don't modify the config
1577 while (*ptr) {
1578 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1579 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1580 cliShowParseError();
1581 return;
1584 arguments[validArgumentCount++] = atoi(ptr);
1586 do {
1587 ptr++;
1588 } while (*ptr >= '0' && *ptr <= '9');
1589 } else if (*ptr == ' ') {
1590 ptr++;
1591 } else {
1592 cliShowParseError();
1593 return;
1597 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1599 i = arguments[INDEX];
1601 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1602 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1603 cliShowParseError();
1604 return;
1607 servo = &masterConfig.servoConf[i];
1609 if (
1610 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1611 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1612 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1613 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1614 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1615 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1616 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1617 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1619 cliShowParseError();
1620 return;
1623 servo->min = arguments[1];
1624 servo->max = arguments[2];
1625 servo->middle = arguments[3];
1626 servo->angleAtMin = arguments[4];
1627 servo->angleAtMax = arguments[5];
1628 servo->rate = arguments[6];
1629 servo->forwardFromChannel = arguments[7];
1632 #endif
1634 #ifdef USE_SERVOS
1635 static void cliServoMix(char *cmdline)
1637 int i;
1638 uint8_t len;
1639 char *ptr;
1640 int args[8], check = 0;
1641 len = strlen(cmdline);
1643 if (len == 0) {
1645 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1647 for (i = 0; i < MAX_SERVO_RULES; i++) {
1648 if (masterConfig.customServoMixer[i].rate == 0)
1649 break;
1651 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1653 masterConfig.customServoMixer[i].targetChannel,
1654 masterConfig.customServoMixer[i].inputSource,
1655 masterConfig.customServoMixer[i].rate,
1656 masterConfig.customServoMixer[i].speed,
1657 masterConfig.customServoMixer[i].min,
1658 masterConfig.customServoMixer[i].max,
1659 masterConfig.customServoMixer[i].box
1662 cliPrintf("\r\n");
1663 return;
1664 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1665 // erase custom mixer
1666 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1667 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1668 masterConfig.servoConf[i].reversedSources = 0;
1670 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1671 ptr = strchr(cmdline, ' ');
1672 if (ptr) {
1673 len = strlen(++ptr);
1674 for (i = 0; ; i++) {
1675 if (mixerNames[i] == NULL) {
1676 cliPrintf("Invalid name\r\n");
1677 break;
1679 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1680 servoMixerLoadMix(i, masterConfig.customServoMixer);
1681 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1682 cliServoMix("");
1683 break;
1687 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1688 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1689 int servoIndex, inputSource;
1690 ptr = strchr(cmdline, ' ');
1692 len = strlen(ptr);
1693 if (len == 0) {
1694 cliPrintf("s");
1695 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1696 cliPrintf("\ti%d", inputSource);
1697 cliPrintf("\r\n");
1699 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1700 cliPrintf("%d", servoIndex);
1701 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1702 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1703 cliPrintf("\r\n");
1705 return;
1708 ptr = strtok(ptr, " ");
1709 while (ptr != NULL && check < ARGS_COUNT - 1) {
1710 args[check++] = atoi(ptr);
1711 ptr = strtok(NULL, " ");
1714 if (ptr == NULL || check != ARGS_COUNT - 1) {
1715 cliShowParseError();
1716 return;
1719 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1720 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1721 && (*ptr == 'r' || *ptr == 'n')) {
1722 if (*ptr == 'r')
1723 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1724 else
1725 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1726 } else
1727 cliShowParseError();
1729 cliServoMix("reverse");
1730 } else {
1731 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1732 ptr = strtok(cmdline, " ");
1733 while (ptr != NULL && check < ARGS_COUNT) {
1734 args[check++] = atoi(ptr);
1735 ptr = strtok(NULL, " ");
1738 if (ptr != NULL || check != ARGS_COUNT) {
1739 cliShowParseError();
1740 return;
1743 i = args[RULE];
1744 if (i >= 0 && i < MAX_SERVO_RULES &&
1745 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1746 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1747 args[RATE] >= -100 && args[RATE] <= 100 &&
1748 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1749 args[MIN] >= 0 && args[MIN] <= 100 &&
1750 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1751 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1752 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1753 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1754 masterConfig.customServoMixer[i].rate = args[RATE];
1755 masterConfig.customServoMixer[i].speed = args[SPEED];
1756 masterConfig.customServoMixer[i].min = args[MIN];
1757 masterConfig.customServoMixer[i].max = args[MAX];
1758 masterConfig.customServoMixer[i].box = args[BOX];
1759 cliServoMix("");
1760 } else {
1761 cliShowParseError();
1765 #endif
1767 #ifdef USE_SDCARD
1769 static void cliWriteBytes(const uint8_t *buffer, int count)
1771 while (count > 0) {
1772 cliWrite(*buffer);
1773 buffer++;
1774 count--;
1778 static void cliSdInfo(char *cmdline) {
1779 UNUSED(cmdline);
1781 cliPrint("SD card: ");
1783 if (!sdcard_isInserted()) {
1784 cliPrint("None inserted\r\n");
1785 return;
1788 if (!sdcard_isInitialized()) {
1789 cliPrint("Startup failed\r\n");
1790 return;
1793 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1795 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1796 metadata->manufacturerID,
1797 metadata->numBlocks / 2, /* One block is half a kB */
1798 metadata->productionMonth,
1799 metadata->productionYear,
1800 metadata->productRevisionMajor,
1801 metadata->productRevisionMinor
1804 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1806 cliPrint("'\r\n" "Filesystem: ");
1808 switch (afatfs_getFilesystemState()) {
1809 case AFATFS_FILESYSTEM_STATE_READY:
1810 cliPrint("Ready");
1811 break;
1812 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1813 cliPrint("Initializing");
1814 break;
1815 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1816 case AFATFS_FILESYSTEM_STATE_FATAL:
1817 cliPrint("Fatal");
1819 switch (afatfs_getLastError()) {
1820 case AFATFS_ERROR_BAD_MBR:
1821 cliPrint(" - no FAT MBR partitions");
1822 break;
1823 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1824 cliPrint(" - bad FAT header");
1825 break;
1826 case AFATFS_ERROR_GENERIC:
1827 case AFATFS_ERROR_NONE:
1828 ; // Nothing more detailed to print
1829 break;
1832 cliPrint("\r\n");
1833 break;
1837 #endif
1839 #ifdef USE_FLASHFS
1841 static void cliFlashInfo(char *cmdline)
1843 const flashGeometry_t *layout = flashfsGetGeometry();
1845 UNUSED(cmdline);
1847 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1848 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1851 static void cliFlashErase(char *cmdline)
1853 UNUSED(cmdline);
1855 cliPrintf("Erasing...\r\n");
1856 flashfsEraseCompletely();
1858 while (!flashfsIsReady()) {
1859 delay(100);
1862 cliPrintf("Done.\r\n");
1865 #ifdef USE_FLASH_TOOLS
1867 static void cliFlashWrite(char *cmdline)
1869 uint32_t address = atoi(cmdline);
1870 char *text = strchr(cmdline, ' ');
1872 if (!text) {
1873 cliShowParseError();
1874 } else {
1875 flashfsSeekAbs(address);
1876 flashfsWrite((uint8_t*)text, strlen(text), true);
1877 flashfsFlushSync();
1879 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1883 static void cliFlashRead(char *cmdline)
1885 uint32_t address = atoi(cmdline);
1886 uint32_t length;
1887 int i;
1889 uint8_t buffer[32];
1891 char *nextArg = strchr(cmdline, ' ');
1893 if (!nextArg) {
1894 cliShowParseError();
1895 } else {
1896 length = atoi(nextArg);
1898 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1900 while (length > 0) {
1901 int bytesRead;
1903 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1905 for (i = 0; i < bytesRead; i++) {
1906 cliWrite(buffer[i]);
1909 length -= bytesRead;
1910 address += bytesRead;
1912 if (bytesRead == 0) {
1913 //Assume we reached the end of the volume or something fatal happened
1914 break;
1917 cliPrintf("\r\n");
1921 #endif
1922 #endif
1924 #ifdef VTX
1925 static void cliVtx(char *cmdline)
1927 int i, val = 0;
1928 char *ptr;
1930 if (isEmpty(cmdline)) {
1931 // print out vtx channel settings
1932 for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
1933 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1934 printf("vtx %u %u %u %u %u %u\r\n",
1936 cac->auxChannelIndex,
1937 cac->band,
1938 cac->channel,
1939 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
1940 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
1943 } else {
1944 ptr = cmdline;
1945 i = atoi(ptr++);
1946 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
1947 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1948 uint8_t validArgumentCount = 0;
1949 ptr = strchr(ptr, ' ');
1950 if (ptr) {
1951 val = atoi(++ptr);
1952 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1953 cac->auxChannelIndex = val;
1954 validArgumentCount++;
1957 ptr = strchr(ptr, ' ');
1958 if (ptr) {
1959 val = atoi(++ptr);
1960 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
1961 cac->band = val;
1962 validArgumentCount++;
1965 ptr = strchr(ptr, ' ');
1966 if (ptr) {
1967 val = atoi(++ptr);
1968 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
1969 cac->channel = val;
1970 validArgumentCount++;
1973 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
1975 if (validArgumentCount != 5) {
1976 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
1978 } else {
1979 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
1983 #endif
1985 static void dumpValues(uint16_t valueSection)
1987 uint32_t i;
1988 const clivalue_t *value;
1989 for (i = 0; i < VALUE_COUNT; i++) {
1990 value = &valueTable[i];
1992 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1993 continue;
1996 cliPrintf("set %s = ", valueTable[i].name);
1997 cliPrintVar(value, 0);
1998 cliPrint("\r\n");
2000 #ifdef USE_SLOW_SERIAL_CLI
2001 delay(2);
2002 #endif
2007 typedef enum {
2008 DUMP_MASTER = (1 << 0),
2009 DUMP_PROFILE = (1 << 1),
2010 DUMP_RATES = (1 << 2),
2011 DUMP_ALL = (1 << 3),
2012 } dumpFlags_e;
2014 static const char* const sectionBreak = "\r\n";
2016 #define printSectionBreak() cliPrintf((char *)sectionBreak)
2018 static void cliDump(char *cmdline)
2020 unsigned int i;
2021 char buf[16];
2022 uint32_t mask;
2024 #ifndef USE_QUAD_MIXER_ONLY
2025 float thr, roll, pitch, yaw;
2026 #endif
2028 uint8_t dumpMask = DUMP_MASTER;
2029 if (strcasecmp(cmdline, "master") == 0) {
2030 dumpMask = DUMP_MASTER; // only
2032 if (strcasecmp(cmdline, "profile") == 0) {
2033 dumpMask = DUMP_PROFILE; // only
2035 if (strcasecmp(cmdline, "rates") == 0) {
2036 dumpMask = DUMP_RATES;
2039 if (strcasecmp(cmdline, "all") == 0) {
2040 dumpMask = DUMP_ALL; // All profiles and rates
2043 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
2045 cliPrint("\r\n# version\r\n");
2046 cliVersion(NULL);
2048 printSectionBreak();
2049 cliPrint("\r\n# name\r\n");
2050 cliName(NULL);
2052 cliPrint("\r\n# mixer\r\n");
2054 #ifndef USE_QUAD_MIXER_ONLY
2055 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2057 cliPrintf("mmix reset\r\n");
2059 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2060 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
2061 break;
2062 thr = masterConfig.customMotorMixer[i].throttle;
2063 roll = masterConfig.customMotorMixer[i].roll;
2064 pitch = masterConfig.customMotorMixer[i].pitch;
2065 yaw = masterConfig.customMotorMixer[i].yaw;
2066 cliPrintf("mmix %d", i);
2067 if (thr < 0)
2068 cliWrite(' ');
2069 cliPrintf("%s", ftoa(thr, buf));
2070 if (roll < 0)
2071 cliWrite(' ');
2072 cliPrintf("%s", ftoa(roll, buf));
2073 if (pitch < 0)
2074 cliWrite(' ');
2075 cliPrintf("%s", ftoa(pitch, buf));
2076 if (yaw < 0)
2077 cliWrite(' ');
2078 cliPrintf("%s\r\n", ftoa(yaw, buf));
2079 #ifdef USE_SLOW_SERIAL_CLI
2080 delay(2);
2081 #endif
2084 #ifdef USE_SERVOS
2085 // print custom servo mixer if exists
2086 cliPrintf("smix reset\r\n");
2088 for (i = 0; i < MAX_SERVO_RULES; i++) {
2090 if (masterConfig.customServoMixer[i].rate == 0)
2091 break;
2093 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
2095 masterConfig.customServoMixer[i].targetChannel,
2096 masterConfig.customServoMixer[i].inputSource,
2097 masterConfig.customServoMixer[i].rate,
2098 masterConfig.customServoMixer[i].speed,
2099 masterConfig.customServoMixer[i].min,
2100 masterConfig.customServoMixer[i].max,
2101 masterConfig.customServoMixer[i].box
2104 #ifdef USE_SLOW_SERIAL_CLI
2105 delay(2);
2106 #endif
2109 #endif
2110 #endif
2112 cliPrint("\r\n# feature\r\n");
2113 mask = featureMask();
2114 for (i = 0; ; i++) { // disable all feature first
2115 if (featureNames[i] == NULL)
2116 break;
2117 cliPrintf("feature -%s\r\n", featureNames[i]);
2118 #ifdef USE_SLOW_SERIAL_CLI
2119 delay(2);
2120 #endif
2122 for (i = 0; ; i++) { // reenable what we want.
2123 if (featureNames[i] == NULL)
2124 break;
2125 if (mask & (1 << i))
2126 cliPrintf("feature %s\r\n", featureNames[i]);
2127 #ifdef USE_SLOW_SERIAL_CLI
2128 delay(2);
2129 #endif
2132 #ifdef BEEPER
2133 cliPrint("\r\n# beeper\r\n");
2134 uint8_t beeperCount = beeperTableEntryCount();
2135 mask = getBeeperOffMask();
2136 for (int i = 0; i < (beeperCount-2); i++) {
2137 if (mask & (1 << i))
2138 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
2139 else
2140 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
2142 #endif
2144 cliPrint("\r\n# map\r\n");
2145 for (i = 0; i < 8; i++)
2146 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2147 buf[i] = '\0';
2148 cliPrintf("map %s\r\n", buf);
2150 cliPrint("\r\n# serial\r\n");
2151 cliSerial("");
2153 #ifdef LED_STRIP
2154 cliPrint("\r\n# led\r\n");
2155 cliLed("");
2157 cliPrint("\r\n# color\r\n");
2158 cliColor("");
2160 cliPrint("\r\n# mode_color\r\n");
2161 cliModeColor("");
2162 #endif
2164 cliPrint("\r\n# aux\r\n");
2165 cliAux("");
2167 cliPrint("\r\n# adjrange\r\n");
2168 cliAdjustmentRange("");
2170 cliPrintf("\r\n# rxrange\r\n");
2171 cliRxRange("");
2173 #ifdef USE_SERVOS
2174 cliPrint("\r\n# servo\r\n");
2175 cliServo("");
2177 // print servo directions
2178 unsigned int channel;
2180 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2181 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2182 if (servoDirection(i, channel) < 0) {
2183 cliPrintf("smix reverse %d %d r\r\n", i , channel);
2184 #ifdef USE_SLOW_SERIAL_CLI
2185 delay(2);
2186 #endif
2190 #endif
2192 #ifdef VTX
2193 cliPrint("\r\n# vtx\r\n");
2194 cliVtx("");
2195 #endif
2197 cliPrint("\r\n# master\r\n");
2198 dumpValues(MASTER_VALUE);
2200 cliPrint("\r\n# rxfail\r\n");
2201 cliRxFail("");
2203 if (dumpMask & DUMP_ALL) {
2204 uint8_t activeProfile = masterConfig.current_profile_index;
2205 uint8_t profileCount;
2206 for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
2207 cliDumpProfile(profileCount);
2209 uint8_t currentRateIndex = currentProfile->activeRateProfile;
2210 uint8_t rateCount;
2211 for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
2212 cliDumpRateProfile(rateCount);
2214 cliPrint("\r\n# restore original rateprofile selection\r\n");
2215 changeControlRateProfile(currentRateIndex);
2216 cliRateProfile("");
2217 #ifdef USE_SLOW_SERIAL_CLI
2218 delay(2);
2219 #endif
2222 cliPrint("\r\n# restore original profile selection\r\n");
2223 changeProfile(activeProfile);
2224 cliProfile("");
2225 printSectionBreak();
2227 cliPrint("\r\n# save configuration\r\nsave\r\n");
2228 } else {
2229 cliDumpProfile(masterConfig.current_profile_index);
2230 cliDumpRateProfile(currentProfile->activeRateProfile);
2234 if (dumpMask & DUMP_PROFILE) {
2235 cliDumpProfile(masterConfig.current_profile_index);
2238 if (dumpMask & DUMP_RATES) {
2239 cliDumpRateProfile(currentProfile->activeRateProfile);
2243 void cliDumpProfile(uint8_t profileIndex)
2245 if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
2246 return;
2247 changeProfile(profileIndex);
2248 cliPrint("\r\n# profile\r\n");
2249 cliProfile("");
2250 printSectionBreak();
2251 dumpValues(PROFILE_VALUE);
2254 void cliDumpRateProfile(uint8_t rateProfileIndex)
2256 if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
2257 return;
2258 changeControlRateProfile(rateProfileIndex);
2259 cliPrint("\r\n# rateprofile\r\n");
2260 cliRateProfile("");
2261 printSectionBreak();
2262 dumpValues(PROFILE_RATE_VALUE);
2265 void cliEnter(serialPort_t *serialPort)
2267 cliMode = 1;
2268 cliPort = serialPort;
2269 setPrintfSerialPort(cliPort);
2270 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
2271 (bufWrite_t)serialWriteBufShim, serialPort);
2273 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2274 cliPrompt();
2275 ENABLE_ARMING_FLAG(PREVENT_ARMING);
2278 static void cliExit(char *cmdline)
2280 UNUSED(cmdline);
2282 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2283 bufWriterFlush(cliWriter);
2285 *cliBuffer = '\0';
2286 bufferIndex = 0;
2287 cliMode = 0;
2288 // incase a motor was left running during motortest, clear it here
2289 mixerResetDisarmedMotors();
2290 cliReboot();
2292 cliWriter = NULL;
2295 static void cliFeature(char *cmdline)
2297 uint32_t i;
2298 uint32_t len;
2299 uint32_t mask;
2301 len = strlen(cmdline);
2302 mask = featureMask();
2304 if (len == 0) {
2305 cliPrint("Enabled: ");
2306 for (i = 0; ; i++) {
2307 if (featureNames[i] == NULL)
2308 break;
2309 if (mask & (1 << i))
2310 cliPrintf("%s ", featureNames[i]);
2312 cliPrint("\r\n");
2313 } else if (strncasecmp(cmdline, "list", len) == 0) {
2314 cliPrint("Available: ");
2315 for (i = 0; ; i++) {
2316 if (featureNames[i] == NULL)
2317 break;
2318 cliPrintf("%s ", featureNames[i]);
2320 cliPrint("\r\n");
2321 return;
2322 } else {
2323 bool remove = false;
2324 if (cmdline[0] == '-') {
2325 // remove feature
2326 remove = true;
2327 cmdline++; // skip over -
2328 len--;
2331 for (i = 0; ; i++) {
2332 if (featureNames[i] == NULL) {
2333 cliPrint("Invalid name\r\n");
2334 break;
2337 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2339 mask = 1 << i;
2340 #ifndef GPS
2341 if (mask & FEATURE_GPS) {
2342 cliPrint("unavailable\r\n");
2343 break;
2345 #endif
2346 #ifndef SONAR
2347 if (mask & FEATURE_SONAR) {
2348 cliPrint("unavailable\r\n");
2349 break;
2351 #endif
2352 if (remove) {
2353 featureClear(mask);
2354 cliPrint("Disabled");
2355 } else {
2356 featureSet(mask);
2357 cliPrint("Enabled");
2359 cliPrintf(" %s\r\n", featureNames[i]);
2360 break;
2366 #ifdef BEEPER
2367 static void cliBeeper(char *cmdline)
2369 uint32_t i;
2370 uint32_t len = strlen(cmdline);;
2371 uint8_t beeperCount = beeperTableEntryCount();
2372 uint32_t mask = getBeeperOffMask();
2374 if (len == 0) {
2375 cliPrintf("Disabled:");
2376 for (int i = 0; ; i++) {
2377 if (i == beeperCount-2){
2378 if (mask == 0)
2379 cliPrint(" none");
2380 break;
2382 if (mask & (1 << i))
2383 cliPrintf(" %s", beeperNameForTableIndex(i));
2385 cliPrint("\r\n");
2386 } else if (strncasecmp(cmdline, "list", len) == 0) {
2387 cliPrint("Available:");
2388 for (i = 0; i < beeperCount; i++)
2389 cliPrintf(" %s", beeperNameForTableIndex(i));
2390 cliPrint("\r\n");
2391 return;
2392 } else {
2393 bool remove = false;
2394 if (cmdline[0] == '-') {
2395 remove = true; // this is for beeper OFF condition
2396 cmdline++;
2397 len--;
2400 for (i = 0; ; i++) {
2401 if (i == beeperCount) {
2402 cliPrint("Invalid name\r\n");
2403 break;
2405 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
2406 if (remove) { // beeper off
2407 if (i == BEEPER_ALL-1)
2408 beeperOffSetAll(beeperCount-2);
2409 else
2410 if (i == BEEPER_PREFERENCE-1)
2411 setBeeperOffMask(getPreferredBeeperOffMask());
2412 else {
2413 mask = 1 << i;
2414 beeperOffSet(mask);
2416 cliPrint("Disabled");
2418 else { // beeper on
2419 if (i == BEEPER_ALL-1)
2420 beeperOffClearAll();
2421 else
2422 if (i == BEEPER_PREFERENCE-1)
2423 setPreferredBeeperOffMask(getBeeperOffMask());
2424 else {
2425 mask = 1 << i;
2426 beeperOffClear(mask);
2428 cliPrint("Enabled");
2430 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
2431 break;
2436 #endif
2439 #ifdef GPS
2440 static void cliGpsPassthrough(char *cmdline)
2442 UNUSED(cmdline);
2444 gpsEnablePassthrough(cliPort);
2446 #endif
2448 static void cliHelp(char *cmdline)
2450 uint32_t i = 0;
2452 UNUSED(cmdline);
2454 for (i = 0; i < CMD_COUNT; i++) {
2455 cliPrint(cmdTable[i].name);
2456 #ifndef SKIP_CLI_COMMAND_HELP
2457 if (cmdTable[i].description) {
2458 cliPrintf(" - %s", cmdTable[i].description);
2460 if (cmdTable[i].args) {
2461 cliPrintf("\r\n\t%s", cmdTable[i].args);
2463 #endif
2464 cliPrint("\r\n");
2468 static void cliMap(char *cmdline)
2470 uint32_t len;
2471 uint32_t i;
2472 char out[9];
2474 len = strlen(cmdline);
2476 if (len == 8) {
2477 // uppercase it
2478 for (i = 0; i < 8; i++)
2479 cmdline[i] = toupper((unsigned char)cmdline[i]);
2480 for (i = 0; i < 8; i++) {
2481 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2482 continue;
2483 cliShowParseError();
2484 return;
2486 parseRcChannels(cmdline, &masterConfig.rxConfig);
2488 cliPrint("Map: ");
2489 for (i = 0; i < 8; i++)
2490 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2491 out[i] = '\0';
2492 cliPrintf("%s\r\n", out);
2495 #ifndef USE_QUAD_MIXER_ONLY
2496 static void cliMixer(char *cmdline)
2498 int i;
2499 int len;
2501 len = strlen(cmdline);
2503 if (len == 0) {
2504 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2505 return;
2506 } else if (strncasecmp(cmdline, "list", len) == 0) {
2507 cliPrint("Available mixers: ");
2508 for (i = 0; ; i++) {
2509 if (mixerNames[i] == NULL)
2510 break;
2511 cliPrintf("%s ", mixerNames[i]);
2513 cliPrint("\r\n");
2514 return;
2517 for (i = 0; ; i++) {
2518 if (mixerNames[i] == NULL) {
2519 cliPrint("Invalid name\r\n");
2520 return;
2522 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2523 masterConfig.mixerMode = i + 1;
2524 break;
2528 cliMixer("");
2530 #endif
2532 static void cliMotor(char *cmdline)
2534 int motor_index = 0;
2535 int motor_value = 0;
2536 int index = 0;
2537 char *pch = NULL;
2538 char *saveptr;
2540 if (isEmpty(cmdline)) {
2541 cliShowParseError();
2542 return;
2545 pch = strtok_r(cmdline, " ", &saveptr);
2546 while (pch != NULL) {
2547 switch (index) {
2548 case 0:
2549 motor_index = atoi(pch);
2550 break;
2551 case 1:
2552 motor_value = atoi(pch);
2553 break;
2555 index++;
2556 pch = strtok_r(NULL, " ", &saveptr);
2559 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2560 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2561 return;
2564 if (index == 2) {
2565 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2566 cliShowArgumentRangeError("value", 1000, 2000);
2567 return;
2568 } else {
2569 motor_disarmed[motor_index] = motor_value;
2573 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2576 static void cliName(char *cmdline)
2578 uint32_t len = strlen(cmdline);
2579 if (len > 0) {
2580 memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
2581 strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
2583 cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
2585 return;
2588 static void cliPlaySound(char *cmdline)
2590 #if FLASH_SIZE <= 64
2591 UNUSED(cmdline);
2592 #else
2593 int i;
2594 const char *name;
2595 static int lastSoundIdx = -1;
2597 if (isEmpty(cmdline)) {
2598 i = lastSoundIdx + 1; //next sound index
2599 if ((name=beeperNameForTableIndex(i)) == NULL) {
2600 while (true) { //no name for index; try next one
2601 if (++i >= beeperTableEntryCount())
2602 i = 0; //if end then wrap around to first entry
2603 if ((name=beeperNameForTableIndex(i)) != NULL)
2604 break; //if name OK then play sound below
2605 if (i == lastSoundIdx + 1) { //prevent infinite loop
2606 cliPrintf("Error playing sound\r\n");
2607 return;
2611 } else { //index value was given
2612 i = atoi(cmdline);
2613 if ((name=beeperNameForTableIndex(i)) == NULL) {
2614 cliPrintf("No sound for index %d\r\n", i);
2615 return;
2618 lastSoundIdx = i;
2619 beeperSilence();
2620 cliPrintf("Playing sound %d: %s\r\n", i, name);
2621 beeper(beeperModeForTableIndex(i));
2622 #endif
2625 static void cliProfile(char *cmdline)
2627 int i;
2629 if (isEmpty(cmdline)) {
2630 cliPrintf("profile %d\r\n", getCurrentProfile());
2631 return;
2632 } else {
2633 i = atoi(cmdline);
2634 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2635 masterConfig.current_profile_index = i;
2636 writeEEPROM();
2637 readEEPROM();
2638 cliProfile("");
2643 static void cliRateProfile(char *cmdline)
2645 int i;
2647 if (isEmpty(cmdline)) {
2648 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2649 return;
2650 } else {
2651 i = atoi(cmdline);
2652 if (i >= 0 && i < MAX_RATEPROFILES) {
2653 changeControlRateProfile(i);
2654 cliRateProfile("");
2659 static void cliReboot(void)
2661 cliRebootEx(false);
2664 static void cliRebootEx(bool bootLoader)
2666 cliPrint("\r\nRebooting");
2667 bufWriterFlush(cliWriter);
2668 waitForSerialPortToFinishTransmitting(cliPort);
2669 stopPwmAllMotors();
2670 if (bootLoader) {
2671 systemResetToBootloader();
2672 return;
2674 systemReset();
2677 static void cliSave(char *cmdline)
2679 UNUSED(cmdline);
2681 cliPrint("Saving");
2682 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2683 writeEEPROM();
2684 cliReboot();
2687 static void cliDefaults(char *cmdline)
2689 UNUSED(cmdline);
2691 cliPrint("Resetting to defaults");
2692 resetEEPROM();
2693 cliReboot();
2696 static void cliPrint(const char *str)
2698 while (*str)
2699 bufWriterAppend(cliWriter, *str++);
2702 static void cliPutp(void *p, char ch)
2704 bufWriterAppend(p, ch);
2707 static void cliPrintf(const char *fmt, ...)
2709 va_list va;
2710 va_start(va, fmt);
2711 tfp_format(cliWriter, cliPutp, fmt, va);
2712 va_end(va);
2715 static void cliWrite(uint8_t ch)
2717 bufWriterAppend(cliWriter, ch);
2720 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2722 int32_t value = 0;
2723 char buf[8];
2725 void *ptr = var->ptr;
2726 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2727 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2730 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2731 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2734 switch (var->type & VALUE_TYPE_MASK) {
2735 case VAR_UINT8:
2736 value = *(uint8_t *)ptr;
2737 break;
2739 case VAR_INT8:
2740 value = *(int8_t *)ptr;
2741 break;
2743 case VAR_UINT16:
2744 value = *(uint16_t *)ptr;
2745 break;
2747 case VAR_INT16:
2748 value = *(int16_t *)ptr;
2749 break;
2751 case VAR_UINT32:
2752 value = *(uint32_t *)ptr;
2753 break;
2755 case VAR_FLOAT:
2756 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2757 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2758 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2759 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2761 return; // return from case for float only
2764 switch(var->type & VALUE_MODE_MASK) {
2765 case MODE_DIRECT:
2766 cliPrintf("%d", value);
2767 if (full) {
2768 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2770 break;
2771 case MODE_LOOKUP:
2772 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2773 break;
2777 static void cliPrintVarRange(const clivalue_t *var)
2779 switch (var->type & VALUE_MODE_MASK) {
2780 case (MODE_DIRECT): {
2781 cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
2783 break;
2784 case (MODE_LOOKUP): {
2785 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
2786 cliPrint("Allowed values:");
2787 uint8_t i;
2788 for (i = 0; i < tableEntry->valueCount ; i++) {
2789 if (i > 0)
2790 cliPrint(",");
2791 cliPrintf(" %s", tableEntry->values[i]);
2793 cliPrint("\r\n");
2795 break;
2799 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2801 void *ptr = var->ptr;
2802 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2803 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2805 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2806 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2809 switch (var->type & VALUE_TYPE_MASK) {
2810 case VAR_UINT8:
2811 case VAR_INT8:
2812 *(int8_t *)ptr = value.int_value;
2813 break;
2815 case VAR_UINT16:
2816 case VAR_INT16:
2817 *(int16_t *)ptr = value.int_value;
2818 break;
2820 case VAR_UINT32:
2821 *(uint32_t *)ptr = value.int_value;
2822 break;
2824 case VAR_FLOAT:
2825 *(float *)ptr = (float)value.float_value;
2826 break;
2830 static void cliSet(char *cmdline)
2832 uint32_t i;
2833 uint32_t len;
2834 const clivalue_t *val;
2835 char *eqptr = NULL;
2837 len = strlen(cmdline);
2839 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2840 cliPrint("Current settings: \r\n");
2841 for (i = 0; i < VALUE_COUNT; i++) {
2842 val = &valueTable[i];
2843 cliPrintf("%s = ", valueTable[i].name);
2844 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2845 cliPrint("\r\n");
2847 #ifdef USE_SLOW_SERIAL_CLI
2848 delay(2);
2849 #endif
2851 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2852 // has equals
2854 char *lastNonSpaceCharacter = eqptr;
2855 while (*(lastNonSpaceCharacter - 1) == ' ') {
2856 lastNonSpaceCharacter--;
2858 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2860 // skip the '=' and any ' ' characters
2861 eqptr++;
2862 while (*(eqptr) == ' ') {
2863 eqptr++;
2866 for (i = 0; i < VALUE_COUNT; i++) {
2867 val = &valueTable[i];
2868 // ensure exact match when setting to prevent setting variables with shorter names
2869 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2871 bool changeValue = false;
2872 int_float_value_t tmp = { 0 };
2873 switch (valueTable[i].type & VALUE_MODE_MASK) {
2874 case MODE_DIRECT: {
2875 int32_t value = 0;
2876 float valuef = 0;
2878 value = atoi(eqptr);
2879 valuef = fastA2F(eqptr);
2881 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2883 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2884 tmp.float_value = valuef;
2885 else
2886 tmp.int_value = value;
2888 changeValue = true;
2891 break;
2892 case MODE_LOOKUP: {
2893 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2894 bool matched = false;
2895 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2896 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2898 if (matched) {
2899 tmp.int_value = tableValueIndex;
2900 changeValue = true;
2904 break;
2907 if (changeValue) {
2908 cliSetVar(val, tmp);
2910 cliPrintf("%s set to ", valueTable[i].name);
2911 cliPrintVar(val, 0);
2912 } else {
2913 cliPrint("Invalid value\r\n");
2914 cliPrintVarRange(val);
2917 return;
2920 cliPrint("Invalid name\r\n");
2921 } else {
2922 // no equals, check for matching variables.
2923 cliGet(cmdline);
2927 static void cliGet(char *cmdline)
2929 uint32_t i;
2930 const clivalue_t *val;
2931 int matchedCommands = 0;
2933 for (i = 0; i < VALUE_COUNT; i++) {
2934 if (strstr(valueTable[i].name, cmdline)) {
2935 val = &valueTable[i];
2936 cliPrintf("%s = ", valueTable[i].name);
2937 cliPrintVar(val, 0);
2938 cliPrint("\n");
2939 cliPrintVarRange(val);
2940 cliPrint("\r\n");
2942 matchedCommands++;
2947 if (matchedCommands) {
2948 return;
2951 cliPrint("Invalid name\r\n");
2954 static void cliStatus(char *cmdline)
2956 UNUSED(cmdline);
2958 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2959 millis() / 1000,
2960 vbat,
2961 batteryCellCount,
2962 getBatteryStateString(),
2963 constrain(averageSystemLoadPercent, 0, 100)
2966 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2968 #if (FLASH_SIZE > 64)
2969 uint8_t i;
2970 uint32_t mask;
2971 uint32_t detectedSensorsMask = sensorsMask();
2973 for (i = 0; ; i++) {
2975 if (sensorTypeNames[i] == NULL)
2976 break;
2978 mask = (1 << i);
2979 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2980 const char *sensorHardware;
2981 uint8_t sensorHardwareIndex = detectedSensors[i];
2982 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2984 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2986 if (mask == SENSOR_ACC && acc.revisionCode) {
2987 cliPrintf(".%c", acc.revisionCode);
2991 #endif
2992 cliPrint("\r\n");
2994 #ifdef USE_I2C
2995 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2996 #else
2997 uint16_t i2cErrorCounter = 0;
2998 #endif
3000 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
3002 #ifdef USE_SDCARD
3003 cliSdInfo(NULL);
3004 #endif
3007 #ifndef SKIP_TASK_STATISTICS
3008 static void cliTasks(char *cmdline)
3010 UNUSED(cmdline);
3011 int maxLoadSum = 0;
3012 int averageLoadSum = 0;
3014 cliPrintf("Task list max/us avg/us rate/hz maxload avgload total/ms\r\n");
3015 for (cfTaskId_e taskId = 0; taskId < TASK_COUNT; taskId++) {
3016 cfTaskInfo_t taskInfo;
3017 getTaskInfo(taskId, &taskInfo);
3018 if (taskInfo.isEnabled) {
3019 int taskFrequency;
3020 int subTaskFrequency;
3022 if (taskId == TASK_GYROPID) {
3023 subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
3024 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
3025 if (masterConfig.pid_process_denom > 1) {
3026 cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
3027 } else {
3028 taskFrequency = subTaskFrequency;
3029 cliPrintf("%02d - (%8s/%3s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
3031 } else {
3032 taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
3033 cliPrintf("%02d - (%12s) ", taskId, taskInfo.taskName);
3035 const int maxLoad = (taskInfo.maxExecutionTime * taskFrequency + 5000) / 1000;
3036 const int averageLoad = (taskInfo.averageExecutionTime * taskFrequency + 5000) / 1000;
3037 if (taskId != TASK_SERIAL) {
3038 maxLoadSum += maxLoad;
3039 averageLoadSum += averageLoad;
3041 cliPrintf("%6d %5d %5d %4d.%1d%% %4d.%1d%% %8d\r\n",
3042 taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency,
3043 maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000);
3044 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) {
3045 cliPrintf(" - (%12s) rate: %d\r\n", taskInfo.subTaskName, subTaskFrequency);
3049 cliPrintf("Total (excluding SERIAL) %22d.%1d%% %4d.%1d%%\r\n", maxLoadSum/10, maxLoadSum%10, averageLoadSum/10, averageLoadSum%10);
3051 #endif
3053 static void cliVersion(char *cmdline)
3055 UNUSED(cmdline);
3057 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
3058 targetName,
3059 FC_VERSION_STRING,
3060 buildDate,
3061 buildTime,
3062 shortGitRevision
3066 void cliProcess(void)
3068 if (!cliWriter) {
3069 return;
3072 // Be a little bit tricky. Flush the last inputs buffer, if any.
3073 bufWriterFlush(cliWriter);
3075 while (serialRxBytesWaiting(cliPort)) {
3076 uint8_t c = serialRead(cliPort);
3077 if (c == '\t' || c == '?') {
3078 // do tab completion
3079 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
3080 uint32_t i = bufferIndex;
3081 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3082 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
3083 continue;
3084 if (!pstart)
3085 pstart = cmd;
3086 pend = cmd;
3088 if (pstart) { /* Buffer matches one or more commands */
3089 for (; ; bufferIndex++) {
3090 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
3091 break;
3092 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
3093 /* Unambiguous -- append a space */
3094 cliBuffer[bufferIndex++] = ' ';
3095 cliBuffer[bufferIndex] = '\0';
3096 break;
3098 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
3101 if (!bufferIndex || pstart != pend) {
3102 /* Print list of ambiguous matches */
3103 cliPrint("\r\033[K");
3104 for (cmd = pstart; cmd <= pend; cmd++) {
3105 cliPrint(cmd->name);
3106 cliWrite('\t');
3108 cliPrompt();
3109 i = 0; /* Redraw prompt */
3111 for (; i < bufferIndex; i++)
3112 cliWrite(cliBuffer[i]);
3113 } else if (!bufferIndex && c == 4) { // CTRL-D
3114 cliExit(cliBuffer);
3115 return;
3116 } else if (c == 12) { // NewPage / CTRL-L
3117 // clear screen
3118 cliPrint("\033[2J\033[1;1H");
3119 cliPrompt();
3120 } else if (bufferIndex && (c == '\n' || c == '\r')) {
3121 // enter pressed
3122 cliPrint("\r\n");
3124 // Strip comment starting with # from line
3125 char *p = cliBuffer;
3126 p = strchr(p, '#');
3127 if (NULL != p) {
3128 bufferIndex = (uint32_t)(p - cliBuffer);
3131 // Strip trailing whitespace
3132 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
3133 bufferIndex--;
3136 // Process non-empty lines
3137 if (bufferIndex > 0) {
3138 cliBuffer[bufferIndex] = 0; // null terminate
3140 const clicmd_t *cmd;
3141 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3142 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
3143 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
3144 break;
3146 if(cmd < cmdTable + CMD_COUNT)
3147 cmd->func(cliBuffer + strlen(cmd->name) + 1);
3148 else
3149 cliPrint("Unknown command, try 'help'");
3150 bufferIndex = 0;
3153 memset(cliBuffer, 0, sizeof(cliBuffer));
3155 // 'exit' will reset this flag, so we don't need to print prompt again
3156 if (!cliMode)
3157 return;
3159 cliPrompt();
3160 } else if (c == 127) {
3161 // backspace
3162 if (bufferIndex) {
3163 cliBuffer[--bufferIndex] = 0;
3164 cliPrint("\010 \010");
3166 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
3167 if (!bufferIndex && c == ' ')
3168 continue; // Ignore leading spaces
3169 cliBuffer[bufferIndex++] = c;
3170 cliWrite(c);
3175 #if (FLASH_SIZE > 64)
3176 static void cliResource(char *cmdline)
3178 UNUSED(cmdline);
3179 cliPrintf("IO:\r\n----------------------\r\n");
3180 for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) {
3181 const char* owner;
3182 owner = ownerNames[ioRecs[i].owner];
3184 const char* resource;
3185 resource = resourceNames[ioRecs[i].resource];
3187 if (ioRecs[i].index > 0) {
3188 cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
3189 } else {
3190 cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
3194 #endif
3196 void cliDfu(char *cmdLine)
3198 UNUSED(cmdLine);
3199 cliPrint("\r\nRestarting in DFU mode");
3200 cliRebootEx(true);
3203 void cliInit(serialConfig_t *serialConfig)
3205 UNUSED(serialConfig);
3207 #endif