Taskmain rework part II
[betaflight.git] / src / main / io / serial_cli.c
blob0cbd7dc0bdb218dd79e61f40e314a3313716d1a0
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <stdarg.h>
22 #include <string.h>
23 #include <math.h>
24 #include <ctype.h>
26 #include "platform.h"
27 #include "scheduler.h"
28 #include "version.h"
30 #include "build_config.h"
32 #include "common/axis.h"
33 #include "common/maths.h"
34 #include "common/color.h"
35 #include "common/typeconversion.h"
37 #include "drivers/system.h"
39 #include "drivers/sensor.h"
40 #include "drivers/accgyro.h"
41 #include "drivers/compass.h"
43 #include "drivers/serial.h"
44 #include "drivers/bus_i2c.h"
45 #include "drivers/gpio.h"
46 #include "drivers/timer.h"
47 #include "drivers/pwm_rx.h"
48 #include "drivers/sdcard.h"
49 #include "drivers/gyro_sync.h"
51 #include "drivers/buf_writer.h"
53 #include "io/escservo.h"
54 #include "io/gps.h"
55 #include "io/gimbal.h"
56 #include "io/rc_controls.h"
57 #include "io/serial.h"
58 #include "io/ledstrip.h"
59 #include "io/flashfs.h"
60 #include "io/beeper.h"
61 #include "io/asyncfatfs/asyncfatfs.h"
63 #include "rx/rx.h"
64 #include "rx/spektrum.h"
66 #include "sensors/battery.h"
67 #include "sensors/boardalignment.h"
68 #include "sensors/sensors.h"
69 #include "sensors/acceleration.h"
70 #include "sensors/gyro.h"
71 #include "sensors/compass.h"
72 #include "sensors/barometer.h"
74 #include "flight/pid.h"
75 #include "flight/imu.h"
76 #include "flight/mixer.h"
77 #include "flight/navigation.h"
78 #include "flight/failsafe.h"
80 #include "telemetry/telemetry.h"
81 #include "telemetry/frsky.h"
83 #include "config/runtime_config.h"
84 #include "config/config.h"
85 #include "config/config_profile.h"
86 #include "config/config_master.h"
88 #include "common/printf.h"
90 #include "serial_cli.h"
92 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
93 // signal that we're in cli mode
94 uint8_t cliMode = 0;
96 #ifdef USE_CLI
98 extern uint16_t cycleTime; // FIXME dependency on mw.c
100 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
102 static serialPort_t *cliPort;
103 static bufWriter_t *cliWriter;
104 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
106 static void cliAux(char *cmdline);
107 static void cliRxFail(char *cmdline);
108 static void cliAdjustmentRange(char *cmdline);
109 static void cliMotorMix(char *cmdline);
110 static void cliDefaults(char *cmdline);
111 static void cliDump(char *cmdLine);
112 static void cliExit(char *cmdline);
113 static void cliFeature(char *cmdline);
114 static void cliMotor(char *cmdline);
115 static void cliPlaySound(char *cmdline);
116 static void cliProfile(char *cmdline);
117 static void cliRateProfile(char *cmdline);
118 static void cliReboot(void);
119 static void cliSave(char *cmdline);
120 static void cliSerial(char *cmdline);
121 #ifndef SKIP_SERIAL_PASSTHROUGH
122 static void cliSerialPassthrough(char *cmdline);
123 #endif
125 #ifdef USE_SERVOS
126 static void cliServo(char *cmdline);
127 static void cliServoMix(char *cmdline);
128 #endif
130 static void cliSet(char *cmdline);
131 static void cliGet(char *cmdline);
132 static void cliStatus(char *cmdline);
133 #ifndef SKIP_TASK_STATISTICS
134 static void cliTasks(char *cmdline);
135 #endif
136 static void cliVersion(char *cmdline);
137 static void cliRxRange(char *cmdline);
139 #ifdef GPS
140 static void cliGpsPassthrough(char *cmdline);
141 #endif
143 static void cliHelp(char *cmdline);
144 static void cliMap(char *cmdline);
146 #ifdef LED_STRIP
147 static void cliLed(char *cmdline);
148 static void cliColor(char *cmdline);
149 #endif
151 #ifndef USE_QUAD_MIXER_ONLY
152 static void cliMixer(char *cmdline);
153 #endif
155 #ifdef USE_FLASHFS
156 static void cliFlashInfo(char *cmdline);
157 static void cliFlashErase(char *cmdline);
158 #ifdef USE_FLASH_TOOLS
159 static void cliFlashWrite(char *cmdline);
160 static void cliFlashRead(char *cmdline);
161 #endif
162 #endif
164 #ifdef USE_SDCARD
165 static void cliSdInfo(char *cmdline);
166 #endif
168 // buffer
169 static char cliBuffer[48];
170 static uint32_t bufferIndex = 0;
172 #ifndef USE_QUAD_MIXER_ONLY
173 // sync this with mixerMode_e
174 static const char * const mixerNames[] = {
175 "TRI", "QUADP", "QUADX", "BI",
176 "GIMBAL", "Y6", "HEX6",
177 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
178 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
179 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
180 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
182 #endif
184 // sync this with features_e
185 static const char * const featureNames[] = {
186 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
187 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
188 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
189 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
190 "BLACKBOX", "CHANNEL_FORWARDING", NULL
193 // sync this with rxFailsafeChannelMode_e
194 static const char rxFailsafeModeCharacters[] = "ahs";
196 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
197 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
198 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
201 #ifndef CJMCU
202 // sync this with sensors_e
203 static const char * const sensorTypeNames[] = {
204 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
207 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
209 static const char * const sensorHardwareNames[4][11] = {
210 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
211 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
212 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
213 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
215 #endif
217 typedef struct {
218 const char *name;
219 #ifndef SKIP_CLI_COMMAND_HELP
220 const char *description;
221 const char *args;
222 #endif
223 void (*func)(char *cmdline);
224 } clicmd_t;
226 #ifndef SKIP_CLI_COMMAND_HELP
227 #define CLI_COMMAND_DEF(name, description, args, method) \
229 name , \
230 description , \
231 args , \
232 method \
234 #else
235 #define CLI_COMMAND_DEF(name, description, args, method) \
237 name, \
238 method \
240 #endif
242 // should be sorted a..z for bsearch()
243 const clicmd_t cmdTable[] = {
244 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
245 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
246 #ifdef LED_STRIP
247 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
248 #endif
249 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
250 CLI_COMMAND_DEF("dump", "dump configuration",
251 "[master|profile]", cliDump),
252 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
253 CLI_COMMAND_DEF("feature", "configure features",
254 "list\r\n"
255 "\t<+|->[name]", cliFeature),
256 #ifdef USE_FLASHFS
257 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
258 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
259 #ifdef USE_FLASH_TOOLS
260 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
261 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
262 #endif
263 #endif
264 CLI_COMMAND_DEF("get", "get variable value",
265 "[name]", cliGet),
266 #ifdef GPS
267 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
268 #endif
269 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
270 #ifdef LED_STRIP
271 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
272 #endif
273 CLI_COMMAND_DEF("map", "configure rc channel order",
274 "[<map>]", cliMap),
275 #ifndef USE_QUAD_MIXER_ONLY
276 CLI_COMMAND_DEF("mixer", "configure mixer",
277 "list\r\n"
278 "\t<name>", cliMixer),
279 #endif
280 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
281 CLI_COMMAND_DEF("motor", "get/set motor",
282 "<index> [<value>]", cliMotor),
283 CLI_COMMAND_DEF("play_sound", NULL,
284 "[<index>]\r\n", cliPlaySound),
285 CLI_COMMAND_DEF("profile", "change profile",
286 "[<index>]", cliProfile),
287 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile),
288 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
289 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
290 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
291 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
292 #ifndef SKIP_SERIAL_PASSTHROUGH
293 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
294 "<id> [baud] [mode] : passthrough to serial",
295 cliSerialPassthrough),
296 #endif
297 #ifdef USE_SERVOS
298 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
299 #endif
300 CLI_COMMAND_DEF("set", "change setting",
301 "[<name>=<value>]", cliSet),
302 #ifdef USE_SERVOS
303 CLI_COMMAND_DEF("smix", "servo mixer",
304 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
305 "\treset\r\n"
306 "\tload <mixer>\r\n"
307 "\treverse <servo> <source> r|n", cliServoMix),
308 #endif
309 #ifdef USE_SDCARD
310 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
311 #endif
312 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
313 #ifndef SKIP_TASK_STATISTICS
314 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
315 #endif
316 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
318 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
320 static const char * const lookupTableOffOn[] = {
321 "OFF", "ON"
324 static const char * const lookupTableUnit[] = {
325 "IMPERIAL", "METRIC"
328 static const char * const lookupTableAlignment[] = {
329 "DEFAULT",
330 "CW0",
331 "CW90",
332 "CW180",
333 "CW270",
334 "CW0FLIP",
335 "CW90FLIP",
336 "CW180FLIP",
337 "CW270FLIP"
340 #ifdef GPS
341 static const char * const lookupTableGPSProvider[] = {
342 "NMEA", "UBLOX"
345 static const char * const lookupTableGPSSBASMode[] = {
346 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
348 #endif
350 static const char * const lookupTableCurrentSensor[] = {
351 "NONE", "ADC", "VIRTUAL"
354 static const char * const lookupTableGimbalMode[] = {
355 "NORMAL", "MIXTILT"
358 static const char * const lookupTableBlackboxDevice[] = {
359 "SERIAL", "SPIFLASH", "SDCARD"
363 static const char * const lookupTablePidController[] = {
364 "MW23", "MWREWRITE", "LUX"
367 static const char * const lookupTableSerialRX[] = {
368 "SPEK1024",
369 "SPEK2048",
370 "SBUS",
371 "SUMD",
372 "SUMH",
373 "XB-B",
374 "XB-B-RJ01",
375 "IBUS",
376 "JETIEXBUS"
379 static const char * const lookupTableGyroLpf[] = {
380 "OFF",
381 "188HZ",
382 "98HZ",
383 "42HZ"
386 static const char * const lookupTableAccHardware[] = {
387 "AUTO",
388 "NONE",
389 "ADXL345",
390 "MPU6050",
391 "MMA8452",
392 "BMA280",
393 "LSM303DLHC",
394 "MPU6000",
395 "MPU6500",
396 "FAKE"
399 static const char * const lookupTableBaroHardware[] = {
400 "AUTO",
401 "NONE",
402 "BMP085",
403 "MS5611",
404 "BMP280"
407 static const char * const lookupTableMagHardware[] = {
408 "AUTO",
409 "NONE",
410 "HMC5883",
411 "AK8975",
412 "AK8963"
415 static const char * const lookupDeltaMethod[] = {
416 "ERROR", "MEASUREMENT"
419 typedef struct lookupTableEntry_s {
420 const char * const *values;
421 const uint8_t valueCount;
422 } lookupTableEntry_t;
424 typedef enum {
425 TABLE_OFF_ON = 0,
426 TABLE_UNIT,
427 TABLE_ALIGNMENT,
428 #ifdef GPS
429 TABLE_GPS_PROVIDER,
430 TABLE_GPS_SBAS_MODE,
431 #endif
432 #ifdef BLACKBOX
433 TABLE_BLACKBOX_DEVICE,
434 #endif
435 TABLE_CURRENT_SENSOR,
436 TABLE_GIMBAL_MODE,
437 TABLE_PID_CONTROLLER,
438 TABLE_SERIAL_RX,
439 TABLE_GYRO_LPF,
440 TABLE_ACC_HARDWARE,
441 TABLE_BARO_HARDWARE,
442 TABLE_MAG_HARDWARE,
443 TABLE_DELTA_METHOD,
444 } lookupTableIndex_e;
446 static const lookupTableEntry_t lookupTables[] = {
447 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
448 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
449 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
450 #ifdef GPS
451 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
452 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
453 #endif
454 #ifdef BLACKBOX
455 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
456 #endif
457 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
458 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
459 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
460 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
461 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
462 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
463 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
464 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
465 { lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) }
468 #define VALUE_TYPE_OFFSET 0
469 #define VALUE_SECTION_OFFSET 4
470 #define VALUE_MODE_OFFSET 6
472 typedef enum {
473 // value type
474 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
475 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
476 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
477 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
478 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
479 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
481 // value section
482 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
483 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
484 PROFILE_RATE_VALUE = (2 << VALUE_SECTION_OFFSET),
485 // value mode
486 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
487 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
488 } cliValueFlag_e;
490 #define VALUE_TYPE_MASK (0x0F)
491 #define VALUE_SECTION_MASK (0x30)
492 #define VALUE_MODE_MASK (0xC0)
494 typedef struct cliMinMaxConfig_s {
495 const int32_t min;
496 const int32_t max;
497 } cliMinMaxConfig_t;
499 typedef struct cliLookupTableConfig_s {
500 const lookupTableIndex_e tableIndex;
501 } cliLookupTableConfig_t;
503 typedef union {
504 cliLookupTableConfig_t lookup;
505 cliMinMaxConfig_t minmax;
507 } cliValueConfig_t;
509 typedef struct {
510 const char *name;
511 const uint8_t type; // see cliValueFlag_e
512 void *ptr;
513 const cliValueConfig_t config;
514 } clivalue_t;
516 const clivalue_t valueTable[] = {
517 { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
519 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
520 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
521 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
522 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
523 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
524 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
525 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
526 { "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_OFF_ON } },
527 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
528 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
529 { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_OFF_ON } },
531 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
532 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
533 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
534 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
536 { "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
537 { "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,
538 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
539 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
541 { "use_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_fast_pwm, .config.lookup = { TABLE_OFF_ON } },
542 { "use_oneshot42", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_oneshot42, .config.lookup = { TABLE_OFF_ON } },
543 { "use_multishot", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_multiShot, .config.lookup = { TABLE_OFF_ON } },
544 #ifdef CC3D
545 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
546 #endif
547 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 } },
548 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
550 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
551 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
552 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
554 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
556 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
558 #ifdef GPS
559 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
560 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
561 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
562 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
564 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
565 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
566 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
567 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
568 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
569 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
570 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
571 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
572 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
573 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
574 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
575 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
576 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
577 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
578 #endif
579 #ifdef GTUNE
580 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
581 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
582 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
583 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
584 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
585 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
586 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
587 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
588 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
589 #endif
591 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
592 { "sbus_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.sbus_inversion, .config.lookup = { TABLE_OFF_ON } },
593 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
595 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
596 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
597 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
598 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
599 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
600 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
601 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
602 { "frsky_vfas_cell_voltage", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_vfas_cell_voltage, .config.lookup = { TABLE_OFF_ON } },
603 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
605 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
606 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
607 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
608 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
609 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
610 { "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
611 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
612 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
613 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
614 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
616 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
617 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
618 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
620 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
621 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
622 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
624 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
626 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
627 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
628 { "gyro_soft_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } },
629 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
630 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
631 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
633 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
634 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
635 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
636 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
638 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
639 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
641 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
643 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
644 { "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, .config.minmax = { YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH } },
645 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
646 #ifdef USE_SERVOS
647 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
648 { "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
649 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
650 #endif
652 { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } },
653 { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } },
654 { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } },
655 { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } },
656 { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } },
657 { "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 } },
658 { "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 } },
659 { "yaw_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
660 { "tpa_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
661 { "tpa_breakpoint", VAR_UINT16 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
662 { "acro_plus_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusFactor, .config.minmax = {1, 100 } },
663 { "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } },
665 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
666 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
667 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
668 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
669 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
670 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
672 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
673 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
675 #ifdef USE_SERVOS
676 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
677 #endif
679 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
680 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
681 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
682 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
683 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
684 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
685 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
687 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
688 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
689 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
690 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
691 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
693 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
694 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
695 { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
696 { "dterm_lpf_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
697 { "dterm_average_count", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_average_count, .config.minmax = {2, 12 } },
698 { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } },
700 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
702 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
703 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
704 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
705 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
706 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
707 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
708 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
709 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
710 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
712 { "p_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[PITCH], .config.minmax = { 0, 100 } },
713 { "i_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[PITCH], .config.minmax = { 0, 100 } },
714 { "d_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[PITCH], .config.minmax = { 0, 100 } },
715 { "p_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[ROLL], .config.minmax = { 0, 100 } },
716 { "i_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[ROLL], .config.minmax = { 0, 100 } },
717 { "d_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[ROLL], .config.minmax = { 0, 100 } },
718 { "p_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[YAW], .config.minmax = { 0, 100 } },
719 { "i_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[YAW], .config.minmax = { 0, 100 } },
720 { "d_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[YAW], .config.minmax = { 0, 100 } },
722 { "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, .config.minmax = { 0, 10 } },
723 { "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, .config.minmax = { 0, 10 } },
724 { "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, .config.minmax = { 0, 250 } },
726 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
727 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
728 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
730 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
731 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
732 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
734 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
735 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
736 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
738 #ifdef BLACKBOX
739 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
740 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
741 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
742 #endif
744 { "beeper_off_flags", VAR_UINT32 | MASTER_VALUE, &masterConfig.beeper_off.flags, .config.minmax = {BEEPER_OFF_FLAGS_MIN, BEEPER_OFF_FLAGS_MAX }},
746 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
747 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
748 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
751 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
754 typedef union {
755 int32_t int_value;
756 float float_value;
757 } int_float_value_t;
759 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
760 static void cliPrintVar(const clivalue_t *var, uint32_t full);
761 static void cliPrint(const char *str);
762 static void cliPrintf(const char *fmt, ...);
763 static void cliWrite(uint8_t ch);
765 static void cliPrompt(void)
767 cliPrint("\r\n# ");
768 bufWriterFlush(cliWriter);
771 static void cliShowParseError(void)
773 cliPrint("Parse error\r\n");
776 static void cliShowArgumentRangeError(char *name, int min, int max)
778 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
781 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
783 int val;
785 for (int argIndex = 0; argIndex < 2; argIndex++) {
786 ptr = strchr(ptr, ' ');
787 if (ptr) {
788 val = atoi(++ptr);
789 val = CHANNEL_VALUE_TO_STEP(val);
790 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
791 if (argIndex == 0) {
792 range->startStep = val;
793 } else {
794 range->endStep = val;
796 (*validArgumentCount)++;
801 return ptr;
804 // Check if a string's length is zero
805 static bool isEmpty(const char *string)
807 return *string == '\0';
810 static void cliRxFail(char *cmdline)
812 uint8_t channel;
813 char buf[3];
815 if (isEmpty(cmdline)) {
816 // print out rxConfig failsafe settings
817 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
818 cliRxFail(itoa(channel, buf, 10));
820 } else {
821 char *ptr = cmdline;
822 channel = atoi(ptr++);
823 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
825 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
827 uint16_t value;
828 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
829 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
830 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
832 ptr = strchr(ptr, ' ');
833 if (ptr) {
834 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
835 if (p) {
836 uint8_t requestedMode = p - rxFailsafeModeCharacters;
837 mode = rxFailsafeModesTable[type][requestedMode];
838 } else {
839 mode = RX_FAILSAFE_MODE_INVALID;
841 if (mode == RX_FAILSAFE_MODE_INVALID) {
842 cliShowParseError();
843 return;
846 requireValue = mode == RX_FAILSAFE_MODE_SET;
848 ptr = strchr(ptr, ' ');
849 if (ptr) {
850 if (!requireValue) {
851 cliShowParseError();
852 return;
854 value = atoi(++ptr);
855 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
856 if (value > MAX_RXFAIL_RANGE_STEP) {
857 cliPrint("Value out of range\r\n");
858 return;
861 channelFailsafeConfiguration->step = value;
862 } else if (requireValue) {
863 cliShowParseError();
864 return;
866 channelFailsafeConfiguration->mode = mode;
870 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
872 // triple use of cliPrintf below
873 // 1. acknowledge interpretation on command,
874 // 2. query current setting on single item,
875 // 3. recursive use for full list.
877 if (requireValue) {
878 cliPrintf("rxfail %u %c %d\r\n",
879 channel,
880 modeCharacter,
881 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
883 } else {
884 cliPrintf("rxfail %u %c\r\n",
885 channel,
886 modeCharacter
889 } else {
890 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
895 static void cliAux(char *cmdline)
897 int i, val = 0;
898 char *ptr;
900 if (isEmpty(cmdline)) {
901 // print out aux channel settings
902 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
903 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
904 cliPrintf("aux %u %u %u %u %u\r\n",
906 mac->modeId,
907 mac->auxChannelIndex,
908 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
909 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
912 } else {
913 ptr = cmdline;
914 i = atoi(ptr++);
915 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
916 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
917 uint8_t validArgumentCount = 0;
918 ptr = strchr(ptr, ' ');
919 if (ptr) {
920 val = atoi(++ptr);
921 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
922 mac->modeId = val;
923 validArgumentCount++;
926 ptr = strchr(ptr, ' ');
927 if (ptr) {
928 val = atoi(++ptr);
929 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
930 mac->auxChannelIndex = val;
931 validArgumentCount++;
934 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
936 if (validArgumentCount != 4) {
937 memset(mac, 0, sizeof(modeActivationCondition_t));
939 } else {
940 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
945 static void cliSerial(char *cmdline)
947 int i, val;
948 char *ptr;
950 if (isEmpty(cmdline)) {
951 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
952 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
953 continue;
955 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
956 masterConfig.serialConfig.portConfigs[i].identifier,
957 masterConfig.serialConfig.portConfigs[i].functionMask,
958 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
959 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
960 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
961 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
964 return;
967 serialPortConfig_t portConfig;
968 memset(&portConfig, 0 , sizeof(portConfig));
970 serialPortConfig_t *currentConfig;
972 uint8_t validArgumentCount = 0;
974 ptr = cmdline;
976 val = atoi(ptr++);
977 currentConfig = serialFindPortConfiguration(val);
978 if (currentConfig) {
979 portConfig.identifier = val;
980 validArgumentCount++;
983 ptr = strchr(ptr, ' ');
984 if (ptr) {
985 val = atoi(++ptr);
986 portConfig.functionMask = val & 0xFFFF;
987 validArgumentCount++;
990 for (i = 0; i < 4; i ++) {
991 ptr = strchr(ptr, ' ');
992 if (!ptr) {
993 break;
996 val = atoi(++ptr);
998 uint8_t baudRateIndex = lookupBaudRateIndex(val);
999 if (baudRates[baudRateIndex] != (uint32_t) val) {
1000 break;
1003 switch(i) {
1004 case 0:
1005 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1006 continue;
1008 portConfig.msp_baudrateIndex = baudRateIndex;
1009 break;
1010 case 1:
1011 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1012 continue;
1014 portConfig.gps_baudrateIndex = baudRateIndex;
1015 break;
1016 case 2:
1017 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1018 continue;
1020 portConfig.telemetry_baudrateIndex = baudRateIndex;
1021 break;
1022 case 3:
1023 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1024 continue;
1026 portConfig.blackbox_baudrateIndex = baudRateIndex;
1027 break;
1030 validArgumentCount++;
1033 if (validArgumentCount < 6) {
1034 cliShowParseError();
1035 return;
1038 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1042 #ifndef SKIP_SERIAL_PASSTHROUGH
1043 static void cliSerialPassthrough(char *cmdline)
1045 if (isEmpty(cmdline)) {
1046 cliShowParseError();
1047 return;
1050 int id = -1;
1051 uint32_t baud = 0;
1052 unsigned mode = 0;
1053 char* tok = strtok(cmdline, " ");
1054 int index = 0;
1056 while (tok != NULL) {
1057 switch(index) {
1058 case 0:
1059 id = atoi(tok);
1060 break;
1061 case 1:
1062 baud = atoi(tok);
1063 break;
1064 case 2:
1065 if (strstr(tok, "rx") || strstr(tok, "RX"))
1066 mode |= MODE_RX;
1067 if (strstr(tok, "tx") || strstr(tok, "TX"))
1068 mode |= MODE_TX;
1069 break;
1071 index++;
1072 tok = strtok(NULL, " ");
1075 serialPort_t *passThroughPort;
1076 serialPortUsage_t *passThroughPortUsage = findSerialPortUsageByIdentifier(id);
1077 if (!passThroughPortUsage || passThroughPortUsage->serialPort == NULL) {
1078 if (!baud) {
1079 printf("Port %d is not open, you must specify baud\r\n", id);
1080 return;
1082 if (!mode)
1083 mode = MODE_RXTX;
1085 passThroughPort = openSerialPort(id, FUNCTION_PASSTHROUGH, NULL,
1086 baud, mode,
1087 SERIAL_NOT_INVERTED);
1088 if (!passThroughPort) {
1089 printf("Port %d could not be opened\r\n", id);
1090 return;
1092 printf("Port %d opened, baud=%d\r\n", id, baud);
1093 } else {
1094 passThroughPort = passThroughPortUsage->serialPort;
1095 // If the user supplied a mode, override the port's mode, otherwise
1096 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1097 printf("Port %d already open\r\n", id);
1098 if (mode && passThroughPort->mode != mode) {
1099 printf("Adjusting mode from configured value %d to %d\r\n",
1100 passThroughPort->mode, mode);
1101 serialSetMode(passThroughPort, mode);
1105 printf("Relaying data to device on port %d, Reset your board to exit "
1106 "serial passthrough mode.\r\n");
1108 serialPassthrough(cliPort, passThroughPort, NULL, NULL);
1110 #endif
1112 static void cliAdjustmentRange(char *cmdline)
1114 int i, val = 0;
1115 char *ptr;
1117 if (isEmpty(cmdline)) {
1118 // print out adjustment ranges channel settings
1119 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1120 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1121 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1123 ar->adjustmentIndex,
1124 ar->auxChannelIndex,
1125 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1126 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1127 ar->adjustmentFunction,
1128 ar->auxSwitchChannelIndex
1131 } else {
1132 ptr = cmdline;
1133 i = atoi(ptr++);
1134 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1135 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1136 uint8_t validArgumentCount = 0;
1138 ptr = strchr(ptr, ' ');
1139 if (ptr) {
1140 val = atoi(++ptr);
1141 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1142 ar->adjustmentIndex = val;
1143 validArgumentCount++;
1146 ptr = strchr(ptr, ' ');
1147 if (ptr) {
1148 val = atoi(++ptr);
1149 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1150 ar->auxChannelIndex = val;
1151 validArgumentCount++;
1155 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1157 ptr = strchr(ptr, ' ');
1158 if (ptr) {
1159 val = atoi(++ptr);
1160 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1161 ar->adjustmentFunction = val;
1162 validArgumentCount++;
1165 ptr = strchr(ptr, ' ');
1166 if (ptr) {
1167 val = atoi(++ptr);
1168 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1169 ar->auxSwitchChannelIndex = val;
1170 validArgumentCount++;
1174 if (validArgumentCount != 6) {
1175 memset(ar, 0, sizeof(adjustmentRange_t));
1176 cliShowParseError();
1178 } else {
1179 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1184 static void cliMotorMix(char *cmdline)
1186 #ifdef USE_QUAD_MIXER_ONLY
1187 UNUSED(cmdline);
1188 #else
1189 int i, check = 0;
1190 int num_motors = 0;
1191 uint8_t len;
1192 char buf[16];
1193 char *ptr;
1195 if (isEmpty(cmdline)) {
1196 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1197 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1198 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1199 break;
1200 num_motors++;
1201 cliPrintf("#%d:\t", i);
1202 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1203 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1204 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1205 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1207 return;
1208 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1209 // erase custom mixer
1210 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1211 masterConfig.customMotorMixer[i].throttle = 0.0f;
1212 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1213 ptr = strchr(cmdline, ' ');
1214 if (ptr) {
1215 len = strlen(++ptr);
1216 for (i = 0; ; i++) {
1217 if (mixerNames[i] == NULL) {
1218 cliPrint("Invalid name\r\n");
1219 break;
1221 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1222 mixerLoadMix(i, masterConfig.customMotorMixer);
1223 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1224 cliMotorMix("");
1225 break;
1229 } else {
1230 ptr = cmdline;
1231 i = atoi(ptr); // get motor number
1232 if (i < MAX_SUPPORTED_MOTORS) {
1233 ptr = strchr(ptr, ' ');
1234 if (ptr) {
1235 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1236 check++;
1238 ptr = strchr(ptr, ' ');
1239 if (ptr) {
1240 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1241 check++;
1243 ptr = strchr(ptr, ' ');
1244 if (ptr) {
1245 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1246 check++;
1248 ptr = strchr(ptr, ' ');
1249 if (ptr) {
1250 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1251 check++;
1253 if (check != 4) {
1254 cliShowParseError();
1255 } else {
1256 cliMotorMix("");
1258 } else {
1259 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1262 #endif
1265 static void cliRxRange(char *cmdline)
1267 int i, validArgumentCount = 0;
1268 char *ptr;
1270 if (isEmpty(cmdline)) {
1271 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1272 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1273 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1275 } else if (strcasecmp(cmdline, "reset") == 0) {
1276 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1277 } else {
1278 ptr = cmdline;
1279 i = atoi(ptr);
1280 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1281 int rangeMin, rangeMax;
1283 ptr = strchr(ptr, ' ');
1284 if (ptr) {
1285 rangeMin = atoi(++ptr);
1286 validArgumentCount++;
1289 ptr = strchr(ptr, ' ');
1290 if (ptr) {
1291 rangeMax = atoi(++ptr);
1292 validArgumentCount++;
1295 if (validArgumentCount != 2) {
1296 cliShowParseError();
1297 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1298 cliShowParseError();
1299 } else {
1300 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1301 channelRangeConfiguration->min = rangeMin;
1302 channelRangeConfiguration->max = rangeMax;
1304 } else {
1305 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1310 #ifdef LED_STRIP
1311 static void cliLed(char *cmdline)
1313 int i;
1314 char *ptr;
1315 char ledConfigBuffer[20];
1317 if (isEmpty(cmdline)) {
1318 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1319 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1320 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1322 } else {
1323 ptr = cmdline;
1324 i = atoi(ptr);
1325 if (i < MAX_LED_STRIP_LENGTH) {
1326 ptr = strchr(cmdline, ' ');
1327 if (!parseLedStripConfig(i, ++ptr)) {
1328 cliShowParseError();
1330 } else {
1331 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1336 static void cliColor(char *cmdline)
1338 int i;
1339 char *ptr;
1341 if (isEmpty(cmdline)) {
1342 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1343 cliPrintf("color %u %d,%u,%u\r\n",
1345 masterConfig.colors[i].h,
1346 masterConfig.colors[i].s,
1347 masterConfig.colors[i].v
1350 } else {
1351 ptr = cmdline;
1352 i = atoi(ptr);
1353 if (i < CONFIGURABLE_COLOR_COUNT) {
1354 ptr = strchr(cmdline, ' ');
1355 if (!parseColor(i, ++ptr)) {
1356 cliShowParseError();
1358 } else {
1359 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1363 #endif
1365 #ifdef USE_SERVOS
1366 static void cliServo(char *cmdline)
1368 enum { SERVO_ARGUMENT_COUNT = 8 };
1369 int16_t arguments[SERVO_ARGUMENT_COUNT];
1371 servoParam_t *servo;
1373 int i;
1374 char *ptr;
1376 if (isEmpty(cmdline)) {
1377 // print out servo settings
1378 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1379 servo = &masterConfig.servoConf[i];
1381 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1383 servo->min,
1384 servo->max,
1385 servo->middle,
1386 servo->angleAtMin,
1387 servo->angleAtMax,
1388 servo->rate,
1389 servo->forwardFromChannel
1392 } else {
1393 int validArgumentCount = 0;
1395 ptr = cmdline;
1397 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1399 // If command line doesn't fit the format, don't modify the config
1400 while (*ptr) {
1401 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1402 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1403 cliShowParseError();
1404 return;
1407 arguments[validArgumentCount++] = atoi(ptr);
1409 do {
1410 ptr++;
1411 } while (*ptr >= '0' && *ptr <= '9');
1412 } else if (*ptr == ' ') {
1413 ptr++;
1414 } else {
1415 cliShowParseError();
1416 return;
1420 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1422 i = arguments[INDEX];
1424 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1425 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1426 cliShowParseError();
1427 return;
1430 servo = &masterConfig.servoConf[i];
1432 if (
1433 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1434 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1435 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1436 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1437 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1438 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1439 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1440 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1442 cliShowParseError();
1443 return;
1446 servo->min = arguments[1];
1447 servo->max = arguments[2];
1448 servo->middle = arguments[3];
1449 servo->angleAtMin = arguments[4];
1450 servo->angleAtMax = arguments[5];
1451 servo->rate = arguments[6];
1452 servo->forwardFromChannel = arguments[7];
1455 #endif
1457 #ifdef USE_SERVOS
1458 static void cliServoMix(char *cmdline)
1460 int i;
1461 uint8_t len;
1462 char *ptr;
1463 int args[8], check = 0;
1464 len = strlen(cmdline);
1466 if (len == 0) {
1468 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1470 for (i = 0; i < MAX_SERVO_RULES; i++) {
1471 if (masterConfig.customServoMixer[i].rate == 0)
1472 break;
1474 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1476 masterConfig.customServoMixer[i].targetChannel,
1477 masterConfig.customServoMixer[i].inputSource,
1478 masterConfig.customServoMixer[i].rate,
1479 masterConfig.customServoMixer[i].speed,
1480 masterConfig.customServoMixer[i].min,
1481 masterConfig.customServoMixer[i].max,
1482 masterConfig.customServoMixer[i].box
1485 cliPrintf("\r\n");
1486 return;
1487 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1488 // erase custom mixer
1489 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1490 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1491 masterConfig.servoConf[i].reversedSources = 0;
1493 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1494 ptr = strchr(cmdline, ' ');
1495 if (ptr) {
1496 len = strlen(++ptr);
1497 for (i = 0; ; i++) {
1498 if (mixerNames[i] == NULL) {
1499 cliPrintf("Invalid name\r\n");
1500 break;
1502 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1503 servoMixerLoadMix(i, masterConfig.customServoMixer);
1504 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1505 cliServoMix("");
1506 break;
1510 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1511 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1512 int servoIndex, inputSource;
1513 ptr = strchr(cmdline, ' ');
1515 len = strlen(ptr);
1516 if (len == 0) {
1517 cliPrintf("s");
1518 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1519 cliPrintf("\ti%d", inputSource);
1520 cliPrintf("\r\n");
1522 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1523 cliPrintf("%d", servoIndex);
1524 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1525 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1526 cliPrintf("\r\n");
1528 return;
1531 ptr = strtok(ptr, " ");
1532 while (ptr != NULL && check < ARGS_COUNT - 1) {
1533 args[check++] = atoi(ptr);
1534 ptr = strtok(NULL, " ");
1537 if (ptr == NULL || check != ARGS_COUNT - 1) {
1538 cliShowParseError();
1539 return;
1542 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1543 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1544 && (*ptr == 'r' || *ptr == 'n')) {
1545 if (*ptr == 'r')
1546 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1547 else
1548 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1549 } else
1550 cliShowParseError();
1552 cliServoMix("reverse");
1553 } else {
1554 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1555 ptr = strtok(cmdline, " ");
1556 while (ptr != NULL && check < ARGS_COUNT) {
1557 args[check++] = atoi(ptr);
1558 ptr = strtok(NULL, " ");
1561 if (ptr != NULL || check != ARGS_COUNT) {
1562 cliShowParseError();
1563 return;
1566 i = args[RULE];
1567 if (i >= 0 && i < MAX_SERVO_RULES &&
1568 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1569 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1570 args[RATE] >= -100 && args[RATE] <= 100 &&
1571 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1572 args[MIN] >= 0 && args[MIN] <= 100 &&
1573 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1574 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1575 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1576 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1577 masterConfig.customServoMixer[i].rate = args[RATE];
1578 masterConfig.customServoMixer[i].speed = args[SPEED];
1579 masterConfig.customServoMixer[i].min = args[MIN];
1580 masterConfig.customServoMixer[i].max = args[MAX];
1581 masterConfig.customServoMixer[i].box = args[BOX];
1582 cliServoMix("");
1583 } else {
1584 cliShowParseError();
1588 #endif
1590 #ifdef USE_SDCARD
1592 static void cliWriteBytes(const uint8_t *buffer, int count)
1594 while (count > 0) {
1595 cliWrite(*buffer);
1596 buffer++;
1597 count--;
1601 static void cliSdInfo(char *cmdline) {
1602 UNUSED(cmdline);
1604 cliPrint("SD card: ");
1606 if (!sdcard_isInserted()) {
1607 cliPrint("None inserted\r\n");
1608 return;
1611 if (!sdcard_isInitialized()) {
1612 cliPrint("Startup failed\r\n");
1613 return;
1616 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1618 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1619 metadata->manufacturerID,
1620 metadata->numBlocks / 2, /* One block is half a kB */
1621 metadata->productionMonth,
1622 metadata->productionYear,
1623 metadata->productRevisionMajor,
1624 metadata->productRevisionMinor
1627 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1629 cliPrint("'\r\n" "Filesystem: ");
1631 switch (afatfs_getFilesystemState()) {
1632 case AFATFS_FILESYSTEM_STATE_READY:
1633 cliPrint("Ready");
1634 break;
1635 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1636 cliPrint("Initializing");
1637 break;
1638 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1639 case AFATFS_FILESYSTEM_STATE_FATAL:
1640 cliPrint("Fatal");
1642 switch (afatfs_getLastError()) {
1643 case AFATFS_ERROR_BAD_MBR:
1644 cliPrint(" - no FAT MBR partitions");
1645 break;
1646 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1647 cliPrint(" - bad FAT header");
1648 break;
1649 case AFATFS_ERROR_GENERIC:
1650 case AFATFS_ERROR_NONE:
1651 ; // Nothing more detailed to print
1652 break;
1655 cliPrint("\r\n");
1656 break;
1660 #endif
1662 #ifdef USE_FLASHFS
1664 static void cliFlashInfo(char *cmdline)
1666 const flashGeometry_t *layout = flashfsGetGeometry();
1668 UNUSED(cmdline);
1670 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1671 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1674 static void cliFlashErase(char *cmdline)
1676 UNUSED(cmdline);
1678 cliPrintf("Erasing...\r\n");
1679 flashfsEraseCompletely();
1681 while (!flashfsIsReady()) {
1682 delay(100);
1685 cliPrintf("Done.\r\n");
1688 #ifdef USE_FLASH_TOOLS
1690 static void cliFlashWrite(char *cmdline)
1692 uint32_t address = atoi(cmdline);
1693 char *text = strchr(cmdline, ' ');
1695 if (!text) {
1696 cliShowParseError();
1697 } else {
1698 flashfsSeekAbs(address);
1699 flashfsWrite((uint8_t*)text, strlen(text), true);
1700 flashfsFlushSync();
1702 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1706 static void cliFlashRead(char *cmdline)
1708 uint32_t address = atoi(cmdline);
1709 uint32_t length;
1710 int i;
1712 uint8_t buffer[32];
1714 char *nextArg = strchr(cmdline, ' ');
1716 if (!nextArg) {
1717 cliShowParseError();
1718 } else {
1719 length = atoi(nextArg);
1721 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1723 while (length > 0) {
1724 int bytesRead;
1726 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1728 for (i = 0; i < bytesRead; i++) {
1729 cliWrite(buffer[i]);
1732 length -= bytesRead;
1733 address += bytesRead;
1735 if (bytesRead == 0) {
1736 //Assume we reached the end of the volume or something fatal happened
1737 break;
1740 cliPrintf("\r\n");
1744 #endif
1745 #endif
1747 static void dumpValues(uint16_t valueSection)
1749 uint32_t i;
1750 const clivalue_t *value;
1751 for (i = 0; i < VALUE_COUNT; i++) {
1752 value = &valueTable[i];
1754 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1755 continue;
1758 cliPrintf("set %s = ", valueTable[i].name);
1759 cliPrintVar(value, 0);
1760 cliPrint("\r\n");
1764 typedef enum {
1765 DUMP_MASTER = (1 << 0),
1766 DUMP_PROFILE = (1 << 1),
1767 DUMP_RATES = (1 << 2),
1768 } dumpFlags_e;
1770 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_RATES)
1773 static const char* const sectionBreak = "\r\n";
1775 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1777 static void cliDump(char *cmdline)
1779 unsigned int i;
1780 char buf[16];
1781 uint32_t mask;
1783 #ifndef USE_QUAD_MIXER_ONLY
1784 float thr, roll, pitch, yaw;
1785 #endif
1787 uint8_t dumpMask = DUMP_ALL;
1788 if (strcasecmp(cmdline, "master") == 0) {
1789 dumpMask = DUMP_MASTER; // only
1791 if (strcasecmp(cmdline, "profile") == 0) {
1792 dumpMask = DUMP_PROFILE; // only
1794 if (strcasecmp(cmdline, "rates") == 0) {
1795 dumpMask = DUMP_RATES;
1798 if (dumpMask & DUMP_MASTER) {
1800 cliPrint("\r\n# version\r\n");
1801 cliVersion(NULL);
1803 cliPrint("\r\n# dump master\r\n");
1804 cliPrint("\r\n# mixer\r\n");
1806 #ifndef USE_QUAD_MIXER_ONLY
1807 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1809 cliPrintf("mmix reset\r\n");
1811 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1812 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1813 break;
1814 thr = masterConfig.customMotorMixer[i].throttle;
1815 roll = masterConfig.customMotorMixer[i].roll;
1816 pitch = masterConfig.customMotorMixer[i].pitch;
1817 yaw = masterConfig.customMotorMixer[i].yaw;
1818 cliPrintf("mmix %d", i);
1819 if (thr < 0)
1820 cliWrite(' ');
1821 cliPrintf("%s", ftoa(thr, buf));
1822 if (roll < 0)
1823 cliWrite(' ');
1824 cliPrintf("%s", ftoa(roll, buf));
1825 if (pitch < 0)
1826 cliWrite(' ');
1827 cliPrintf("%s", ftoa(pitch, buf));
1828 if (yaw < 0)
1829 cliWrite(' ');
1830 cliPrintf("%s\r\n", ftoa(yaw, buf));
1833 #ifdef USE_SERVOS
1834 // print custom servo mixer if exists
1835 cliPrintf("smix reset\r\n");
1837 for (i = 0; i < MAX_SERVO_RULES; i++) {
1839 if (masterConfig.customServoMixer[i].rate == 0)
1840 break;
1842 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1844 masterConfig.customServoMixer[i].targetChannel,
1845 masterConfig.customServoMixer[i].inputSource,
1846 masterConfig.customServoMixer[i].rate,
1847 masterConfig.customServoMixer[i].speed,
1848 masterConfig.customServoMixer[i].min,
1849 masterConfig.customServoMixer[i].max,
1850 masterConfig.customServoMixer[i].box
1854 #endif
1855 #endif
1857 cliPrint("\r\n\r\n# feature\r\n");
1859 mask = featureMask();
1860 for (i = 0; ; i++) { // disable all feature first
1861 if (featureNames[i] == NULL)
1862 break;
1863 cliPrintf("feature -%s\r\n", featureNames[i]);
1865 for (i = 0; ; i++) { // reenable what we want.
1866 if (featureNames[i] == NULL)
1867 break;
1868 if (mask & (1 << i))
1869 cliPrintf("feature %s\r\n", featureNames[i]);
1872 cliPrint("\r\n\r\n# map\r\n");
1874 for (i = 0; i < 8; i++)
1875 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1876 buf[i] = '\0';
1877 cliPrintf("map %s\r\n", buf);
1879 cliPrint("\r\n\r\n# serial\r\n");
1880 cliSerial("");
1882 #ifdef LED_STRIP
1883 cliPrint("\r\n\r\n# led\r\n");
1884 cliLed("");
1886 cliPrint("\r\n\r\n# color\r\n");
1887 cliColor("");
1888 #endif
1890 cliPrint("\r\n# aux\r\n");
1892 cliAux("");
1894 cliPrint("\r\n# adjrange\r\n");
1896 cliAdjustmentRange("");
1898 cliPrintf("\r\n# rxrange\r\n");
1900 cliRxRange("");
1902 #ifdef USE_SERVOS
1903 cliPrint("\r\n# servo\r\n");
1905 cliServo("");
1907 // print servo directions
1908 unsigned int channel;
1910 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1911 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
1912 if (servoDirection(i, channel) < 0) {
1913 cliPrintf("smix reverse %d %d r\r\n", i , channel);
1917 #endif
1919 printSectionBreak();
1920 dumpValues(MASTER_VALUE);
1922 cliPrint("\r\n# rxfail\r\n");
1923 cliRxFail("");
1926 if (dumpMask & DUMP_PROFILE) {
1927 cliPrint("\r\n# dump profile\r\n");
1929 cliPrint("\r\n# profile\r\n");
1930 cliProfile("");
1932 printSectionBreak();
1934 dumpValues(PROFILE_VALUE);
1936 cliPrint("\r\n# rateprofile\r\n");
1937 cliRateProfile("");
1939 printSectionBreak();
1941 dumpValues(PROFILE_RATE_VALUE);
1943 if (dumpMask & DUMP_RATES) {
1944 cliPrint("\r\n# dump rates\r\n");
1946 cliPrint("\r\n# rateprofile\r\n");
1947 cliRateProfile("");
1949 printSectionBreak();
1951 dumpValues(PROFILE_RATE_VALUE);
1956 void cliEnter(serialPort_t *serialPort)
1958 cliMode = 1;
1959 cliPort = serialPort;
1960 setPrintfSerialPort(cliPort);
1961 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
1962 (bufWrite_t)serialWriteBufShim, serialPort);
1964 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1965 cliPrompt();
1966 ENABLE_ARMING_FLAG(PREVENT_ARMING);
1969 static void cliExit(char *cmdline)
1971 UNUSED(cmdline);
1973 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1974 bufWriterFlush(cliWriter);
1976 *cliBuffer = '\0';
1977 bufferIndex = 0;
1978 cliMode = 0;
1979 // incase a motor was left running during motortest, clear it here
1980 mixerResetDisarmedMotors();
1981 cliReboot();
1983 cliWriter = NULL;
1986 static void cliFeature(char *cmdline)
1988 uint32_t i;
1989 uint32_t len;
1990 uint32_t mask;
1992 len = strlen(cmdline);
1993 mask = featureMask();
1995 if (len == 0) {
1996 cliPrint("Enabled: ");
1997 for (i = 0; ; i++) {
1998 if (featureNames[i] == NULL)
1999 break;
2000 if (mask & (1 << i))
2001 cliPrintf("%s ", featureNames[i]);
2003 cliPrint("\r\n");
2004 } else if (strncasecmp(cmdline, "list", len) == 0) {
2005 cliPrint("Available: ");
2006 for (i = 0; ; i++) {
2007 if (featureNames[i] == NULL)
2008 break;
2009 cliPrintf("%s ", featureNames[i]);
2011 cliPrint("\r\n");
2012 return;
2013 } else {
2014 bool remove = false;
2015 if (cmdline[0] == '-') {
2016 // remove feature
2017 remove = true;
2018 cmdline++; // skip over -
2019 len--;
2022 for (i = 0; ; i++) {
2023 if (featureNames[i] == NULL) {
2024 cliPrint("Invalid name\r\n");
2025 break;
2028 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
2030 mask = 1 << i;
2031 #ifndef GPS
2032 if (mask & FEATURE_GPS) {
2033 cliPrint("unavailable\r\n");
2034 break;
2036 #endif
2037 #ifndef SONAR
2038 if (mask & FEATURE_SONAR) {
2039 cliPrint("unavailable\r\n");
2040 break;
2042 #endif
2043 if (remove) {
2044 featureClear(mask);
2045 cliPrint("Disabled");
2046 } else {
2047 featureSet(mask);
2048 cliPrint("Enabled");
2050 cliPrintf(" %s\r\n", featureNames[i]);
2051 break;
2057 #ifdef GPS
2058 static void cliGpsPassthrough(char *cmdline)
2060 UNUSED(cmdline);
2062 gpsEnablePassthrough(cliPort);
2064 #endif
2066 static void cliHelp(char *cmdline)
2068 uint32_t i = 0;
2070 UNUSED(cmdline);
2072 for (i = 0; i < CMD_COUNT; i++) {
2073 cliPrint(cmdTable[i].name);
2074 #ifndef SKIP_CLI_COMMAND_HELP
2075 if (cmdTable[i].description) {
2076 cliPrintf(" - %s", cmdTable[i].description);
2078 if (cmdTable[i].args) {
2079 cliPrintf("\r\n\t%s", cmdTable[i].args);
2081 #endif
2082 cliPrint("\r\n");
2086 static void cliMap(char *cmdline)
2088 uint32_t len;
2089 uint32_t i;
2090 char out[9];
2092 len = strlen(cmdline);
2094 if (len == 8) {
2095 // uppercase it
2096 for (i = 0; i < 8; i++)
2097 cmdline[i] = toupper((unsigned char)cmdline[i]);
2098 for (i = 0; i < 8; i++) {
2099 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2100 continue;
2101 cliShowParseError();
2102 return;
2104 parseRcChannels(cmdline, &masterConfig.rxConfig);
2106 cliPrint("Map: ");
2107 for (i = 0; i < 8; i++)
2108 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2109 out[i] = '\0';
2110 cliPrintf("%s\r\n", out);
2113 #ifndef USE_QUAD_MIXER_ONLY
2114 static void cliMixer(char *cmdline)
2116 int i;
2117 int len;
2119 len = strlen(cmdline);
2121 if (len == 0) {
2122 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2123 return;
2124 } else if (strncasecmp(cmdline, "list", len) == 0) {
2125 cliPrint("Available mixers: ");
2126 for (i = 0; ; i++) {
2127 if (mixerNames[i] == NULL)
2128 break;
2129 cliPrintf("%s ", mixerNames[i]);
2131 cliPrint("\r\n");
2132 return;
2135 for (i = 0; ; i++) {
2136 if (mixerNames[i] == NULL) {
2137 cliPrint("Invalid name\r\n");
2138 return;
2140 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2141 masterConfig.mixerMode = i + 1;
2142 break;
2146 cliMixer("");
2148 #endif
2150 static void cliMotor(char *cmdline)
2152 int motor_index = 0;
2153 int motor_value = 0;
2154 int index = 0;
2155 char *pch = NULL;
2156 char *saveptr;
2158 if (isEmpty(cmdline)) {
2159 cliShowParseError();
2160 return;
2163 pch = strtok_r(cmdline, " ", &saveptr);
2164 while (pch != NULL) {
2165 switch (index) {
2166 case 0:
2167 motor_index = atoi(pch);
2168 break;
2169 case 1:
2170 motor_value = atoi(pch);
2171 break;
2173 index++;
2174 pch = strtok_r(NULL, " ", &saveptr);
2177 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2178 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2179 return;
2182 if (index == 2) {
2183 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2184 cliShowArgumentRangeError("value", 1000, 2000);
2185 return;
2186 } else {
2187 motor_disarmed[motor_index] = motor_value;
2191 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2194 static void cliPlaySound(char *cmdline)
2196 #if FLASH_SIZE <= 64
2197 UNUSED(cmdline);
2198 #else
2199 int i;
2200 const char *name;
2201 static int lastSoundIdx = -1;
2203 if (isEmpty(cmdline)) {
2204 i = lastSoundIdx + 1; //next sound index
2205 if ((name=beeperNameForTableIndex(i)) == NULL) {
2206 while (true) { //no name for index; try next one
2207 if (++i >= beeperTableEntryCount())
2208 i = 0; //if end then wrap around to first entry
2209 if ((name=beeperNameForTableIndex(i)) != NULL)
2210 break; //if name OK then play sound below
2211 if (i == lastSoundIdx + 1) { //prevent infinite loop
2212 cliPrintf("Error playing sound\r\n");
2213 return;
2217 } else { //index value was given
2218 i = atoi(cmdline);
2219 if ((name=beeperNameForTableIndex(i)) == NULL) {
2220 cliPrintf("No sound for index %d\r\n", i);
2221 return;
2224 lastSoundIdx = i;
2225 beeperSilence();
2226 cliPrintf("Playing sound %d: %s\r\n", i, name);
2227 beeper(beeperModeForTableIndex(i));
2228 #endif
2231 static void cliProfile(char *cmdline)
2233 int i;
2235 if (isEmpty(cmdline)) {
2236 cliPrintf("profile %d\r\n", getCurrentProfile());
2237 return;
2238 } else {
2239 i = atoi(cmdline);
2240 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2241 masterConfig.current_profile_index = i;
2242 writeEEPROM();
2243 readEEPROM();
2244 cliProfile("");
2249 static void cliRateProfile(char *cmdline) {
2250 int i;
2252 if (isEmpty(cmdline)) {
2253 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2254 return;
2255 } else {
2256 i = atoi(cmdline);
2257 if (i >= 0 && i < MAX_RATEPROFILES) {
2258 changeControlRateProfile(i);
2259 cliRateProfile("");
2264 static void cliReboot(void) {
2265 cliPrint("\r\nRebooting");
2266 bufWriterFlush(cliWriter);
2267 waitForSerialPortToFinishTransmitting(cliPort);
2268 stopMotors();
2269 handleOneshotFeatureChangeOnRestart();
2270 systemReset();
2273 static void cliSave(char *cmdline)
2275 UNUSED(cmdline);
2277 cliPrint("Saving");
2278 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2279 writeEEPROM();
2280 cliReboot();
2283 static void cliDefaults(char *cmdline)
2285 UNUSED(cmdline);
2287 cliPrint("Resetting to defaults");
2288 resetEEPROM();
2289 cliReboot();
2292 static void cliPrint(const char *str)
2294 while (*str)
2295 bufWriterAppend(cliWriter, *str++);
2298 static void cliPutp(void *p, char ch)
2300 bufWriterAppend(p, ch);
2303 static void cliPrintf(const char *fmt, ...)
2305 va_list va;
2306 va_start(va, fmt);
2307 tfp_format(cliWriter, cliPutp, fmt, va);
2308 va_end(va);
2311 static void cliWrite(uint8_t ch)
2313 bufWriterAppend(cliWriter, ch);
2316 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2318 int32_t value = 0;
2319 char buf[8];
2321 void *ptr = var->ptr;
2322 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2323 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2326 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2327 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2330 switch (var->type & VALUE_TYPE_MASK) {
2331 case VAR_UINT8:
2332 value = *(uint8_t *)ptr;
2333 break;
2335 case VAR_INT8:
2336 value = *(int8_t *)ptr;
2337 break;
2339 case VAR_UINT16:
2340 value = *(uint16_t *)ptr;
2341 break;
2343 case VAR_INT16:
2344 value = *(int16_t *)ptr;
2345 break;
2347 case VAR_UINT32:
2348 value = *(uint32_t *)ptr;
2349 break;
2351 case VAR_FLOAT:
2352 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2353 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2354 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2355 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2357 return; // return from case for float only
2360 switch(var->type & VALUE_MODE_MASK) {
2361 case MODE_DIRECT:
2362 cliPrintf("%d", value);
2363 if (full) {
2364 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2366 break;
2367 case MODE_LOOKUP:
2368 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2369 break;
2373 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2375 void *ptr = var->ptr;
2376 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2377 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2379 if ((var->type & VALUE_SECTION_MASK) == PROFILE_RATE_VALUE) {
2380 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2383 switch (var->type & VALUE_TYPE_MASK) {
2384 case VAR_UINT8:
2385 case VAR_INT8:
2386 *(int8_t *)ptr = value.int_value;
2387 break;
2389 case VAR_UINT16:
2390 case VAR_INT16:
2391 *(int16_t *)ptr = value.int_value;
2392 break;
2394 case VAR_UINT32:
2395 *(uint32_t *)ptr = value.int_value;
2396 break;
2398 case VAR_FLOAT:
2399 *(float *)ptr = (float)value.float_value;
2400 break;
2404 static void cliSet(char *cmdline)
2406 uint32_t i;
2407 uint32_t len;
2408 const clivalue_t *val;
2409 char *eqptr = NULL;
2411 len = strlen(cmdline);
2413 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2414 cliPrint("Current settings: \r\n");
2415 for (i = 0; i < VALUE_COUNT; i++) {
2416 val = &valueTable[i];
2417 cliPrintf("%s = ", valueTable[i].name);
2418 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2419 cliPrint("\r\n");
2421 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2422 // has equals
2424 char *lastNonSpaceCharacter = eqptr;
2425 while (*(lastNonSpaceCharacter - 1) == ' ') {
2426 lastNonSpaceCharacter--;
2428 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2430 // skip the '=' and any ' ' characters
2431 eqptr++;
2432 while (*(eqptr) == ' ') {
2433 eqptr++;
2436 for (i = 0; i < VALUE_COUNT; i++) {
2437 val = &valueTable[i];
2438 // ensure exact match when setting to prevent setting variables with shorter names
2439 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2441 bool changeValue = false;
2442 int_float_value_t tmp;
2443 switch (valueTable[i].type & VALUE_MODE_MASK) {
2444 case MODE_DIRECT: {
2445 int32_t value = 0;
2446 float valuef = 0;
2448 value = atoi(eqptr);
2449 valuef = fastA2F(eqptr);
2451 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2453 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2454 tmp.float_value = valuef;
2455 else
2456 tmp.int_value = value;
2458 changeValue = true;
2461 break;
2462 case MODE_LOOKUP: {
2463 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2464 bool matched = false;
2465 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2466 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2468 if (matched) {
2469 tmp.int_value = tableValueIndex;
2470 changeValue = true;
2474 break;
2477 if (changeValue) {
2478 cliSetVar(val, tmp);
2480 cliPrintf("%s set to ", valueTable[i].name);
2481 cliPrintVar(val, 0);
2482 } else {
2483 cliPrint("Invalid value\r\n");
2486 return;
2489 cliPrint("Invalid name\r\n");
2490 } else {
2491 // no equals, check for matching variables.
2492 cliGet(cmdline);
2496 static void cliGet(char *cmdline)
2498 uint32_t i;
2499 const clivalue_t *val;
2500 int matchedCommands = 0;
2502 for (i = 0; i < VALUE_COUNT; i++) {
2503 if (strstr(valueTable[i].name, cmdline)) {
2504 val = &valueTable[i];
2505 cliPrintf("%s = ", valueTable[i].name);
2506 cliPrintVar(val, 0);
2507 cliPrint("\r\n");
2509 matchedCommands++;
2514 if (matchedCommands) {
2515 return;
2518 cliPrint("Invalid name\r\n");
2521 static void cliStatus(char *cmdline)
2523 UNUSED(cmdline);
2525 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2526 millis() / 1000,
2527 vbat,
2528 batteryCellCount,
2529 getBatteryStateString(),
2530 constrain(averageSystemLoadPercent, 0, 100)
2533 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2535 #ifndef CJMCU
2536 uint8_t i;
2537 uint32_t mask;
2538 uint32_t detectedSensorsMask = sensorsMask();
2540 for (i = 0; ; i++) {
2542 if (sensorTypeNames[i] == NULL)
2543 break;
2545 mask = (1 << i);
2546 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2547 const char *sensorHardware;
2548 uint8_t sensorHardwareIndex = detectedSensors[i];
2549 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2551 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2553 if (mask == SENSOR_ACC && acc.revisionCode) {
2554 cliPrintf(".%c", acc.revisionCode);
2558 #endif
2559 cliPrint("\r\n");
2561 #ifdef USE_I2C
2562 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2563 #else
2564 uint16_t i2cErrorCounter = 0;
2565 #endif
2567 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2570 #ifndef SKIP_TASK_STATISTICS
2571 static void cliTasks(char *cmdline)
2573 UNUSED(cmdline);
2575 cfTaskId_e taskId;
2576 cfTaskInfo_t taskInfo;
2578 cliPrintf("Task list:\r\n");
2579 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2580 getTaskInfo(taskId, &taskInfo);
2581 if (taskInfo.isEnabled) {
2582 uint16_t taskFrequency;
2583 uint16_t subTaskFrequency;
2585 uint32_t taskTotalTime = taskInfo.totalExecutionTime / 1000;
2587 if (taskId == TASK_GYROPID) {
2588 subTaskFrequency = (uint16_t)(1.0f / ((float)cycleTime * 0.000001f));
2589 if (masterConfig.pid_process_denom > 1) {
2590 taskFrequency = subTaskFrequency / masterConfig.pid_process_denom;
2591 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2592 } else {
2593 taskFrequency = subTaskFrequency;
2594 cliPrintf("%d - (%s/%s) ", taskId, taskInfo.subTaskName, taskInfo.taskName);
2596 } else {
2597 taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
2598 cliPrintf("%d - (%s) ", taskId, taskInfo.taskName);
2601 cliPrintf("max: %dus, avg: %dus, rate: %dhz, total: ", taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency);
2603 if (taskTotalTime >= 1000) {
2604 cliPrintf("%dsec", taskTotalTime / 1000);
2605 } else {
2606 cliPrintf("%dms", taskTotalTime);
2609 if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) cliPrintf("\r\n- - (%s) rate: %dhz", taskInfo.subTaskName, subTaskFrequency);
2610 cliPrintf("\r\n", taskTotalTime);
2614 #endif
2616 static void cliVersion(char *cmdline)
2618 UNUSED(cmdline);
2620 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
2621 targetName,
2622 FC_VERSION_STRING,
2623 buildDate,
2624 buildTime,
2625 shortGitRevision
2629 void cliProcess(void)
2631 if (!cliWriter) {
2632 return;
2635 // Be a little bit tricky. Flush the last inputs buffer, if any.
2636 bufWriterFlush(cliWriter);
2638 while (serialRxBytesWaiting(cliPort)) {
2639 uint8_t c = serialRead(cliPort);
2640 if (c == '\t' || c == '?') {
2641 // do tab completion
2642 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2643 uint32_t i = bufferIndex;
2644 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2645 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2646 continue;
2647 if (!pstart)
2648 pstart = cmd;
2649 pend = cmd;
2651 if (pstart) { /* Buffer matches one or more commands */
2652 for (; ; bufferIndex++) {
2653 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2654 break;
2655 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2656 /* Unambiguous -- append a space */
2657 cliBuffer[bufferIndex++] = ' ';
2658 cliBuffer[bufferIndex] = '\0';
2659 break;
2661 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2664 if (!bufferIndex || pstart != pend) {
2665 /* Print list of ambiguous matches */
2666 cliPrint("\r\033[K");
2667 for (cmd = pstart; cmd <= pend; cmd++) {
2668 cliPrint(cmd->name);
2669 cliWrite('\t');
2671 cliPrompt();
2672 i = 0; /* Redraw prompt */
2674 for (; i < bufferIndex; i++)
2675 cliWrite(cliBuffer[i]);
2676 } else if (!bufferIndex && c == 4) { // CTRL-D
2677 cliExit(cliBuffer);
2678 return;
2679 } else if (c == 12) { // NewPage / CTRL-L
2680 // clear screen
2681 cliPrint("\033[2J\033[1;1H");
2682 cliPrompt();
2683 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2684 // enter pressed
2685 cliPrint("\r\n");
2687 // Strip comment starting with # from line
2688 char *p = cliBuffer;
2689 p = strchr(p, '#');
2690 if (NULL != p) {
2691 bufferIndex = (uint32_t)(p - cliBuffer);
2694 // Strip trailing whitespace
2695 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2696 bufferIndex--;
2699 // Process non-empty lines
2700 if (bufferIndex > 0) {
2701 cliBuffer[bufferIndex] = 0; // null terminate
2703 const clicmd_t *cmd;
2704 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2705 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2706 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2707 break;
2709 if(cmd < cmdTable + CMD_COUNT)
2710 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2711 else
2712 cliPrint("Unknown command, try 'help'");
2713 bufferIndex = 0;
2716 memset(cliBuffer, 0, sizeof(cliBuffer));
2718 // 'exit' will reset this flag, so we don't need to print prompt again
2719 if (!cliMode)
2720 return;
2722 cliPrompt();
2723 } else if (c == 127) {
2724 // backspace
2725 if (bufferIndex) {
2726 cliBuffer[--bufferIndex] = 0;
2727 cliPrint("\010 \010");
2729 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2730 if (!bufferIndex && c == ' ')
2731 continue; // Ignore leading spaces
2732 cliBuffer[bufferIndex++] = c;
2733 cliWrite(c);
2738 void cliInit(serialConfig_t *serialConfig)
2740 UNUSED(serialConfig);
2742 #endif