Update serial_cli.c
[betaflight.git] / src / main / io / serial_cli.c
blobfa822f8314b4f6f7ad84057a2ce5799b0a820e13
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 static void cliResource(char *cmdline);
149 #ifdef GPS
150 static void cliGpsPassthrough(char *cmdline);
151 #endif
153 static void cliHelp(char *cmdline);
154 static void cliMap(char *cmdline);
156 #ifdef LED_STRIP
157 static void cliLed(char *cmdline);
158 static void cliColor(char *cmdline);
159 static void cliModeColor(char *cmdline);
160 #endif
162 #ifndef USE_QUAD_MIXER_ONLY
163 static void cliMixer(char *cmdline);
164 #endif
166 #ifdef USE_FLASHFS
167 static void cliFlashInfo(char *cmdline);
168 static void cliFlashErase(char *cmdline);
169 #ifdef USE_FLASH_TOOLS
170 static void cliFlashWrite(char *cmdline);
171 static void cliFlashRead(char *cmdline);
172 #endif
173 #endif
175 #ifdef VTX
176 static void cliVtx(char *cmdline);
177 #endif
179 #ifdef USE_SDCARD
180 static void cliSdInfo(char *cmdline);
181 #endif
183 #ifdef BEEPER
184 static void cliBeeper(char *cmdline);
185 #endif
187 // buffer
188 static char cliBuffer[48];
189 static uint32_t bufferIndex = 0;
191 #ifndef USE_QUAD_MIXER_ONLY
192 // sync this with mixerMode_e
193 static const char * const mixerNames[] = {
194 "TRI", "QUADP", "QUADX", "BI",
195 "GIMBAL", "Y6", "HEX6",
196 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
197 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
198 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
199 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
201 #endif
203 // sync this with features_e
204 static const char * const featureNames[] = {
205 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
206 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
207 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
208 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
209 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE", "SUPEREXPO_RATES",
210 "OSD", NULL
213 // sync this with rxFailsafeChannelMode_e
214 static const char rxFailsafeModeCharacters[] = "ahs";
216 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
217 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
218 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
221 #ifndef CJMCU
222 // sync this with sensors_e
223 static const char * const sensorTypeNames[] = {
224 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
227 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
229 static const char * const sensorHardwareNames[4][11] = {
230 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE", NULL },
231 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
232 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
233 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
235 #endif
237 typedef struct {
238 const char *name;
239 #ifndef SKIP_CLI_COMMAND_HELP
240 const char *description;
241 const char *args;
242 #endif
243 void (*func)(char *cmdline);
244 } clicmd_t;
246 #ifndef SKIP_CLI_COMMAND_HELP
247 #define CLI_COMMAND_DEF(name, description, args, method) \
249 name , \
250 description , \
251 args , \
252 method \
254 #else
255 #define CLI_COMMAND_DEF(name, description, args, method) \
257 name, \
258 method \
260 #endif
262 // should be sorted a..z for bsearch()
263 const clicmd_t cmdTable[] = {
264 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
265 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
266 #ifdef LED_STRIP
267 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
268 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL, cliModeColor),
269 #endif
270 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
271 CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL, cliDfu),
272 CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump),
273 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
274 CLI_COMMAND_DEF("feature", "configure features",
275 "list\r\n"
276 "\t<+|->[name]", cliFeature),
277 #ifdef USE_FLASHFS
278 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
279 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
280 #ifdef USE_FLASH_TOOLS
281 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
282 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
283 #endif
284 #endif
285 CLI_COMMAND_DEF("get", "get variable value",
286 "[name]", cliGet),
287 #ifdef GPS
288 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
289 #endif
290 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
291 #ifdef LED_STRIP
292 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
293 #endif
294 CLI_COMMAND_DEF("map", "configure rc channel order",
295 "[<map>]", cliMap),
296 #ifndef USE_QUAD_MIXER_ONLY
297 CLI_COMMAND_DEF("mixer", "configure mixer",
298 "list\r\n"
299 "\t<name>", cliMixer),
300 #endif
301 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
302 CLI_COMMAND_DEF("motor", "get/set motor",
303 "<index> [<value>]", cliMotor),
304 CLI_COMMAND_DEF("play_sound", NULL,
305 "[<index>]\r\n", cliPlaySound),
306 CLI_COMMAND_DEF("profile", "change profile",
307 "[<index>]", cliProfile),
308 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
309 CLI_COMMAND_DEF("resource", "view currently used resources", NULL, cliResource),
310 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
311 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
312 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
313 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
314 #ifndef SKIP_SERIAL_PASSTHROUGH
315 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
316 "<id> [baud] [mode] : passthrough to serial",
317 cliSerialPassthrough),
318 #endif
319 #ifdef USE_SERVOS
320 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
321 #endif
322 CLI_COMMAND_DEF("set", "change setting",
323 "[<name>=<value>]", cliSet),
324 #ifdef USE_SERVOS
325 CLI_COMMAND_DEF("smix", "servo mixer",
326 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
327 "\treset\r\n"
328 "\tload <mixer>\r\n"
329 "\treverse <servo> <source> r|n", cliServoMix),
330 #endif
331 #ifdef USE_SDCARD
332 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
333 #endif
334 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
335 #ifndef SKIP_TASK_STATISTICS
336 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
337 #endif
338 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
339 #ifdef BEEPER
340 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
341 "\t<+|->[name]", cliBeeper),
342 #endif
343 #ifdef VTX
344 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL, cliVtx),
345 #endif
346 CLI_COMMAND_DEF("name", "Name of craft", NULL, cliName),
348 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
350 static const char * const lookupTableOffOn[] = {
351 "OFF", "ON"
354 static const char * const lookupTableUnit[] = {
355 "IMPERIAL", "METRIC"
358 static const char * const lookupTableAlignment[] = {
359 "DEFAULT",
360 "CW0",
361 "CW90",
362 "CW180",
363 "CW270",
364 "CW0FLIP",
365 "CW90FLIP",
366 "CW180FLIP",
367 "CW270FLIP"
370 #ifdef GPS
371 static const char * const lookupTableGPSProvider[] = {
372 "NMEA", "UBLOX"
375 static const char * const lookupTableGPSSBASMode[] = {
376 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
378 #endif
380 static const char * const lookupTableCurrentSensor[] = {
381 "NONE", "ADC", "VIRTUAL"
384 static const char * const lookupTableGimbalMode[] = {
385 "NORMAL", "MIXTILT"
388 static const char * const lookupTableBlackboxDevice[] = {
389 "SERIAL", "SPIFLASH", "SDCARD"
393 static const char * const lookupTablePidController[] = {
394 "LEGACY", "BETAFLIGHT"
397 static const char * const lookupTableSerialRX[] = {
398 "SPEK1024",
399 "SPEK2048",
400 "SBUS",
401 "SUMD",
402 "SUMH",
403 "XB-B",
404 "XB-B-RJ01",
405 "IBUS",
406 "JETIEXBUS"
409 static const char * const lookupTableGyroLpf[] = {
410 "OFF",
411 "188HZ",
412 "98HZ",
413 "42HZ",
414 "20HZ",
415 "10HZ",
416 "5HZ",
417 "EXPERIMENTAL"
420 static const char * const lookupTableAccHardware[] = {
421 "AUTO",
422 "NONE",
423 "ADXL345",
424 "MPU6050",
425 "MMA8452",
426 "BMA280",
427 "LSM303DLHC",
428 "MPU6000",
429 "MPU6500",
430 "FAKE"
433 static const char * const lookupTableBaroHardware[] = {
434 "AUTO",
435 "NONE",
436 "BMP085",
437 "MS5611",
438 "BMP280"
441 static const char * const lookupTableMagHardware[] = {
442 "AUTO",
443 "NONE",
444 "HMC5883",
445 "AK8975",
446 "AK8963"
449 static const char * const lookupTableDebug[DEBUG_COUNT] = {
450 "NONE",
451 "CYCLETIME",
452 "BATTERY",
453 "GYRO",
454 "ACCELEROMETER",
455 "MIXER",
456 "AIRMODE",
457 "PIDLOOP",
458 "NOTCH",
460 #ifdef OSD
461 static const char * const lookupTableOsdType[] = {
462 "AUTO",
463 "PAL",
464 "NTSC"
466 #endif
468 static const char * const lookupTableSuperExpoYaw[] = {
469 "OFF", "ON", "ALWAYS"
472 static const char * const lookupTablePwmProtocol[] = {
473 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED"
476 static const char * const lookupDeltaMethod[] = {
477 "ERROR", "MEASUREMENT"
480 typedef struct lookupTableEntry_s {
481 const char * const *values;
482 const uint8_t valueCount;
483 } lookupTableEntry_t;
485 typedef enum {
486 TABLE_OFF_ON = 0,
487 TABLE_UNIT,
488 TABLE_ALIGNMENT,
489 #ifdef GPS
490 TABLE_GPS_PROVIDER,
491 TABLE_GPS_SBAS_MODE,
492 #endif
493 #ifdef BLACKBOX
494 TABLE_BLACKBOX_DEVICE,
495 #endif
496 TABLE_CURRENT_SENSOR,
497 TABLE_GIMBAL_MODE,
498 TABLE_PID_CONTROLLER,
499 TABLE_SERIAL_RX,
500 TABLE_GYRO_LPF,
501 TABLE_ACC_HARDWARE,
502 TABLE_BARO_HARDWARE,
503 TABLE_MAG_HARDWARE,
504 TABLE_DEBUG,
505 TABLE_SUPEREXPO_YAW,
506 TABLE_MOTOR_PWM_PROTOCOL,
507 TABLE_DELTA_METHOD,
508 #ifdef OSD
509 TABLE_OSD,
510 #endif
511 } lookupTableIndex_e;
513 static const lookupTableEntry_t lookupTables[] = {
514 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
515 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
516 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
517 #ifdef GPS
518 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
519 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
520 #endif
521 #ifdef BLACKBOX
522 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
523 #endif
524 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
525 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
526 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
527 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
528 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
529 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
530 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
531 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
532 { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) },
533 { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) },
534 { lookupTablePwmProtocol, sizeof(lookupTablePwmProtocol) / sizeof(char *) },
535 { lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) },
536 #ifdef OSD
537 { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) },
538 #endif
541 #define VALUE_TYPE_OFFSET 0
542 #define VALUE_SECTION_OFFSET 4
543 #define VALUE_MODE_OFFSET 6
545 typedef enum {
546 // value type
547 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
548 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
549 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
550 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
551 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
552 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
554 // value section
555 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
556 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
557 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
558 // value mode
559 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
560 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
561 } cliValueFlag_e;
563 #define VALUE_TYPE_MASK (0x0F)
564 #define VALUE_SECTION_MASK (0x30)
565 #define VALUE_MODE_MASK (0xC0)
567 typedef struct cliMinMaxConfig_s {
568 const int32_t min;
569 const int32_t max;
570 } cliMinMaxConfig_t;
572 typedef struct cliLookupTableConfig_s {
573 const lookupTableIndex_e tableIndex;
574 } cliLookupTableConfig_t;
576 typedef union {
577 cliLookupTableConfig_t lookup;
578 cliMinMaxConfig_t minmax;
580 } cliValueConfig_t;
582 typedef struct {
583 const char *name;
584 const uint8_t type; // see cliValueFlag_e
585 void *ptr;
586 const cliValueConfig_t config;
587 } clivalue_t;
589 const clivalue_t valueTable[] = {
590 // { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
591 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
592 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
593 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
594 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
595 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
596 { "rc_smooth_interval_ms", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothInterval, .config.minmax = { 0, 255 } },
597 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
598 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
599 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
600 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
601 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } },
603 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
604 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
605 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
606 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
608 { "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
609 { "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,
610 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
611 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
613 #ifdef CC3D
614 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
615 #endif
616 { "use_unsynced_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_unsyncedPwm, .config.lookup = { TABLE_OFF_ON } },
617 { "motor_pwm_protocol", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.motor_pwm_protocol, .config.lookup = { TABLE_MOTOR_PWM_PROTOCOL } },
618 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 200, 32000 } },
619 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
621 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
622 { "gyro_cal_on_first_arm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_cal_on_first_arm, .config.lookup = { TABLE_OFF_ON } },
623 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
624 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
626 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
628 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
630 #ifdef GPS
631 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
632 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
633 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
634 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
636 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
637 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
638 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
639 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
640 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
641 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
642 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
643 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
644 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
645 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
646 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
647 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
648 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
649 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
650 #endif
651 #ifdef GTUNE
652 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
653 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
654 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
655 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
656 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
657 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
658 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
659 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
660 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
661 #endif
663 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
664 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
665 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
666 { "spektrum_sat_bind_autoreset",VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind_autoreset, .config.minmax = { 0, 1} },
668 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
669 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
670 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
671 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
672 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
673 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
674 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
675 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
676 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
678 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
679 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
680 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
681 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
682 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
683 { "vbat_hysteresis", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbathysteresis, .config.minmax = { 0, 250 } },
684 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
685 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
686 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
687 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
689 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
690 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
691 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
693 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
694 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
695 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
697 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
698 { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
699 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
700 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
701 { "gyro_lowpass", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 255 } },
702 { "gyro_notch_hz", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_soft_notch_hz, .config.minmax = { 0, 500 } },
703 { "gyro_notch_q", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_soft_notch_q, .config.minmax = { 1, 100 } },
704 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
705 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
706 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
708 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
709 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
710 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
711 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
713 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
714 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
716 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
718 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
719 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
720 #ifdef USE_SERVOS
721 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
722 { "servo_lowpass_freq", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
723 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
724 #endif
726 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
727 { "rc_rate_yaw", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawRate8, .config.minmax = { 0, 250 } },
728 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
729 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
730 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
731 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
732 { "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 } },
733 { "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 } },
734 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
735 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
736 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
737 { "airmode_activate_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.airModeActivateThreshold, .config.minmax = {1000, 2000 } },
739 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
740 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
741 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
742 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
743 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
744 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
746 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
747 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
749 #ifdef USE_SERVOS
750 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
751 #endif
753 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
754 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
755 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
756 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
757 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
758 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
759 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
761 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
762 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
763 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
764 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
765 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
767 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
768 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
769 { "dterm_lowpass", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
770 { "vbat_pid_compensation", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
771 { "zero_throttle_stabilisation",VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.zeroThrottleStabilisation, .config.lookup = { TABLE_OFF_ON } },
772 { "motor_accel_limit_percent", VAR_UINT16 | MASTER_VALUE, &masterConfig.profile[0].pidProfile.accelerationLimitPercent, .config.minmax = { 0, 10000 } },
773 { "pid_tolerance_band", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBand, .config.minmax = {0, 200 } },
774 { "tolerance_band_reduction", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.toleranceBandReduction, .config.minmax = {0, 100 } },
775 { "zero_cross_allowance", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.zeroCrossAllowanceCount, .config.minmax = {0, 50 } },
776 { "iterm_throttle_gain", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.itermThrottleGain, .config.minmax = {0, 200 } },
778 { "iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } },
779 { "yaw_iterm_ignore_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } },
780 { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } },
781 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
783 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
785 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
786 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
787 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
788 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
789 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
790 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
791 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
792 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
793 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
795 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
796 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
797 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
799 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
800 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
801 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
803 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
804 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
805 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
807 #ifdef BLACKBOX
808 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
809 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
810 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
811 #endif
813 #ifdef VTX
814 { "vtx_band", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_band, .config.minmax = { 1, 5 } },
815 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 1, 8 } },
816 { "vtx_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_mode, .config.minmax = { 0, 2 } },
817 { "vtx_mhz", VAR_UINT16 | MASTER_VALUE, &masterConfig.vtx_mhz, .config.minmax = { 5600, 5950 } },
818 #endif
820 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
821 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
822 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
823 #ifdef LED_STRIP
824 { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } },
825 #endif
826 #ifdef USE_RTC6705
827 { "vtx_channel", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } },
828 { "vtx_power", VAR_UINT8 | MASTER_VALUE, &masterConfig.vtx_power, .config.minmax = { 0, 1 } },
829 #endif
830 #ifdef OSD
831 { "osd_video_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.video_system, .config.minmax = { 0, 2 } },
832 { "osd_main_voltage_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { -480, 480 } },
833 { "osd_rssi_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { -480, 480 } },
834 { "osd_timer_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_TIMER], .config.minmax = { -480, 480 } },
835 { "osd_throttle_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { -480, 480 } },
836 { "osd_cpu_load_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], .config.minmax = { -480, 480 } },
837 { "osd_vtx_channel_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { -480, 480 } },
838 { "osd_voltage_warning_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING], .config.minmax = { -480, 480 } },
839 { "osd_armed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARMED], .config.minmax = { -480, 480 } },
840 { "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } },
841 { "osd_artificial_horizon", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], .config.minmax = { -1, 0 } },
842 { "osd_horizon_sidebars", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], .config.minmax = { -1, 0 } },
843 #endif
846 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
849 typedef union {
850 int32_t int_value;
851 float float_value;
852 } int_float_value_t;
854 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
855 static void cliPrintVar(const clivalue_t *var, uint32_t full);
856 static void cliPrintVarRange(const clivalue_t *var);
857 static void cliPrint(const char *str);
858 static void cliPrintf(const char *fmt, ...);
859 static void cliWrite(uint8_t ch);
861 static void cliPrompt(void)
863 cliPrint("\r\n# ");
864 bufWriterFlush(cliWriter);
867 static void cliShowParseError(void)
869 cliPrint("Parse error\r\n");
872 static void cliShowArgumentRangeError(char *name, int min, int max)
874 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
877 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
879 int val;
881 for (int argIndex = 0; argIndex < 2; argIndex++) {
882 ptr = strchr(ptr, ' ');
883 if (ptr) {
884 val = atoi(++ptr);
885 val = CHANNEL_VALUE_TO_STEP(val);
886 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
887 if (argIndex == 0) {
888 range->startStep = val;
889 } else {
890 range->endStep = val;
892 (*validArgumentCount)++;
897 return ptr;
900 // Check if a string's length is zero
901 static bool isEmpty(const char *string)
903 return *string == '\0';
906 static void cliRxFail(char *cmdline)
908 uint8_t channel;
909 char buf[3];
911 if (isEmpty(cmdline)) {
912 // print out rxConfig failsafe settings
913 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
914 cliRxFail(itoa(channel, buf, 10));
916 } else {
917 char *ptr = cmdline;
918 channel = atoi(ptr++);
919 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
921 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
923 uint16_t value;
924 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
925 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
926 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
928 ptr = strchr(ptr, ' ');
929 if (ptr) {
930 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
931 if (p) {
932 uint8_t requestedMode = p - rxFailsafeModeCharacters;
933 mode = rxFailsafeModesTable[type][requestedMode];
934 } else {
935 mode = RX_FAILSAFE_MODE_INVALID;
937 if (mode == RX_FAILSAFE_MODE_INVALID) {
938 cliShowParseError();
939 return;
942 requireValue = mode == RX_FAILSAFE_MODE_SET;
944 ptr = strchr(ptr, ' ');
945 if (ptr) {
946 if (!requireValue) {
947 cliShowParseError();
948 return;
950 value = atoi(++ptr);
951 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
952 if (value > MAX_RXFAIL_RANGE_STEP) {
953 cliPrint("Value out of range\r\n");
954 return;
957 channelFailsafeConfiguration->step = value;
958 } else if (requireValue) {
959 cliShowParseError();
960 return;
962 channelFailsafeConfiguration->mode = mode;
966 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
968 // triple use of cliPrintf below
969 // 1. acknowledge interpretation on command,
970 // 2. query current setting on single item,
971 // 3. recursive use for full list.
973 if (requireValue) {
974 cliPrintf("rxfail %u %c %d\r\n",
975 channel,
976 modeCharacter,
977 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
979 } else {
980 cliPrintf("rxfail %u %c\r\n",
981 channel,
982 modeCharacter
985 } else {
986 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
991 static void cliAux(char *cmdline)
993 int i, val = 0;
994 char *ptr;
996 if (isEmpty(cmdline)) {
997 // print out aux channel settings
998 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
999 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1000 cliPrintf("aux %u %u %u %u %u\r\n",
1002 mac->modeId,
1003 mac->auxChannelIndex,
1004 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
1005 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
1008 } else {
1009 ptr = cmdline;
1010 i = atoi(ptr++);
1011 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
1012 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
1013 uint8_t validArgumentCount = 0;
1014 ptr = strchr(ptr, ' ');
1015 if (ptr) {
1016 val = atoi(++ptr);
1017 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
1018 mac->modeId = val;
1019 validArgumentCount++;
1022 ptr = strchr(ptr, ' ');
1023 if (ptr) {
1024 val = atoi(++ptr);
1025 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1026 mac->auxChannelIndex = val;
1027 validArgumentCount++;
1030 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
1032 if (validArgumentCount != 4) {
1033 memset(mac, 0, sizeof(modeActivationCondition_t));
1035 } else {
1036 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
1041 static void cliSerial(char *cmdline)
1043 int i, val;
1044 char *ptr;
1046 if (isEmpty(cmdline)) {
1047 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
1048 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
1049 continue;
1051 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
1052 masterConfig.serialConfig.portConfigs[i].identifier,
1053 masterConfig.serialConfig.portConfigs[i].functionMask,
1054 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
1055 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
1056 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
1057 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
1060 return;
1063 serialPortConfig_t portConfig;
1064 memset(&portConfig, 0 , sizeof(portConfig));
1066 serialPortConfig_t *currentConfig;
1068 uint8_t validArgumentCount = 0;
1070 ptr = cmdline;
1072 val = atoi(ptr++);
1073 currentConfig = serialFindPortConfiguration(val);
1074 if (currentConfig) {
1075 portConfig.identifier = val;
1076 validArgumentCount++;
1079 ptr = strchr(ptr, ' ');
1080 if (ptr) {
1081 val = atoi(++ptr);
1082 portConfig.functionMask = val & 0xFFFF;
1083 validArgumentCount++;
1086 for (i = 0; i < 4; i ++) {
1087 ptr = strchr(ptr, ' ');
1088 if (!ptr) {
1089 break;
1092 val = atoi(++ptr);
1094 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1095 if (baudRates[baudRateIndex] != (uint32_t) val) {
1096 break;
1099 switch(i) {
1100 case 0:
1101 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1102 continue;
1104 portConfig.msp_baudrateIndex = baudRateIndex;
1105 break;
1106 case 1:
1107 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1108 continue;
1110 portConfig.gps_baudrateIndex = baudRateIndex;
1111 break;
1112 case 2:
1113 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1114 continue;
1116 portConfig.telemetry_baudrateIndex = baudRateIndex;
1117 break;
1118 case 3:
1119 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1120 continue;
1122 portConfig.blackbox_baudrateIndex = baudRateIndex;
1123 break;
1126 validArgumentCount++;
1129 if (validArgumentCount < 6) {
1130 cliShowParseError();
1131 return;
1134 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1138 #ifndef SKIP_SERIAL_PASSTHROUGH
1139 static void cliSerialPassthrough(char *cmdline)
1141 if (isEmpty(cmdline)) {
1142 cliShowParseError();
1143 return;
1146 int id = -1;
1147 uint32_t baud = 0;
1148 unsigned mode = 0;
1149 char* tok = strtok(cmdline, " ");
1150 int index = 0;
1152 while (tok != NULL) {
1153 switch(index) {
1154 case 0:
1155 id = atoi(tok);
1156 break;
1157 case 1:
1158 baud = atoi(tok);
1159 break;
1160 case 2:
1161 if (strstr(tok, "rx") || strstr(tok, "RX"))
1162 mode |= MODE_RX;
1163 if (strstr(tok, "tx") || strstr(tok, "TX"))
1164 mode |= MODE_TX;
1165 break;
1167 index++;
1168 tok = strtok(NULL, " ");
1171 serialPort_t *passThroughPort;
1172 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1173 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1174 if (!baud) {
1175 printf("Port %d is not open, you must specify baud\r\n", id);
1176 return;
1178 if (!mode)
1179 mode = MODE_RXTX;
1181 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1182 baud, mode,
1183 SERIAL_NOT_INVERTED);
1184 if (!passThroughPort) {
1185 printf("Port %d could not be opened\r\n", id);
1186 return;
1188 printf("Port %d opened, baud=%d\r\n", id, baud);
1189 } else {
1190 passThroughPort = passThroughPortUsage->serialPort;
1191 // If the user supplied a mode, override the port's mode, otherwise
1192 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1193 printf("Port %d already open\r\n", id);
1194 if (mode && passThroughPort->mode != mode) {
1195 printf("Adjusting mode from configured value %d to %d\r\n",
1196 passThroughPort->mode, mode);
1197 serialSetMode(passThroughPort, mode);
1201 printf("Relaying data to device on port %d, Reset your board to exit "
1202 "serial passthrough mode.\r\n");
1204 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1206 #endif
1208 static void cliAdjustmentRange(char *cmdline)
1210 int i, val = 0;
1211 char *ptr;
1213 if (isEmpty(cmdline)) {
1214 // print out adjustment ranges channel settings
1215 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1216 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1217 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1219 ar->adjustmentIndex,
1220 ar->auxChannelIndex,
1221 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1222 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1223 ar->adjustmentFunction,
1224 ar->auxSwitchChannelIndex
1227 } else {
1228 ptr = cmdline;
1229 i = atoi(ptr++);
1230 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1231 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1232 uint8_t validArgumentCount = 0;
1234 ptr = strchr(ptr, ' ');
1235 if (ptr) {
1236 val = atoi(++ptr);
1237 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1238 ar->adjustmentIndex = val;
1239 validArgumentCount++;
1242 ptr = strchr(ptr, ' ');
1243 if (ptr) {
1244 val = atoi(++ptr);
1245 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1246 ar->auxChannelIndex = val;
1247 validArgumentCount++;
1251 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1253 ptr = strchr(ptr, ' ');
1254 if (ptr) {
1255 val = atoi(++ptr);
1256 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1257 ar->adjustmentFunction = val;
1258 validArgumentCount++;
1261 ptr = strchr(ptr, ' ');
1262 if (ptr) {
1263 val = atoi(++ptr);
1264 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1265 ar->auxSwitchChannelIndex = val;
1266 validArgumentCount++;
1270 if (validArgumentCount != 6) {
1271 memset(ar, 0, sizeof(adjustmentRange_t));
1272 cliShowParseError();
1274 } else {
1275 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1280 static void cliMotorMix(char *cmdline)
1282 #ifdef USE_QUAD_MIXER_ONLY
1283 UNUSED(cmdline);
1284 #else
1285 int i, check = 0;
1286 int num_motors = 0;
1287 uint8_t len;
1288 char buf[16];
1289 char *ptr;
1291 if (isEmpty(cmdline)) {
1292 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1293 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1294 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1295 break;
1296 num_motors++;
1297 cliPrintf("#%d:\t", i);
1298 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1299 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1300 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1301 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1303 return;
1304 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1305 // erase custom mixer
1306 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1307 masterConfig.customMotorMixer[i].throttle = 0.0f;
1308 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1309 ptr = strchr(cmdline, ' ');
1310 if (ptr) {
1311 len = strlen(++ptr);
1312 for (i = 0; ; i++) {
1313 if (mixerNames[i] == NULL) {
1314 cliPrint("Invalid name\r\n");
1315 break;
1317 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1318 mixerLoadMix(i, masterConfig.customMotorMixer);
1319 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1320 cliMotorMix("");
1321 break;
1325 } else {
1326 ptr = cmdline;
1327 i = atoi(ptr); // get motor number
1328 if (i < MAX_SUPPORTED_MOTORS) {
1329 ptr = strchr(ptr, ' ');
1330 if (ptr) {
1331 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1332 check++;
1334 ptr = strchr(ptr, ' ');
1335 if (ptr) {
1336 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1337 check++;
1339 ptr = strchr(ptr, ' ');
1340 if (ptr) {
1341 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1342 check++;
1344 ptr = strchr(ptr, ' ');
1345 if (ptr) {
1346 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1347 check++;
1349 if (check != 4) {
1350 cliShowParseError();
1351 } else {
1352 cliMotorMix("");
1354 } else {
1355 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1358 #endif
1361 static void cliRxRange(char *cmdline)
1363 int i, validArgumentCount = 0;
1364 char *ptr;
1366 if (isEmpty(cmdline)) {
1367 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1368 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1369 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1371 } else if (strcasecmp(cmdline, "reset") == 0) {
1372 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1373 } else {
1374 ptr = cmdline;
1375 i = atoi(ptr);
1376 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1377 int rangeMin, rangeMax;
1379 ptr = strchr(ptr, ' ');
1380 if (ptr) {
1381 rangeMin = atoi(++ptr);
1382 validArgumentCount++;
1385 ptr = strchr(ptr, ' ');
1386 if (ptr) {
1387 rangeMax = atoi(++ptr);
1388 validArgumentCount++;
1391 if (validArgumentCount != 2) {
1392 cliShowParseError();
1393 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1394 cliShowParseError();
1395 } else {
1396 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1397 channelRangeConfiguration->min = rangeMin;
1398 channelRangeConfiguration->max = rangeMax;
1400 } else {
1401 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1406 #ifdef LED_STRIP
1407 static void cliLed(char *cmdline)
1409 int i;
1410 char *ptr;
1411 char ledConfigBuffer[20];
1413 if (isEmpty(cmdline)) {
1414 for (i = 0; i < LED_MAX_STRIP_LENGTH; i++) {
1415 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1416 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1418 } else {
1419 ptr = cmdline;
1420 i = atoi(ptr);
1421 if (i < LED_MAX_STRIP_LENGTH) {
1422 ptr = strchr(cmdline, ' ');
1423 if (!parseLedStripConfig(i, ++ptr)) {
1424 cliShowParseError();
1426 } else {
1427 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH - 1);
1432 static void cliColor(char *cmdline)
1434 int i;
1435 char *ptr;
1437 if (isEmpty(cmdline)) {
1438 for (i = 0; i < LED_CONFIGURABLE_COLOR_COUNT; i++) {
1439 cliPrintf("color %u %d,%u,%u\r\n",
1441 masterConfig.colors[i].h,
1442 masterConfig.colors[i].s,
1443 masterConfig.colors[i].v
1446 } else {
1447 ptr = cmdline;
1448 i = atoi(ptr);
1449 if (i < LED_CONFIGURABLE_COLOR_COUNT) {
1450 ptr = strchr(cmdline, ' ');
1451 if (!parseColor(i, ++ptr)) {
1452 cliShowParseError();
1454 } else {
1455 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT - 1);
1460 static void cliModeColor(char *cmdline)
1462 if (isEmpty(cmdline)) {
1463 for (int i = 0; i < LED_MODE_COUNT; i++) {
1464 for (int j = 0; j < LED_DIRECTION_COUNT; j++) {
1465 int colorIndex = modeColors[i].color[j];
1466 cliPrintf("mode_color %u %u %u\r\n", i, j, colorIndex);
1470 for (int j = 0; j < LED_SPECIAL_COLOR_COUNT; j++) {
1471 int colorIndex = specialColors.color[j];
1472 cliPrintf("mode_color %u %u %u\r\n", LED_SPECIAL, j, colorIndex);
1474 } else {
1475 enum {MODE = 0, FUNCTION, COLOR, ARGS_COUNT};
1476 int args[ARGS_COUNT];
1477 int argNo = 0;
1478 char* ptr = strtok(cmdline, " ");
1479 while (ptr && argNo < ARGS_COUNT) {
1480 args[argNo++] = atoi(ptr);
1481 ptr = strtok(NULL, " ");
1484 if (ptr != NULL || argNo != ARGS_COUNT) {
1485 cliShowParseError();
1486 return;
1489 int modeIdx = args[MODE];
1490 int funIdx = args[FUNCTION];
1491 int color = args[COLOR];
1492 if(!setModeColor(modeIdx, funIdx, color)) {
1493 cliShowParseError();
1494 return;
1496 // values are validated
1497 cliPrintf("mode_color %u %u %u\r\n", modeIdx, funIdx, color);
1500 #endif
1502 #ifdef USE_SERVOS
1503 static void cliServo(char *cmdline)
1505 enum { SERVO_ARGUMENT_COUNT = 8 };
1506 int16_t arguments[SERVO_ARGUMENT_COUNT];
1508 servoParam_t *servo;
1510 int i;
1511 char *ptr;
1513 if (isEmpty(cmdline)) {
1514 // print out servo settings
1515 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1516 servo = &masterConfig.servoConf[i];
1518 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1520 servo->min,
1521 servo->max,
1522 servo->middle,
1523 servo->angleAtMin,
1524 servo->angleAtMax,
1525 servo->rate,
1526 servo->forwardFromChannel
1529 } else {
1530 int validArgumentCount = 0;
1532 ptr = cmdline;
1534 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1536 // If command line doesn't fit the format, don't modify the config
1537 while (*ptr) {
1538 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1539 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1540 cliShowParseError();
1541 return;
1544 arguments[validArgumentCount++] = atoi(ptr);
1546 do {
1547 ptr++;
1548 } while (*ptr >= '0' && *ptr <= '9');
1549 } else if (*ptr == ' ') {
1550 ptr++;
1551 } else {
1552 cliShowParseError();
1553 return;
1557 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1559 i = arguments[INDEX];
1561 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1562 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1563 cliShowParseError();
1564 return;
1567 servo = &masterConfig.servoConf[i];
1569 if (
1570 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1571 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1572 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1573 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1574 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1575 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1576 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1577 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1579 cliShowParseError();
1580 return;
1583 servo->min = arguments[1];
1584 servo->max = arguments[2];
1585 servo->middle = arguments[3];
1586 servo->angleAtMin = arguments[4];
1587 servo->angleAtMax = arguments[5];
1588 servo->rate = arguments[6];
1589 servo->forwardFromChannel = arguments[7];
1592 #endif
1594 #ifdef USE_SERVOS
1595 static void cliServoMix(char *cmdline)
1597 int i;
1598 uint8_t len;
1599 char *ptr;
1600 int args[8], check = 0;
1601 len = strlen(cmdline);
1603 if (len == 0) {
1605 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1607 for (i = 0; i < MAX_SERVO_RULES; i++) {
1608 if (masterConfig.customServoMixer[i].rate == 0)
1609 break;
1611 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1613 masterConfig.customServoMixer[i].targetChannel,
1614 masterConfig.customServoMixer[i].inputSource,
1615 masterConfig.customServoMixer[i].rate,
1616 masterConfig.customServoMixer[i].speed,
1617 masterConfig.customServoMixer[i].min,
1618 masterConfig.customServoMixer[i].max,
1619 masterConfig.customServoMixer[i].box
1622 cliPrintf("\r\n");
1623 return;
1624 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1625 // erase custom mixer
1626 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1627 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1628 masterConfig.servoConf[i].reversedSources = 0;
1630 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1631 ptr = strchr(cmdline, ' ');
1632 if (ptr) {
1633 len = strlen(++ptr);
1634 for (i = 0; ; i++) {
1635 if (mixerNames[i] == NULL) {
1636 cliPrintf("Invalid name\r\n");
1637 break;
1639 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1640 servoMixerLoadMix(i, masterConfig.customServoMixer);
1641 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1642 cliServoMix("");
1643 break;
1647 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1648 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1649 int servoIndex, inputSource;
1650 ptr = strchr(cmdline, ' ');
1652 len = strlen(ptr);
1653 if (len == 0) {
1654 cliPrintf("s");
1655 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1656 cliPrintf("\ti%d", inputSource);
1657 cliPrintf("\r\n");
1659 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1660 cliPrintf("%d", servoIndex);
1661 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1662 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1663 cliPrintf("\r\n");
1665 return;
1668 ptr = strtok(ptr, " ");
1669 while (ptr != NULL && check < ARGS_COUNT - 1) {
1670 args[check++] = atoi(ptr);
1671 ptr = strtok(NULL, " ");
1674 if (ptr == NULL || check != ARGS_COUNT - 1) {
1675 cliShowParseError();
1676 return;
1679 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1680 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1681 && (*ptr == 'r' || *ptr == 'n')) {
1682 if (*ptr == 'r')
1683 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1684 else
1685 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1686 } else
1687 cliShowParseError();
1689 cliServoMix("reverse");
1690 } else {
1691 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1692 ptr = strtok(cmdline, " ");
1693 while (ptr != NULL && check < ARGS_COUNT) {
1694 args[check++] = atoi(ptr);
1695 ptr = strtok(NULL, " ");
1698 if (ptr != NULL || check != ARGS_COUNT) {
1699 cliShowParseError();
1700 return;
1703 i = args[RULE];
1704 if (i >= 0 && i < MAX_SERVO_RULES &&
1705 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1706 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1707 args[RATE] >= -100 && args[RATE] <= 100 &&
1708 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1709 args[MIN] >= 0 && args[MIN] <= 100 &&
1710 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1711 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1712 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1713 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1714 masterConfig.customServoMixer[i].rate = args[RATE];
1715 masterConfig.customServoMixer[i].speed = args[SPEED];
1716 masterConfig.customServoMixer[i].min = args[MIN];
1717 masterConfig.customServoMixer[i].max = args[MAX];
1718 masterConfig.customServoMixer[i].box = args[BOX];
1719 cliServoMix("");
1720 } else {
1721 cliShowParseError();
1725 #endif
1727 #ifdef USE_SDCARD
1729 static void cliWriteBytes(const uint8_t *buffer, int count)
1731 while (count > 0) {
1732 cliWrite(*buffer);
1733 buffer++;
1734 count--;
1738 static void cliSdInfo(char *cmdline) {
1739 UNUSED(cmdline);
1741 cliPrint("SD card: ");
1743 if (!sdcard_isInserted()) {
1744 cliPrint("None inserted\r\n");
1745 return;
1748 if (!sdcard_isInitialized()) {
1749 cliPrint("Startup failed\r\n");
1750 return;
1753 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1755 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1756 metadata->manufacturerID,
1757 metadata->numBlocks / 2, /* One block is half a kB */
1758 metadata->productionMonth,
1759 metadata->productionYear,
1760 metadata->productRevisionMajor,
1761 metadata->productRevisionMinor
1764 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1766 cliPrint("'\r\n" "Filesystem: ");
1768 switch (afatfs_getFilesystemState()) {
1769 case AFATFS_FILESYSTEM_STATE_READY:
1770 cliPrint("Ready");
1771 break;
1772 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1773 cliPrint("Initializing");
1774 break;
1775 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1776 case AFATFS_FILESYSTEM_STATE_FATAL:
1777 cliPrint("Fatal");
1779 switch (afatfs_getLastError()) {
1780 case AFATFS_ERROR_BAD_MBR:
1781 cliPrint(" - no FAT MBR partitions");
1782 break;
1783 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1784 cliPrint(" - bad FAT header");
1785 break;
1786 case AFATFS_ERROR_GENERIC:
1787 case AFATFS_ERROR_NONE:
1788 ; // Nothing more detailed to print
1789 break;
1792 cliPrint("\r\n");
1793 break;
1797 #endif
1799 #ifdef USE_FLASHFS
1801 static void cliFlashInfo(char *cmdline)
1803 const flashGeometry_t *layout = flashfsGetGeometry();
1805 UNUSED(cmdline);
1807 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1808 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1811 static void cliFlashErase(char *cmdline)
1813 UNUSED(cmdline);
1815 cliPrintf("Erasing...\r\n");
1816 flashfsEraseCompletely();
1818 while (!flashfsIsReady()) {
1819 delay(100);
1822 cliPrintf("Done.\r\n");
1825 #ifdef USE_FLASH_TOOLS
1827 static void cliFlashWrite(char *cmdline)
1829 uint32_t address = atoi(cmdline);
1830 char *text = strchr(cmdline, ' ');
1832 if (!text) {
1833 cliShowParseError();
1834 } else {
1835 flashfsSeekAbs(address);
1836 flashfsWrite((uint8_t*)text, strlen(text), true);
1837 flashfsFlushSync();
1839 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1843 static void cliFlashRead(char *cmdline)
1845 uint32_t address = atoi(cmdline);
1846 uint32_t length;
1847 int i;
1849 uint8_t buffer[32];
1851 char *nextArg = strchr(cmdline, ' ');
1853 if (!nextArg) {
1854 cliShowParseError();
1855 } else {
1856 length = atoi(nextArg);
1858 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1860 while (length > 0) {
1861 int bytesRead;
1863 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1865 for (i = 0; i < bytesRead; i++) {
1866 cliWrite(buffer[i]);
1869 length -= bytesRead;
1870 address += bytesRead;
1872 if (bytesRead == 0) {
1873 //Assume we reached the end of the volume or something fatal happened
1874 break;
1877 cliPrintf("\r\n");
1881 #endif
1882 #endif
1884 #ifdef VTX
1885 static void cliVtx(char *cmdline)
1887 int i, val = 0;
1888 char *ptr;
1890 if (isEmpty(cmdline)) {
1891 // print out vtx channel settings
1892 for (i = 0; i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT; i++) {
1893 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1894 printf("vtx %u %u %u %u %u %u\r\n",
1896 cac->auxChannelIndex,
1897 cac->band,
1898 cac->channel,
1899 MODE_STEP_TO_CHANNEL_VALUE(cac->range.startStep),
1900 MODE_STEP_TO_CHANNEL_VALUE(cac->range.endStep)
1903 } else {
1904 ptr = cmdline;
1905 i = atoi(ptr++);
1906 if (i < MAX_CHANNEL_ACTIVATION_CONDITION_COUNT) {
1907 vtxChannelActivationCondition_t *cac = &masterConfig.vtxChannelActivationConditions[i];
1908 uint8_t validArgumentCount = 0;
1909 ptr = strchr(ptr, ' ');
1910 if (ptr) {
1911 val = atoi(++ptr);
1912 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1913 cac->auxChannelIndex = val;
1914 validArgumentCount++;
1917 ptr = strchr(ptr, ' ');
1918 if (ptr) {
1919 val = atoi(++ptr);
1920 if (val >= VTX_BAND_MIN && val <= VTX_BAND_MAX) {
1921 cac->band = val;
1922 validArgumentCount++;
1925 ptr = strchr(ptr, ' ');
1926 if (ptr) {
1927 val = atoi(++ptr);
1928 if (val >= VTX_CHANNEL_MIN && val <= VTX_CHANNEL_MAX) {
1929 cac->channel = val;
1930 validArgumentCount++;
1933 ptr = processChannelRangeArgs(ptr, &cac->range, &validArgumentCount);
1935 if (validArgumentCount != 5) {
1936 memset(cac, 0, sizeof(vtxChannelActivationCondition_t));
1938 } else {
1939 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT - 1);
1943 #endif
1945 static void dumpValues(uint16_t valueSection)
1947 uint32_t i;
1948 const clivalue_t *value;
1949 for (i = 0; i < VALUE_COUNT; i++) {
1950 value = &valueTable[i];
1952 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1953 continue;
1956 cliPrintf("set %s = ", valueTable[i].name);
1957 cliPrintVar(value, 0);
1958 cliPrint("\r\n");
1960 #ifdef USE_SLOW_SERIAL_CLI
1961 delay(2);
1962 #endif
1967 typedef enum {
1968 DUMP_MASTER = (1 << 0),
1969 DUMP_PROFILE = (1 << 1),
1970 DUMP_RATES = (1 << 2),
1971 DUMP_ALL = (1 << 3),
1972 } dumpFlags_e;
1974 static const char* const sectionBreak = "\r\n";
1976 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1978 static void cliDump(char *cmdline)
1980 unsigned int i;
1981 char buf[16];
1982 uint32_t mask;
1984 #ifndef USE_QUAD_MIXER_ONLY
1985 float thr, roll, pitch, yaw;
1986 #endif
1988 uint8_t dumpMask = DUMP_MASTER;
1989 if (strcasecmp(cmdline, "master") == 0) {
1990 dumpMask = DUMP_MASTER; // only
1992 if (strcasecmp(cmdline, "profile") == 0) {
1993 dumpMask = DUMP_PROFILE; // only
1995 if (strcasecmp(cmdline, "rates") == 0) {
1996 dumpMask = DUMP_RATES;
1999 if (strcasecmp(cmdline, "all") == 0) {
2000 dumpMask = DUMP_ALL; // All profiles and rates
2003 if ((dumpMask & DUMP_MASTER) || (dumpMask & DUMP_ALL)) {
2005 cliPrint("\r\n# version\r\n");
2006 cliVersion(NULL);
2008 printSectionBreak();
2009 cliPrint("\r\n# name\r\n");
2010 cliName(NULL);
2012 cliPrint("\r\n# mixer\r\n");
2014 #ifndef USE_QUAD_MIXER_ONLY
2015 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2017 cliPrintf("mmix reset\r\n");
2019 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
2020 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
2021 break;
2022 thr = masterConfig.customMotorMixer[i].throttle;
2023 roll = masterConfig.customMotorMixer[i].roll;
2024 pitch = masterConfig.customMotorMixer[i].pitch;
2025 yaw = masterConfig.customMotorMixer[i].yaw;
2026 cliPrintf("mmix %d", i);
2027 if (thr < 0)
2028 cliWrite(' ');
2029 cliPrintf("%s", ftoa(thr, buf));
2030 if (roll < 0)
2031 cliWrite(' ');
2032 cliPrintf("%s", ftoa(roll, buf));
2033 if (pitch < 0)
2034 cliWrite(' ');
2035 cliPrintf("%s", ftoa(pitch, buf));
2036 if (yaw < 0)
2037 cliWrite(' ');
2038 cliPrintf("%s\r\n", ftoa(yaw, buf));
2039 #ifdef USE_SLOW_SERIAL_CLI
2040 delay(2);
2041 #endif
2044 #ifdef USE_SERVOS
2045 // print custom servo mixer if exists
2046 cliPrintf("smix reset\r\n");
2048 for (i = 0; i < MAX_SERVO_RULES; i++) {
2050 if (masterConfig.customServoMixer[i].rate == 0)
2051 break;
2053 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
2055 masterConfig.customServoMixer[i].targetChannel,
2056 masterConfig.customServoMixer[i].inputSource,
2057 masterConfig.customServoMixer[i].rate,
2058 masterConfig.customServoMixer[i].speed,
2059 masterConfig.customServoMixer[i].min,
2060 masterConfig.customServoMixer[i].max,
2061 masterConfig.customServoMixer[i].box
2064 #ifdef USE_SLOW_SERIAL_CLI
2065 delay(2);
2066 #endif
2069 #endif
2070 #endif
2072 cliPrint("\r\n# feature\r\n");
2073 mask = featureMask();
2074 for (i = 0; ; i++) { // disable all feature first
2075 if (featureNames[i] == NULL)
2076 break;
2077 cliPrintf("feature -%s\r\n", featureNames[i]);
2078 #ifdef USE_SLOW_SERIAL_CLI
2079 delay(2);
2080 #endif
2082 for (i = 0; ; i++) { // reenable what we want.
2083 if (featureNames[i] == NULL)
2084 break;
2085 if (mask & (1 << i))
2086 cliPrintf("feature %s\r\n", featureNames[i]);
2087 #ifdef USE_SLOW_SERIAL_CLI
2088 delay(2);
2089 #endif
2092 #ifdef BEEPER
2093 cliPrint("\r\n# beeper\r\n");
2094 uint8_t beeperCount = beeperTableEntryCount();
2095 mask = getBeeperOffMask();
2096 for (int i = 0; i < (beeperCount-2); i++) {
2097 if (mask & (1 << i))
2098 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
2099 else
2100 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
2102 #endif
2104 cliPrint("\r\n# map\r\n");
2105 for (i = 0; i < 8; i++)
2106 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2107 buf[i] = '\0';
2108 cliPrintf("map %s\r\n", buf);
2110 cliPrint("\r\n# serial\r\n");
2111 cliSerial("");
2113 #ifdef LED_STRIP
2114 cliPrint("\r\n# led\r\n");
2115 cliLed("");
2117 cliPrint("\r\n# color\r\n");
2118 cliColor("");
2120 cliPrint("\r\n# mode_color\r\n");
2121 cliModeColor("");
2122 #endif
2124 cliPrint("\r\n# aux\r\n");
2125 cliAux("");
2127 cliPrint("\r\n# adjrange\r\n");
2128 cliAdjustmentRange("");
2130 cliPrintf("\r\n# rxrange\r\n");
2131 cliRxRange("");
2133 #ifdef USE_SERVOS
2134 cliPrint("\r\n# servo\r\n");
2135 cliServo("");
2137 // print servo directions
2138 unsigned int channel;
2140 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
2141 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
2142 if (servoDirection(i, channel) < 0) {
2143 cliPrintf("smix reverse %d %d r\r\n", i , channel);
2144 #ifdef USE_SLOW_SERIAL_CLI
2145 delay(2);
2146 #endif
2150 #endif
2152 #ifdef VTX
2153 cliPrint("\r\n# vtx\r\n");
2154 cliVtx("");
2155 #endif
2157 cliPrint("\r\n# master\r\n");
2158 dumpValues(MASTER_VALUE);
2160 cliPrint("\r\n# rxfail\r\n");
2161 cliRxFail("");
2163 if (dumpMask & DUMP_ALL) {
2164 uint8_t activeProfile = masterConfig.current_profile_index;
2165 uint8_t profileCount;
2166 for (profileCount=0; profileCount<MAX_PROFILE_COUNT;profileCount++) {
2167 cliDumpProfile(profileCount);
2169 uint8_t currentRateIndex = currentProfile->activeRateProfile;
2170 uint8_t rateCount;
2171 for (rateCount=0; rateCount<MAX_RATEPROFILES; rateCount++)
2172 cliDumpRateProfile(rateCount);
2174 cliPrint("\r\n# restore original rateprofile selection\r\n");
2175 changeControlRateProfile(currentRateIndex);
2176 cliRateProfile("");
2177 #ifdef USE_SLOW_SERIAL_CLI
2178 delay(2);
2179 #endif
2182 cliPrint("\r\n# restore original profile selection\r\n");
2183 changeProfile(activeProfile);
2184 cliProfile("");
2185 printSectionBreak();
2187 cliPrint("\r\n# save configuration\r\nsave\r\n");
2188 } else {
2189 cliDumpProfile(masterConfig.current_profile_index);
2190 cliDumpRateProfile(currentProfile->activeRateProfile);
2194 if (dumpMask & DUMP_PROFILE) {
2195 cliDumpProfile(masterConfig.current_profile_index);
2198 if (dumpMask & DUMP_RATES) {
2199 cliDumpRateProfile(currentProfile->activeRateProfile);
2203 void cliDumpProfile(uint8_t profileIndex)
2205 if (profileIndex >= MAX_PROFILE_COUNT) // Faulty values
2206 return;
2207 changeProfile(profileIndex);
2208 cliPrint("\r\n# profile\r\n");
2209 cliProfile("");
2210 printSectionBreak();
2211 dumpValues(PROFILE_VALUE);
2214 void cliDumpRateProfile(uint8_t rateProfileIndex)
2216 if (rateProfileIndex >= MAX_RATEPROFILES) // Faulty values
2217 return;
2218 changeControlRateProfile(rateProfileIndex);
2219 cliPrint("\r\n# rateprofile\r\n");
2220 cliRateProfile("");
2221 printSectionBreak();
2222 dumpValues(PROFILE_RATE_VALUE);
2225 void cliEnter(serialPort_t *serialPort)
2227 cliMode = 1;
2228 cliPort = serialPort;
2229 setPrintfSerialPort(cliPort);
2230 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
2231 (bufWrite_t)serialWriteBufShim, serialPort);
2233 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2234 cliPrompt();
2235 ENABLE_ARMING_FLAG(PREVENT_ARMING);
2238 static void cliExit(char *cmdline)
2240 UNUSED(cmdline);
2242 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2243 bufWriterFlush(cliWriter);
2245 *cliBuffer = '\0';
2246 bufferIndex = 0;
2247 cliMode = 0;
2248 // incase a motor was left running during motortest, clear it here
2249 mixerResetDisarmedMotors();
2250 cliReboot();
2252 cliWriter = NULL;
2255 static void cliFeature(char *cmdline)
2257 uint32_t i;
2258 uint32_t len;
2259 uint32_t mask;
2261 len = strlen(cmdline);
2262 mask = featureMask();
2264 if (len == 0) {
2265 cliPrint("Enabled: ");
2266 for (i = 0; ; i++) {
2267 if (featureNames[i] == NULL)
2268 break;
2269 if (mask & (1 << i))
2270 cliPrintf("%s ", featureNames[i]);
2272 cliPrint("\r\n");
2273 } else if (strncasecmp(cmdline, "list", len) == 0) {
2274 cliPrint("Available: ");
2275 for (i = 0; ; i++) {
2276 if (featureNames[i] == NULL)
2277 break;
2278 cliPrintf("%s ", featureNames[i]);
2280 cliPrint("\r\n");
2281 return;
2282 } else {
2283 bool remove = false;
2284 if (cmdline[0] == '-') {
2285 // remove feature
2286 remove = true;
2287 cmdline++; // skip over -
2288 len--;
2291 for (i = 0; ; i++) {
2292 if (featureNames[i] == NULL) {
2293 cliPrint("Invalid name\r\n");
2294 break;
2297 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2299 mask = 1 << i;
2300 #ifndef GPS
2301 if (mask & FEATURE_GPS) {
2302 cliPrint("unavailable\r\n");
2303 break;
2305 #endif
2306 #ifndef SONAR
2307 if (mask & FEATURE_SONAR) {
2308 cliPrint("unavailable\r\n");
2309 break;
2311 #endif
2312 if (remove) {
2313 featureClear(mask);
2314 cliPrint("Disabled");
2315 } else {
2316 featureSet(mask);
2317 cliPrint("Enabled");
2319 cliPrintf(" %s\r\n", featureNames[i]);
2320 break;
2326 #ifdef BEEPER
2327 static void cliBeeper(char *cmdline)
2329 uint32_t i;
2330 uint32_t len = strlen(cmdline);;
2331 uint8_t beeperCount = beeperTableEntryCount();
2332 uint32_t mask = getBeeperOffMask();
2334 if (len == 0) {
2335 cliPrintf("Disabled:");
2336 for (int i = 0; ; i++) {
2337 if (i == beeperCount-2){
2338 if (mask == 0)
2339 cliPrint(" none");
2340 break;
2342 if (mask & (1 << i))
2343 cliPrintf(" %s", beeperNameForTableIndex(i));
2345 cliPrint("\r\n");
2346 } else if (strncasecmp(cmdline, "list", len) == 0) {
2347 cliPrint("Available:");
2348 for (i = 0; i < beeperCount; i++)
2349 cliPrintf(" %s", beeperNameForTableIndex(i));
2350 cliPrint("\r\n");
2351 return;
2352 } else {
2353 bool remove = false;
2354 if (cmdline[0] == '-') {
2355 remove = true; // this is for beeper OFF condition
2356 cmdline++;
2357 len--;
2360 for (i = 0; ; i++) {
2361 if (i == beeperCount) {
2362 cliPrint("Invalid name\r\n");
2363 break;
2365 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
2366 if (remove) { // beeper off
2367 if (i == BEEPER_ALL-1)
2368 beeperOffSetAll(beeperCount-2);
2369 else
2370 if (i == BEEPER_PREFERENCE-1)
2371 setBeeperOffMask(getPreferredBeeperOffMask());
2372 else {
2373 mask = 1 << i;
2374 beeperOffSet(mask);
2376 cliPrint("Disabled");
2378 else { // beeper on
2379 if (i == BEEPER_ALL-1)
2380 beeperOffClearAll();
2381 else
2382 if (i == BEEPER_PREFERENCE-1)
2383 setPreferredBeeperOffMask(getBeeperOffMask());
2384 else {
2385 mask = 1 << i;
2386 beeperOffClear(mask);
2388 cliPrint("Enabled");
2390 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
2391 break;
2396 #endif
2399 #ifdef GPS
2400 static void cliGpsPassthrough(char *cmdline)
2402 UNUSED(cmdline);
2404 gpsEnablePassthrough(cliPort);
2406 #endif
2408 static void cliHelp(char *cmdline)
2410 uint32_t i = 0;
2412 UNUSED(cmdline);
2414 for (i = 0; i < CMD_COUNT; i++) {
2415 cliPrint(cmdTable[i].name);
2416 #ifndef SKIP_CLI_COMMAND_HELP
2417 if (cmdTable[i].description) {
2418 cliPrintf(" - %s", cmdTable[i].description);
2420 if (cmdTable[i].args) {
2421 cliPrintf("\r\n\t%s", cmdTable[i].args);
2423 #endif
2424 cliPrint("\r\n");
2428 static void cliMap(char *cmdline)
2430 uint32_t len;
2431 uint32_t i;
2432 char out[9];
2434 len = strlen(cmdline);
2436 if (len == 8) {
2437 // uppercase it
2438 for (i = 0; i < 8; i++)
2439 cmdline[i] = toupper((unsigned char)cmdline[i]);
2440 for (i = 0; i < 8; i++) {
2441 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2442 continue;
2443 cliShowParseError();
2444 return;
2446 parseRcChannels(cmdline, &masterConfig.rxConfig);
2448 cliPrint("Map: ");
2449 for (i = 0; i < 8; i++)
2450 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2451 out[i] = '\0';
2452 cliPrintf("%s\r\n", out);
2455 #ifndef USE_QUAD_MIXER_ONLY
2456 static void cliMixer(char *cmdline)
2458 int i;
2459 int len;
2461 len = strlen(cmdline);
2463 if (len == 0) {
2464 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2465 return;
2466 } else if (strncasecmp(cmdline, "list", len) == 0) {
2467 cliPrint("Available mixers: ");
2468 for (i = 0; ; i++) {
2469 if (mixerNames[i] == NULL)
2470 break;
2471 cliPrintf("%s ", mixerNames[i]);
2473 cliPrint("\r\n");
2474 return;
2477 for (i = 0; ; i++) {
2478 if (mixerNames[i] == NULL) {
2479 cliPrint("Invalid name\r\n");
2480 return;
2482 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2483 masterConfig.mixerMode = i + 1;
2484 break;
2488 cliMixer("");
2490 #endif
2492 static void cliMotor(char *cmdline)
2494 int motor_index = 0;
2495 int motor_value = 0;
2496 int index = 0;
2497 char *pch = NULL;
2498 char *saveptr;
2500 if (isEmpty(cmdline)) {
2501 cliShowParseError();
2502 return;
2505 pch = strtok_r(cmdline, " ", &saveptr);
2506 while (pch != NULL) {
2507 switch (index) {
2508 case 0:
2509 motor_index = atoi(pch);
2510 break;
2511 case 1:
2512 motor_value = atoi(pch);
2513 break;
2515 index++;
2516 pch = strtok_r(NULL, " ", &saveptr);
2519 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2520 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2521 return;
2524 if (index == 2) {
2525 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2526 cliShowArgumentRangeError("value", 1000, 2000);
2527 return;
2528 } else {
2529 motor_disarmed[motor_index] = motor_value;
2533 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2536 static void cliName(char *cmdline)
2538 uint32_t len = strlen(cmdline);
2539 if (len > 0) {
2540 memset(masterConfig.name, 0, ARRAYLEN(masterConfig.name));
2541 strncpy(masterConfig.name, cmdline, MIN(len, MAX_NAME_LENGTH));
2543 cliPrintf("name %s\r\n", strlen(masterConfig.name) > 0 ? masterConfig.name : "-");
2545 return;
2548 static void cliPlaySound(char *cmdline)
2550 #if FLASH_SIZE <= 64
2551 UNUSED(cmdline);
2552 #else
2553 int i;
2554 const char *name;
2555 static int lastSoundIdx = -1;
2557 if (isEmpty(cmdline)) {
2558 i = lastSoundIdx + 1; //next sound index
2559 if ((name=beeperNameForTableIndex(i)) == NULL) {
2560 while (true) { //no name for index; try next one
2561 if (++i >= beeperTableEntryCount())
2562 i = 0; //if end then wrap around to first entry
2563 if ((name=beeperNameForTableIndex(i)) != NULL)
2564 break; //if name OK then play sound below
2565 if (i == lastSoundIdx + 1) { //prevent infinite loop
2566 cliPrintf("Error playing sound\r\n");
2567 return;
2571 } else { //index value was given
2572 i = atoi(cmdline);
2573 if ((name=beeperNameForTableIndex(i)) == NULL) {
2574 cliPrintf("No sound for index %d\r\n", i);
2575 return;
2578 lastSoundIdx = i;
2579 beeperSilence();
2580 cliPrintf("Playing sound %d: %s\r\n", i, name);
2581 beeper(beeperModeForTableIndex(i));
2582 #endif
2585 static void cliProfile(char *cmdline)
2587 int i;
2589 if (isEmpty(cmdline)) {
2590 cliPrintf("profile %d\r\n", getCurrentProfile());
2591 return;
2592 } else {
2593 i = atoi(cmdline);
2594 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2595 masterConfig.current_profile_index = i;
2596 writeEEPROM();
2597 readEEPROM();
2598 cliProfile("");
2603 static void cliRateProfile(char *cmdline) {
2604 int i;
2606 if (isEmpty(cmdline)) {
2607 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2608 return;
2609 } else {
2610 i = atoi(cmdline);
2611 if (i >= 0 && i < MAX_RATEPROFILES) {
2612 changeControlRateProfile(i);
2613 cliRateProfile("");
2618 static void cliReboot(void)
2620 cliRebootEx(false);
2623 static void cliRebootEx(bool bootLoader)
2625 cliPrint("\r\nRebooting");
2626 bufWriterFlush(cliWriter);
2627 waitForSerialPortToFinishTransmitting(cliPort);
2628 stopPwmAllMotors();
2629 if (bootLoader) {
2630 systemResetToBootloader();
2631 return;
2633 systemReset();
2636 static void cliSave(char *cmdline)
2638 UNUSED(cmdline);
2640 cliPrint("Saving");
2641 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2642 writeEEPROM();
2643 cliReboot();
2646 static void cliDefaults(char *cmdline)
2648 UNUSED(cmdline);
2650 cliPrint("Resetting to defaults");
2651 resetEEPROM();
2652 cliReboot();
2655 static void cliPrint(const char *str)
2657 while (*str)
2658 bufWriterAppend(cliWriter, *str++);
2661 static void cliPutp(void *p, char ch)
2663 bufWriterAppend(p, ch);
2666 static void cliPrintf(const char *fmt, ...)
2668 va_list va;
2669 va_start(va, fmt);
2670 tfp_format(cliWriter, cliPutp, fmt, va);
2671 va_end(va);
2674 static void cliWrite(uint8_t ch)
2676 bufWriterAppend(cliWriter, ch);
2679 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2681 int32_t value = 0;
2682 char buf[8];
2684 void *ptr = var->ptr;
2685 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2686 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2689 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2690 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2693 switch (var->type & VALUE_TYPE_MASK) {
2694 case VAR_UINT8:
2695 value = *(uint8_t *)ptr;
2696 break;
2698 case VAR_INT8:
2699 value = *(int8_t *)ptr;
2700 break;
2702 case VAR_UINT16:
2703 value = *(uint16_t *)ptr;
2704 break;
2706 case VAR_INT16:
2707 value = *(int16_t *)ptr;
2708 break;
2710 case VAR_UINT32:
2711 value = *(uint32_t *)ptr;
2712 break;
2714 case VAR_FLOAT:
2715 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2716 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2717 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2718 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2720 return; // return from case for float only
2723 switch(var->type & VALUE_MODE_MASK) {
2724 case MODE_DIRECT:
2725 cliPrintf("%d", value);
2726 if (full) {
2727 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2729 break;
2730 case MODE_LOOKUP:
2731 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2732 break;
2735 static void cliPrintVarRange(const clivalue_t *var)
2737 switch (var->type & VALUE_MODE_MASK) {
2738 case (MODE_DIRECT): {
2739 cliPrintf("Allowed range: %d - %d\r\n", var->config.minmax.min, var->config.minmax.max);
2741 break;
2742 case (MODE_LOOKUP): {
2743 const lookupTableEntry_t *tableEntry = &lookupTables[var->config.lookup.tableIndex];
2744 cliPrint("Allowed values:");
2745 uint8_t i;
2746 for (i = 0; i < tableEntry->valueCount ; i++) {
2747 if (i > 0)
2748 cliPrint(",");
2749 cliPrintf(" %s", tableEntry->values[i]);
2751 cliPrint("\r\n");
2753 break;
2756 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2758 void *ptr = var->ptr;
2759 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2760 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2762 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2763 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2766 switch (var->type & VALUE_TYPE_MASK) {
2767 case VAR_UINT8:
2768 case VAR_INT8:
2769 *(int8_t *)ptr = value.int_value;
2770 break;
2772 case VAR_UINT16:
2773 case VAR_INT16:
2774 *(int16_t *)ptr = value.int_value;
2775 break;
2777 case VAR_UINT32:
2778 *(uint32_t *)ptr = value.int_value;
2779 break;
2781 case VAR_FLOAT:
2782 *(float *)ptr = (float)value.float_value;
2783 break;
2787 static void cliSet(char *cmdline)
2789 uint32_t i;
2790 uint32_t len;
2791 const clivalue_t *val;
2792 char *eqptr = NULL;
2794 len = strlen(cmdline);
2796 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2797 cliPrint("Current settings: \r\n");
2798 for (i = 0; i < VALUE_COUNT; i++) {
2799 val = &valueTable[i];
2800 cliPrintf("%s = ", valueTable[i].name);
2801 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2802 cliPrint("\r\n");
2804 #ifdef USE_SLOW_SERIAL_CLI
2805 delay(2);
2806 #endif
2808 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2809 // has equals
2811 char *lastNonSpaceCharacter = eqptr;
2812 while (*(lastNonSpaceCharacter - 1) == ' ') {
2813 lastNonSpaceCharacter--;
2815 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2817 // skip the '=' and any ' ' characters
2818 eqptr++;
2819 while (*(eqptr) == ' ') {
2820 eqptr++;
2823 for (i = 0; i < VALUE_COUNT; i++) {
2824 val = &valueTable[i];
2825 // ensure exact match when setting to prevent setting variables with shorter names
2826 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2828 bool changeValue = false;
2829 int_float_value_t tmp = { 0 };
2830 switch (valueTable[i].type & VALUE_MODE_MASK) {
2831 case MODE_DIRECT: {
2832 int32_t value = 0;
2833 float valuef = 0;
2835 value = atoi(eqptr);
2836 valuef = fastA2F(eqptr);
2838 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2840 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2841 tmp.float_value = valuef;
2842 else
2843 tmp.int_value = value;
2845 changeValue = true;
2848 break;
2849 case MODE_LOOKUP: {
2850 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2851 bool matched = false;
2852 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2853 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2855 if (matched) {
2856 tmp.int_value = tableValueIndex;
2857 changeValue = true;
2861 break;
2864 if (changeValue) {
2865 cliSetVar(val, tmp);
2867 cliPrintf("%s set to ", valueTable[i].name);
2868 cliPrintVar(val, 0);
2869 } else {
2870 cliPrint("Invalid value\r\n");
2871 cliPrintVarRange(val);
2874 return;
2877 cliPrint("Invalid name\r\n");
2878 } else {
2879 // no equals, check for matching variables.
2880 cliGet(cmdline);
2884 static void cliGet(char *cmdline)
2886 uint32_t i;
2887 const clivalue_t *val;
2888 int matchedCommands = 0;
2890 for (i = 0; i < VALUE_COUNT; i++) {
2891 if (strstr(valueTable[i].name, cmdline)) {
2892 val = &valueTable[i];
2893 cliPrintf("%s = ", valueTable[i].name);
2894 cliPrintVar(val, 0);
2895 cliPrint("\n");
2896 cliPrintVarRange(val);
2897 cliPrint("\r\n");
2899 matchedCommands++;
2904 if (matchedCommands) {
2905 return;
2908 cliPrint("Invalid name\r\n");
2911 static void cliStatus(char *cmdline)
2913 UNUSED(cmdline);
2915 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2916 millis() / 1000,
2917 vbat,
2918 batteryCellCount,
2919 getBatteryStateString(),
2920 constrain(averageSystemLoadPercent, 0, 100)
2923 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2925 #ifndef CJMCU
2926 uint8_t i;
2927 uint32_t mask;
2928 uint32_t detectedSensorsMask = sensorsMask();
2930 for (i = 0; ; i++) {
2932 if (sensorTypeNames[i] == NULL)
2933 break;
2935 mask = (1 << i);
2936 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2937 const char *sensorHardware;
2938 uint8_t sensorHardwareIndex = detectedSensors[i];
2939 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2941 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2943 if (mask == SENSOR_ACC && acc.revisionCode) {
2944 cliPrintf(".%c", acc.revisionCode);
2948 #endif
2949 cliPrint("\r\n");
2951 #ifdef USE_I2C
2952 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2953 #else
2954 uint16_t i2cErrorCounter = 0;
2955 #endif
2957 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2959 #ifdef USE_SDCARD
2960 cliSdInfo(NULL);
2961 #endif
2964 #ifndef SKIP_TASK_STATISTICS
2965 static void cliTasks(char *cmdline)
2967 UNUSED(cmdline);
2969 cfTaskId_e taskId;
2970 cfTaskInfo_t taskInfo;
2972 cliPrintf("Task list:\r\n");
2973 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2974 getTaskInfo(taskId, &taskInfo);
2975 if (taskInfo.isEnabled) {
2976 uint16_t taskFrequency;
2977 uint16_t subTaskFrequency;
2979 uint32_t taskTotalTime = taskInfo.totalExecutionTime / 1000;
2981 if (taskId == TASK_GYROPID) {
2982 subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
2983 if (masterConfig.pid_process_denom > 1) {
2984 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
2985 cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
2986 } else {
2987 taskFrequency = subTaskFrequency;
2988 cliPrintf("%02d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
2990 } else {
2991 taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
2992 cliPrintf("%02d - (%s) ", taskId, taskInfo.taskName);
2995 cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
2997 if (taskTotalTime >= 1000) {
2998 cliPrintf("%dsec", taskTotalTime / 1000);
2999 } else {
3000 cliPrintf("%dms", taskTotalTime);
3003 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n - - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
3004 cliPrintf("\r\n", taskTotalTime);
3008 #endif
3010 static void cliVersion(char *cmdline)
3012 UNUSED(cmdline);
3014 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
3015 targetName,
3016 FC_VERSION_STRING,
3017 buildDate,
3018 buildTime,
3019 shortGitRevision
3023 void cliProcess(void)
3025 if (!cliWriter) {
3026 return;
3029 // Be a little bit tricky. Flush the last inputs buffer, if any.
3030 bufWriterFlush(cliWriter);
3032 while (serialRxBytesWaiting(cliPort)) {
3033 uint8_t c = serialRead(cliPort);
3034 if (c == '\t' || c == '?') {
3035 // do tab completion
3036 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
3037 uint32_t i = bufferIndex;
3038 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3039 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
3040 continue;
3041 if (!pstart)
3042 pstart = cmd;
3043 pend = cmd;
3045 if (pstart) { /* Buffer matches one or more commands */
3046 for (; ; bufferIndex++) {
3047 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
3048 break;
3049 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
3050 /* Unambiguous -- append a space */
3051 cliBuffer[bufferIndex++] = ' ';
3052 cliBuffer[bufferIndex] = '\0';
3053 break;
3055 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
3058 if (!bufferIndex || pstart != pend) {
3059 /* Print list of ambiguous matches */
3060 cliPrint("\r\033[K");
3061 for (cmd = pstart; cmd <= pend; cmd++) {
3062 cliPrint(cmd->name);
3063 cliWrite('\t');
3065 cliPrompt();
3066 i = 0; /* Redraw prompt */
3068 for (; i < bufferIndex; i++)
3069 cliWrite(cliBuffer[i]);
3070 } else if (!bufferIndex && c == 4) { // CTRL-D
3071 cliExit(cliBuffer);
3072 return;
3073 } else if (c == 12) { // NewPage / CTRL-L
3074 // clear screen
3075 cliPrint("\033[2J\033[1;1H");
3076 cliPrompt();
3077 } else if (bufferIndex && (c == '\n' || c == '\r')) {
3078 // enter pressed
3079 cliPrint("\r\n");
3081 // Strip comment starting with # from line
3082 char *p = cliBuffer;
3083 p = strchr(p, '#');
3084 if (NULL != p) {
3085 bufferIndex = (uint32_t)(p - cliBuffer);
3088 // Strip trailing whitespace
3089 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
3090 bufferIndex--;
3093 // Process non-empty lines
3094 if (bufferIndex > 0) {
3095 cliBuffer[bufferIndex] = 0; // null terminate
3097 const clicmd_t *cmd;
3098 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
3099 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
3100 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
3101 break;
3103 if(cmd < cmdTable + CMD_COUNT)
3104 cmd->func(cliBuffer + strlen(cmd->name) + 1);
3105 else
3106 cliPrint("Unknown command, try 'help'");
3107 bufferIndex = 0;
3110 memset(cliBuffer, 0, sizeof(cliBuffer));
3112 // 'exit' will reset this flag, so we don't need to print prompt again
3113 if (!cliMode)
3114 return;
3116 cliPrompt();
3117 } else if (c == 127) {
3118 // backspace
3119 if (bufferIndex) {
3120 cliBuffer[--bufferIndex] = 0;
3121 cliPrint("\010 \010");
3123 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
3124 if (!bufferIndex && c == ' ')
3125 continue; // Ignore leading spaces
3126 cliBuffer[bufferIndex++] = c;
3127 cliWrite(c);
3132 static void cliResource(char *cmdline)
3134 UNUSED(cmdline);
3135 cliPrintf("IO:\r\n----------------------\r\n");
3136 for (unsigned i = 0; i < DEFIO_IO_USED_COUNT; i++) {
3137 const char* owner;
3138 owner = ownerNames[ioRecs[i].owner];
3140 const char* resource;
3141 resource = resourceNames[ioRecs[i].resource];
3143 if (ioRecs[i].index > 0) {
3144 cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, ioRecs[i].index, resource);
3145 } else {
3146 cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs + i) + 'A', IO_GPIOPinIdx(ioRecs + i), owner, resource);
3151 void cliDfu(char *cmdLine)
3153 UNUSED(cmdLine);
3154 cliPrint("\r\nRestarting in DFU mode");
3155 cliRebootEx(true);
3158 void cliInit(serialConfig_t *serialConfig)
3160 UNUSED(serialConfig);
3162 #endif