Configurable max_aux_channel
[betaflight.git] / src / main / io / serial_cli.c
blobb3a0109d866f7c2d250e5e5eb43cf5cd3b6a6bd8
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"
50 #include "drivers/buf_writer.h"
52 #include "io/escservo.h"
53 #include "io/gps.h"
54 #include "io/gimbal.h"
55 #include "io/rc_controls.h"
56 #include "io/serial.h"
57 #include "io/ledstrip.h"
58 #include "io/flashfs.h"
59 #include "io/beeper.h"
60 #include "io/asyncfatfs/asyncfatfs.h"
62 #include "rx/rx.h"
63 #include "rx/spektrum.h"
65 #include "sensors/battery.h"
66 #include "sensors/boardalignment.h"
67 #include "sensors/sensors.h"
68 #include "sensors/acceleration.h"
69 #include "sensors/gyro.h"
70 #include "sensors/compass.h"
71 #include "sensors/barometer.h"
73 #include "flight/pid.h"
74 #include "flight/imu.h"
75 #include "flight/mixer.h"
76 #include "flight/navigation.h"
77 #include "flight/failsafe.h"
79 #include "telemetry/telemetry.h"
80 #include "telemetry/frsky.h"
82 #include "config/runtime_config.h"
83 #include "config/config.h"
84 #include "config/config_profile.h"
85 #include "config/config_master.h"
87 #include "common/printf.h"
89 #include "serial_cli.h"
91 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
92 // signal that we're in cli mode
93 uint8_t cliMode = 0;
95 #ifdef USE_CLI
97 extern uint16_t cycleTime; // FIXME dependency on mw.c
99 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
101 static serialPort_t *cliPort;
102 static bufWriter_t *cliWriter;
103 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
105 static void cliAux(char *cmdline);
106 static void cliRxFail(char *cmdline);
107 static void cliAdjustmentRange(char *cmdline);
108 static void cliMotorMix(char *cmdline);
109 static void cliDefaults(char *cmdline);
110 static void cliDump(char *cmdLine);
111 static void cliExit(char *cmdline);
112 static void cliFeature(char *cmdline);
113 static void cliMotor(char *cmdline);
114 static void cliPlaySound(char *cmdline);
115 static void cliProfile(char *cmdline);
116 static void cliReboot(void);
117 static void cliSave(char *cmdline);
118 static void cliSerial(char *cmdline);
120 #ifdef USE_SERVOS
121 static void cliServo(char *cmdline);
122 static void cliServoMix(char *cmdline);
123 #endif
125 static void cliSet(char *cmdline);
126 static void cliGet(char *cmdline);
127 static void cliStatus(char *cmdline);
128 #ifndef SKIP_TASK_STATISTICS
129 static void cliTasks(char *cmdline);
130 #endif
131 static void cliVersion(char *cmdline);
132 static void cliRxRange(char *cmdline);
134 #ifdef GPS
135 static void cliGpsPassthrough(char *cmdline);
136 #endif
138 static void cliHelp(char *cmdline);
139 static void cliMap(char *cmdline);
141 #ifdef LED_STRIP
142 static void cliLed(char *cmdline);
143 static void cliColor(char *cmdline);
144 #endif
146 #ifndef USE_QUAD_MIXER_ONLY
147 static void cliMixer(char *cmdline);
148 #endif
150 #ifdef USE_FLASHFS
151 static void cliFlashInfo(char *cmdline);
152 static void cliFlashErase(char *cmdline);
153 #ifdef USE_FLASH_TOOLS
154 static void cliFlashWrite(char *cmdline);
155 static void cliFlashRead(char *cmdline);
156 #endif
157 #endif
159 #ifdef USE_SDCARD
160 static void cliSdInfo(char *cmdline);
161 #endif
163 // buffer
164 static char cliBuffer[48];
165 static uint32_t bufferIndex = 0;
167 #ifndef USE_QUAD_MIXER_ONLY
168 // sync this with mixerMode_e
169 static const char * const mixerNames[] = {
170 "TRI", "QUADP", "QUADX", "BI",
171 "GIMBAL", "Y6", "HEX6",
172 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
173 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
174 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
175 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
177 #endif
179 // sync this with features_e
180 static const char * const featureNames[] = {
181 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
182 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
183 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
184 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
185 "BLACKBOX", "CHANNEL_FORWARDING", NULL
188 // sync this with rxFailsafeChannelMode_e
189 static const char rxFailsafeModeCharacters[] = "ahs";
191 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
192 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
193 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
196 #ifndef CJMCU
197 // sync this with sensors_e
198 static const char * const sensorTypeNames[] = {
199 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
202 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
204 static const char * const sensorHardwareNames[4][11] = {
205 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
206 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
207 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
208 { "", "None", "HMC5883", "AK8975", "AK8963", NULL }
210 #endif
212 typedef struct {
213 const char *name;
214 #ifndef SKIP_CLI_COMMAND_HELP
215 const char *description;
216 const char *args;
217 #endif
218 void (*func)(char *cmdline);
219 } clicmd_t;
221 #ifndef SKIP_CLI_COMMAND_HELP
222 #define CLI_COMMAND_DEF(name, description, args, method) \
224 name , \
225 description , \
226 args , \
227 method \
229 #else
230 #define CLI_COMMAND_DEF(name, description, args, method) \
232 name, \
233 method \
235 #endif
237 // should be sorted a..z for bsearch()
238 const clicmd_t cmdTable[] = {
239 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
240 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
241 #ifdef LED_STRIP
242 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
243 #endif
244 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
245 CLI_COMMAND_DEF("dump", "dump configuration",
246 "[master|profile]", cliDump),
247 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
248 CLI_COMMAND_DEF("feature", "configure features",
249 "list\r\n"
250 "\t<+|->[name]", cliFeature),
251 #ifdef USE_FLASHFS
252 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
253 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
254 #ifdef USE_FLASH_TOOLS
255 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
256 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
257 #endif
258 #endif
259 CLI_COMMAND_DEF("get", "get variable value",
260 "[name]", cliGet),
261 #ifdef GPS
262 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
263 #endif
264 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
265 #ifdef LED_STRIP
266 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
267 #endif
268 CLI_COMMAND_DEF("map", "configure rc channel order",
269 "[<map>]", cliMap),
270 #ifndef USE_QUAD_MIXER_ONLY
271 CLI_COMMAND_DEF("mixer", "configure mixer",
272 "list\r\n"
273 "\t<name>", cliMixer),
274 #endif
275 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
276 CLI_COMMAND_DEF("motor", "get/set motor",
277 "<index> [<value>]", cliMotor),
278 CLI_COMMAND_DEF("play_sound", NULL,
279 "[<index>]\r\n", cliPlaySound),
280 CLI_COMMAND_DEF("profile", "change profile",
281 "[<index>]", cliProfile),
282 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
283 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
284 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
285 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
286 #ifdef USE_SERVOS
287 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
288 #endif
289 CLI_COMMAND_DEF("set", "change setting",
290 "[<name>=<value>]", cliSet),
291 #ifdef USE_SERVOS
292 CLI_COMMAND_DEF("smix", "servo mixer",
293 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
294 "\treset\r\n"
295 "\tload <mixer>\r\n"
296 "\treverse <servo> <source> r|n", cliServoMix),
297 #endif
298 #ifdef USE_SDCARD
299 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL, cliSdInfo),
300 #endif
301 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
302 #ifndef SKIP_TASK_STATISTICS
303 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
304 #endif
305 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
307 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
309 static const char * const lookupTableOffOn[] = {
310 "OFF", "ON"
313 static const char * const lookupTableUnit[] = {
314 "IMPERIAL", "METRIC"
317 static const char * const lookupTableAlignment[] = {
318 "DEFAULT",
319 "CW0",
320 "CW90",
321 "CW180",
322 "CW270",
323 "CW0FLIP",
324 "CW90FLIP",
325 "CW180FLIP",
326 "CW270FLIP"
329 #ifdef GPS
330 static const char * const lookupTableGPSProvider[] = {
331 "NMEA", "UBLOX"
334 static const char * const lookupTableGPSSBASMode[] = {
335 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
337 #endif
339 static const char * const lookupTableCurrentSensor[] = {
340 "NONE", "ADC", "VIRTUAL"
343 static const char * const lookupTableGimbalMode[] = {
344 "NORMAL", "MIXTILT"
347 static const char * const lookupTableBlackboxDevice[] = {
348 "SERIAL", "SPIFLASH", "SDCARD"
352 static const char * const lookupTablePidController[] = {
353 "MW23", "MWREWRITE", "LUX"
356 static const char * const lookupTableSerialRX[] = {
357 "SPEK1024",
358 "SPEK2048",
359 "SBUS",
360 "SUMD",
361 "SUMH",
362 "XB-B",
363 "XB-B-RJ01",
364 "IBUS",
365 "JETIEXBUS"
368 static const char * const lookupTableGyroLpf[] = {
369 "OFF",
370 "188HZ",
371 "98HZ",
372 "42HZ"
375 static const char * const lookupTableAccHardware[] = {
376 "AUTO",
377 "NONE",
378 "ADXL345",
379 "MPU6050",
380 "MMA8452",
381 "BMA280",
382 "LSM303DLHC",
383 "MPU6000",
384 "MPU6500",
385 "FAKE"
388 static const char * const lookupTableBaroHardware[] = {
389 "AUTO",
390 "NONE",
391 "BMP085",
392 "MS5611",
393 "BMP280"
396 static const char * const lookupTableMagHardware[] = {
397 "AUTO",
398 "NONE",
399 "HMC5883",
400 "AK8975",
401 "AK8963"
404 static const char * const lookupDeltaMethod[] = {
405 "ERROR", "MEASUREMENT"
408 typedef struct lookupTableEntry_s {
409 const char * const *values;
410 const uint8_t valueCount;
411 } lookupTableEntry_t;
413 typedef enum {
414 TABLE_OFF_ON = 0,
415 TABLE_UNIT,
416 TABLE_ALIGNMENT,
417 #ifdef GPS
418 TABLE_GPS_PROVIDER,
419 TABLE_GPS_SBAS_MODE,
420 #endif
421 #ifdef BLACKBOX
422 TABLE_BLACKBOX_DEVICE,
423 #endif
424 TABLE_CURRENT_SENSOR,
425 TABLE_GIMBAL_MODE,
426 TABLE_PID_CONTROLLER,
427 TABLE_SERIAL_RX,
428 TABLE_GYRO_LPF,
429 TABLE_ACC_HARDWARE,
430 TABLE_BARO_HARDWARE,
431 TABLE_MAG_HARDWARE,
432 TABLE_DELTA_METHOD,
433 } lookupTableIndex_e;
435 static const lookupTableEntry_t lookupTables[] = {
436 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
437 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
438 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
439 #ifdef GPS
440 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
441 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
442 #endif
443 #ifdef BLACKBOX
444 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
445 #endif
446 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
447 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
448 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
449 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
450 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
451 { lookupTableAccHardware, sizeof(lookupTableAccHardware) / sizeof(char *) },
452 { lookupTableBaroHardware, sizeof(lookupTableBaroHardware) / sizeof(char *) },
453 { lookupTableMagHardware, sizeof(lookupTableMagHardware) / sizeof(char *) },
454 { lookupDeltaMethod, sizeof(lookupDeltaMethod) / sizeof(char *) }
457 #define VALUE_TYPE_OFFSET 0
458 #define VALUE_SECTION_OFFSET 4
459 #define VALUE_MODE_OFFSET 6
461 typedef enum {
462 // value type
463 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
464 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
465 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
466 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
467 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
468 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
470 // value section
471 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
472 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
474 // value mode
475 MODE_DIRECT = (0 << VALUE_MODE_OFFSET),
476 MODE_LOOKUP = (1 << VALUE_MODE_OFFSET)
477 } cliValueFlag_e;
479 #define VALUE_TYPE_MASK (0x0F)
480 #define VALUE_SECTION_MASK (0x30)
481 #define VALUE_MODE_MASK (0xC0)
483 typedef struct cliMinMaxConfig_s {
484 const int32_t min;
485 const int32_t max;
486 } cliMinMaxConfig_t;
488 typedef struct cliLookupTableConfig_s {
489 const lookupTableIndex_e tableIndex;
490 } cliLookupTableConfig_t;
492 typedef union {
493 cliLookupTableConfig_t lookup;
494 cliMinMaxConfig_t minmax;
496 } cliValueConfig_t;
498 typedef struct {
499 const char *name;
500 const uint8_t type; // see cliValueFlag_e
501 void *ptr;
502 const cliValueConfig_t config;
503 } clivalue_t;
505 const clivalue_t valueTable[] = {
506 { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON } },
508 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 } },
509 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
510 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
511 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT } },
512 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX } },
513 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } },
514 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } },
515 { "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_OFF_ON } },
516 { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.fpvCamAngleDegrees, .config.minmax = { 0, 50 } },
517 { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.max_aux_channel, .config.minmax = { 0, 13 } },
519 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
520 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
521 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
522 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
524 { "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
525 { "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,
526 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
527 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } },
529 { "enable_fast_pwm", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_fast_pwm, .config.lookup = { TABLE_OFF_ON } },
530 #ifdef CC3D
531 { "enable_buzzer_p6", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.use_buzzer_p6, .config.lookup = { TABLE_OFF_ON } },
532 #endif
533 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 } },
534 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 } },
536 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON } },
537 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 } },
538 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 } },
540 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, .config.minmax = { -1, 1 } },
542 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 } },
544 #ifdef GPS
545 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER } },
546 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE } },
547 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON } },
548 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON } },
550 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 200 } },
551 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 200 } },
552 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 200 } },
553 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 200 } },
554 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 200 } },
555 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 200 } },
556 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 200 } },
557 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 200 } },
558 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 200 } },
559 { "gps_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.gps_wp_radius, .config.minmax = { 0, 2000 } },
560 { "nav_controls_heading", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsProfile.nav_controls_heading, .config.lookup = { TABLE_OFF_ON } },
561 { "nav_speed_min", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_min, .config.minmax = { 10, 2000 } },
562 { "nav_speed_max", VAR_UINT16 | MASTER_VALUE, &masterConfig.gpsProfile.nav_speed_max, .config.minmax = { 10, 2000 } },
563 { "nav_slew_rate", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsProfile.nav_slew_rate, .config.minmax = { 0, 100 } },
564 #endif
565 #ifdef GTUNE
566 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], .config.minmax = { 10, 200 } },
567 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], .config.minmax = { 10, 200 } },
568 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], .config.minmax = { 10, 200 } },
569 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], .config.minmax = { 0, 200 } },
570 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], .config.minmax = { 0, 200 } },
571 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], .config.minmax = { 0, 200 } },
572 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, .config.minmax = { 0, 10 } },
573 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, .config.minmax = { 200, 1000 } },
574 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, .config.minmax = { 8, 128 } },
575 #endif
577 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX } },
578 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX} },
580 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON } },
581 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON } },
582 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 } },
583 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 } },
584 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA } },
585 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT } },
586 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH } },
587 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 } },
589 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 } },
590 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX } },
591 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 } },
592 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 } },
593 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 } },
594 { "vbat_pid_compensation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.vbatPidCompensation, .config.lookup = { TABLE_OFF_ON } },
595 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 } },
596 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 } },
597 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON } },
598 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR } },
600 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT } },
601 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT } },
602 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT } },
604 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, .config.minmax = { -180, 360 } },
605 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, .config.minmax = { -180, 360 } },
606 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, .config.minmax = { -180, 360 } },
608 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } },
610 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
611 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyro_sync_denom, .config.minmax = { 1, 8 } },
612 { "gyro_soft_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.gyro_soft_lpf_hz, .config.minmax = { 0, 500 } },
613 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 } },
614 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp, .config.minmax = { 0, 50000 } },
615 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki, .config.minmax = { 0, 50000 } },
617 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.alt_hold_deadband, .config.minmax = { 1, 250 } },
618 { "alt_hold_fast_change", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rcControlsConfig.alt_hold_fast_change, .config.lookup = { TABLE_OFF_ON } },
619 { "deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.deadband, .config.minmax = { 0, 32 } },
620 { "yaw_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 } },
622 { "throttle_correction_value", VAR_UINT8 | MASTER_VALUE, &masterConfig.throttle_correction_value, .config.minmax = { 0, 150 } },
623 { "throttle_correction_angle", VAR_UINT16 | MASTER_VALUE, &masterConfig.throttle_correction_angle, .config.minmax = { 1, 900 } },
625 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 } },
627 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 } },
628 { "airmode_saturation_limit", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.airmode_saturation_limit, .config.minmax = { 0, 100 } },
629 { "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 } },
630 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } },
631 #ifdef USE_SERVOS
632 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } },
633 { "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400} },
634 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON } },
635 #endif
637 { "rc_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcRate8, .config.minmax = { 0, 250 } },
638 { "rc_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcExpo8, .config.minmax = { 0, 100 } },
639 { "rc_yaw_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rcYawExpo8, .config.minmax = { 0, 100 } },
640 { "thr_mid", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrMid8, .config.minmax = { 0, 100 } },
641 { "thr_expo", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.thrExpo8, .config.minmax = { 0, 100 } },
642 { "roll_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
643 { "pitch_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX } },
644 { "yaw_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX } },
645 { "tpa_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX} },
646 { "tpa_breakpoint", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].controlRateProfile.tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX} },
648 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 } },
649 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 } },
650 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX } },
651 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON } },
652 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 } },
653 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_OFF_ON } },
655 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
656 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX } },
658 #ifdef USE_SERVOS
659 { "gimbal_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE } },
660 #endif
662 { "acc_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_hardware, .config.lookup = { TABLE_ACC_HARDWARE } },
663 { "acc_lpf_hz", VAR_FLOAT | MASTER_VALUE, &masterConfig.acc_lpf_hz, .config.minmax = { 0, 400 } },
664 { "accxy_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.xy, .config.minmax = { 0, 100 } },
665 { "accz_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.accDeadband.z, .config.minmax = { 0, 100 } },
666 { "acc_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.acc_unarmedcal, .config.lookup = { TABLE_OFF_ON } },
667 { "acc_trim_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.pitch, .config.minmax = { -300, 300 } },
668 { "acc_trim_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.accelerometerTrims.values.roll, .config.minmax = { -300, 300 } },
670 { "baro_tab_size", VAR_UINT8 | MASTER_VALUE, &masterConfig.barometerConfig.baro_sample_count, .config.minmax = { 0, BARO_SAMPLE_COUNT_MAX } },
671 { "baro_noise_lpf", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_noise_lpf, .config.minmax = { 0 , 1 } },
672 { "baro_cf_vel", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_vel, .config.minmax = { 0 , 1 } },
673 { "baro_cf_alt", VAR_FLOAT | MASTER_VALUE, &masterConfig.barometerConfig.baro_cf_alt, .config.minmax = { 0 , 1 } },
674 { "baro_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.baro_hardware, .config.lookup = { TABLE_BARO_HARDWARE } },
676 { "mag_hardware", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mag_hardware, .config.lookup = { TABLE_MAG_HARDWARE } },
677 { "mag_declination", VAR_INT16 | MASTER_VALUE, &masterConfig.mag_declination, .config.minmax = { -18000, 18000 } },
678 { "pid_delta_method", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.deltaMethod, .config.lookup = { TABLE_DELTA_METHOD } },
679 { "dterm_lpf_hz", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 500 } },
680 { "dterm_average_count", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_average_count, .config.minmax = {2, 10 } },
682 { "pid_controller", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].pidProfile.pidController, .config.lookup = { TABLE_PID_CONTROLLER } },
684 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } },
685 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } },
686 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 } },
687 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 } },
688 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 } },
689 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 } },
690 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 } },
691 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 } },
692 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 } },
694 { "p_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[PITCH], .config.minmax = { 0, 100 } },
695 { "i_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[PITCH], .config.minmax = { 0, 100 } },
696 { "d_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[PITCH], .config.minmax = { 0, 100 } },
697 { "p_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[ROLL], .config.minmax = { 0, 100 } },
698 { "i_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[ROLL], .config.minmax = { 0, 100 } },
699 { "d_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[ROLL], .config.minmax = { 0, 100 } },
700 { "p_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[YAW], .config.minmax = { 0, 100 } },
701 { "i_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[YAW], .config.minmax = { 0, 100 } },
702 { "d_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[YAW], .config.minmax = { 0, 100 } },
704 { "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, .config.minmax = { 0, 10 } },
705 { "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, .config.minmax = { 0, 10 } },
706 { "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, .config.minmax = { 0, 250 } },
708 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 200 } },
709 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 200 } },
710 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 200 } },
712 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 200 } },
713 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 200 } },
714 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 200 } },
716 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 200 } },
717 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 200 } },
718 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 200 } },
720 { "acro_plus_factor", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.airModeInsaneAcrobilityFactor, .config.minmax = {0, 100 } },
722 #ifdef BLACKBOX
723 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 } },
724 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 } },
725 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE } },
726 #endif
728 { "beeper_off_flags", VAR_UINT32 | MASTER_VALUE, &masterConfig.beeper_off.flags, .config.minmax = {BEEPER_OFF_FLAGS_MIN, BEEPER_OFF_FLAGS_MAX }},
730 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 } },
731 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 } },
732 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 } },
735 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
738 typedef union {
739 int32_t int_value;
740 float float_value;
741 } int_float_value_t;
743 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
744 static void cliPrintVar(const clivalue_t *var, uint32_t full);
745 static void cliPrint(const char *str);
746 static void cliPrintf(const char *fmt, ...);
747 static void cliWrite(uint8_t ch);
749 static void cliPrompt(void)
751 cliPrint("\r\n# ");
752 bufWriterFlush(cliWriter);
755 static void cliShowParseError(void)
757 cliPrint("Parse error\r\n");
760 static void cliShowArgumentRangeError(char *name, int min, int max)
762 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
765 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
767 int val;
769 for (int argIndex = 0; argIndex < 2; argIndex++) {
770 ptr = strchr(ptr, ' ');
771 if (ptr) {
772 val = atoi(++ptr);
773 val = CHANNEL_VALUE_TO_STEP(val);
774 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
775 if (argIndex == 0) {
776 range->startStep = val;
777 } else {
778 range->endStep = val;
780 (*validArgumentCount)++;
785 return ptr;
788 // Check if a string's length is zero
789 static bool isEmpty(const char *string)
791 return *string == '\0';
794 static void cliRxFail(char *cmdline)
796 uint8_t channel;
797 char buf[3];
799 if (isEmpty(cmdline)) {
800 // print out rxConfig failsafe settings
801 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
802 cliRxFail(itoa(channel, buf, 10));
804 } else {
805 char *ptr = cmdline;
806 channel = atoi(ptr++);
807 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
809 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
811 uint16_t value;
812 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
813 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
814 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
816 ptr = strchr(ptr, ' ');
817 if (ptr) {
818 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
819 if (p) {
820 uint8_t requestedMode = p - rxFailsafeModeCharacters;
821 mode = rxFailsafeModesTable[type][requestedMode];
822 } else {
823 mode = RX_FAILSAFE_MODE_INVALID;
825 if (mode == RX_FAILSAFE_MODE_INVALID) {
826 cliShowParseError();
827 return;
830 requireValue = mode == RX_FAILSAFE_MODE_SET;
832 ptr = strchr(ptr, ' ');
833 if (ptr) {
834 if (!requireValue) {
835 cliShowParseError();
836 return;
838 value = atoi(++ptr);
839 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
840 if (value > MAX_RXFAIL_RANGE_STEP) {
841 cliPrint("Value out of range\r\n");
842 return;
845 channelFailsafeConfiguration->step = value;
846 } else if (requireValue) {
847 cliShowParseError();
848 return;
850 channelFailsafeConfiguration->mode = mode;
854 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
856 // triple use of cliPrintf below
857 // 1. acknowledge interpretation on command,
858 // 2. query current setting on single item,
859 // 3. recursive use for full list.
861 if (requireValue) {
862 cliPrintf("rxfail %u %c %d\r\n",
863 channel,
864 modeCharacter,
865 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
867 } else {
868 cliPrintf("rxfail %u %c\r\n",
869 channel,
870 modeCharacter
873 } else {
874 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
879 static void cliAux(char *cmdline)
881 int i, val = 0;
882 char *ptr;
884 if (isEmpty(cmdline)) {
885 // print out aux channel settings
886 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
887 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
888 cliPrintf("aux %u %u %u %u %u\r\n",
890 mac->modeId,
891 mac->auxChannelIndex,
892 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
893 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
896 } else {
897 ptr = cmdline;
898 i = atoi(ptr++);
899 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
900 modeActivationCondition_t *mac = &masterConfig.modeActivationConditions[i];
901 uint8_t validArgumentCount = 0;
902 ptr = strchr(ptr, ' ');
903 if (ptr) {
904 val = atoi(++ptr);
905 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
906 mac->modeId = val;
907 validArgumentCount++;
910 ptr = strchr(ptr, ' ');
911 if (ptr) {
912 val = atoi(++ptr);
913 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
914 mac->auxChannelIndex = val;
915 validArgumentCount++;
918 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
920 if (validArgumentCount != 4) {
921 memset(mac, 0, sizeof(modeActivationCondition_t));
923 } else {
924 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
929 static void cliSerial(char *cmdline)
931 int i, val;
932 char *ptr;
934 if (isEmpty(cmdline)) {
935 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
936 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
937 continue;
939 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
940 masterConfig.serialConfig.portConfigs[i].identifier,
941 masterConfig.serialConfig.portConfigs[i].functionMask,
942 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
943 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
944 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
945 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
948 return;
951 serialPortConfig_t portConfig;
952 memset(&portConfig, 0 , sizeof(portConfig));
954 serialPortConfig_t *currentConfig;
956 uint8_t validArgumentCount = 0;
958 ptr = cmdline;
960 val = atoi(ptr++);
961 currentConfig = serialFindPortConfiguration(val);
962 if (currentConfig) {
963 portConfig.identifier = val;
964 validArgumentCount++;
967 ptr = strchr(ptr, ' ');
968 if (ptr) {
969 val = atoi(++ptr);
970 portConfig.functionMask = val & 0xFFFF;
971 validArgumentCount++;
974 for (i = 0; i < 4; i ++) {
975 ptr = strchr(ptr, ' ');
976 if (!ptr) {
977 break;
980 val = atoi(++ptr);
982 uint8_t baudRateIndex = lookupBaudRateIndex(val);
983 if (baudRates[baudRateIndex] != (uint32_t) val) {
984 break;
987 switch(i) {
988 case 0:
989 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
990 continue;
992 portConfig.msp_baudrateIndex = baudRateIndex;
993 break;
994 case 1:
995 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
996 continue;
998 portConfig.gps_baudrateIndex = baudRateIndex;
999 break;
1000 case 2:
1001 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1002 continue;
1004 portConfig.telemetry_baudrateIndex = baudRateIndex;
1005 break;
1006 case 3:
1007 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1008 continue;
1010 portConfig.blackbox_baudrateIndex = baudRateIndex;
1011 break;
1014 validArgumentCount++;
1017 if (validArgumentCount < 6) {
1018 cliShowParseError();
1019 return;
1022 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1026 static void cliAdjustmentRange(char *cmdline)
1028 int i, val = 0;
1029 char *ptr;
1031 if (isEmpty(cmdline)) {
1032 // print out adjustment ranges channel settings
1033 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1034 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1035 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1037 ar->adjustmentIndex,
1038 ar->auxChannelIndex,
1039 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1040 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1041 ar->adjustmentFunction,
1042 ar->auxSwitchChannelIndex
1045 } else {
1046 ptr = cmdline;
1047 i = atoi(ptr++);
1048 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1049 adjustmentRange_t *ar = &masterConfig.adjustmentRanges[i];
1050 uint8_t validArgumentCount = 0;
1052 ptr = strchr(ptr, ' ');
1053 if (ptr) {
1054 val = atoi(++ptr);
1055 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1056 ar->adjustmentIndex = val;
1057 validArgumentCount++;
1060 ptr = strchr(ptr, ' ');
1061 if (ptr) {
1062 val = atoi(++ptr);
1063 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1064 ar->auxChannelIndex = val;
1065 validArgumentCount++;
1069 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1071 ptr = strchr(ptr, ' ');
1072 if (ptr) {
1073 val = atoi(++ptr);
1074 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1075 ar->adjustmentFunction = val;
1076 validArgumentCount++;
1079 ptr = strchr(ptr, ' ');
1080 if (ptr) {
1081 val = atoi(++ptr);
1082 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1083 ar->auxSwitchChannelIndex = val;
1084 validArgumentCount++;
1088 if (validArgumentCount != 6) {
1089 memset(ar, 0, sizeof(adjustmentRange_t));
1090 cliShowParseError();
1092 } else {
1093 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1098 static void cliMotorMix(char *cmdline)
1100 #ifdef USE_QUAD_MIXER_ONLY
1101 UNUSED(cmdline);
1102 #else
1103 int i, check = 0;
1104 int num_motors = 0;
1105 uint8_t len;
1106 char buf[16];
1107 char *ptr;
1109 if (isEmpty(cmdline)) {
1110 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1111 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1112 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1113 break;
1114 num_motors++;
1115 cliPrintf("#%d:\t", i);
1116 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
1117 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
1118 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
1119 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
1121 return;
1122 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1123 // erase custom mixer
1124 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1125 masterConfig.customMotorMixer[i].throttle = 0.0f;
1126 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1127 ptr = strchr(cmdline, ' ');
1128 if (ptr) {
1129 len = strlen(++ptr);
1130 for (i = 0; ; i++) {
1131 if (mixerNames[i] == NULL) {
1132 cliPrint("Invalid name\r\n");
1133 break;
1135 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1136 mixerLoadMix(i, masterConfig.customMotorMixer);
1137 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1138 cliMotorMix("");
1139 break;
1143 } else {
1144 ptr = cmdline;
1145 i = atoi(ptr); // get motor number
1146 if (i < MAX_SUPPORTED_MOTORS) {
1147 ptr = strchr(ptr, ' ');
1148 if (ptr) {
1149 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1150 check++;
1152 ptr = strchr(ptr, ' ');
1153 if (ptr) {
1154 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1155 check++;
1157 ptr = strchr(ptr, ' ');
1158 if (ptr) {
1159 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1160 check++;
1162 ptr = strchr(ptr, ' ');
1163 if (ptr) {
1164 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1165 check++;
1167 if (check != 4) {
1168 cliShowParseError();
1169 } else {
1170 cliMotorMix("");
1172 } else {
1173 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1176 #endif
1179 static void cliRxRange(char *cmdline)
1181 int i, validArgumentCount = 0;
1182 char *ptr;
1184 if (isEmpty(cmdline)) {
1185 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1186 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1187 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1189 } else if (strcasecmp(cmdline, "reset") == 0) {
1190 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1191 } else {
1192 ptr = cmdline;
1193 i = atoi(ptr);
1194 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1195 int rangeMin, rangeMax;
1197 ptr = strchr(ptr, ' ');
1198 if (ptr) {
1199 rangeMin = atoi(++ptr);
1200 validArgumentCount++;
1203 ptr = strchr(ptr, ' ');
1204 if (ptr) {
1205 rangeMax = atoi(++ptr);
1206 validArgumentCount++;
1209 if (validArgumentCount != 2) {
1210 cliShowParseError();
1211 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1212 cliShowParseError();
1213 } else {
1214 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1215 channelRangeConfiguration->min = rangeMin;
1216 channelRangeConfiguration->max = rangeMax;
1218 } else {
1219 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1224 #ifdef LED_STRIP
1225 static void cliLed(char *cmdline)
1227 int i;
1228 char *ptr;
1229 char ledConfigBuffer[20];
1231 if (isEmpty(cmdline)) {
1232 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1233 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1234 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1236 } else {
1237 ptr = cmdline;
1238 i = atoi(ptr);
1239 if (i < MAX_LED_STRIP_LENGTH) {
1240 ptr = strchr(cmdline, ' ');
1241 if (!parseLedStripConfig(i, ++ptr)) {
1242 cliShowParseError();
1244 } else {
1245 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1250 static void cliColor(char *cmdline)
1252 int i;
1253 char *ptr;
1255 if (isEmpty(cmdline)) {
1256 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1257 cliPrintf("color %u %d,%u,%u\r\n",
1259 masterConfig.colors[i].h,
1260 masterConfig.colors[i].s,
1261 masterConfig.colors[i].v
1264 } else {
1265 ptr = cmdline;
1266 i = atoi(ptr);
1267 if (i < CONFIGURABLE_COLOR_COUNT) {
1268 ptr = strchr(cmdline, ' ');
1269 if (!parseColor(i, ++ptr)) {
1270 cliShowParseError();
1272 } else {
1273 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1277 #endif
1279 #ifdef USE_SERVOS
1280 static void cliServo(char *cmdline)
1282 enum { SERVO_ARGUMENT_COUNT = 8 };
1283 int16_t arguments[SERVO_ARGUMENT_COUNT];
1285 servoParam_t *servo;
1287 int i;
1288 char *ptr;
1290 if (isEmpty(cmdline)) {
1291 // print out servo settings
1292 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1293 servo = &masterConfig.servoConf[i];
1295 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1297 servo->min,
1298 servo->max,
1299 servo->middle,
1300 servo->angleAtMin,
1301 servo->angleAtMax,
1302 servo->rate,
1303 servo->forwardFromChannel
1306 } else {
1307 int validArgumentCount = 0;
1309 ptr = cmdline;
1311 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1313 // If command line doesn't fit the format, don't modify the config
1314 while (*ptr) {
1315 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1316 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1317 cliShowParseError();
1318 return;
1321 arguments[validArgumentCount++] = atoi(ptr);
1323 do {
1324 ptr++;
1325 } while (*ptr >= '0' && *ptr <= '9');
1326 } else if (*ptr == ' ') {
1327 ptr++;
1328 } else {
1329 cliShowParseError();
1330 return;
1334 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1336 i = arguments[INDEX];
1338 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1339 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1340 cliShowParseError();
1341 return;
1344 servo = &masterConfig.servoConf[i];
1346 if (
1347 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1348 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1349 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1350 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1351 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1352 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1353 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1354 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1356 cliShowParseError();
1357 return;
1360 servo->min = arguments[1];
1361 servo->max = arguments[2];
1362 servo->middle = arguments[3];
1363 servo->angleAtMin = arguments[4];
1364 servo->angleAtMax = arguments[5];
1365 servo->rate = arguments[6];
1366 servo->forwardFromChannel = arguments[7];
1369 #endif
1371 #ifdef USE_SERVOS
1372 static void cliServoMix(char *cmdline)
1374 int i;
1375 uint8_t len;
1376 char *ptr;
1377 int args[8], check = 0;
1378 len = strlen(cmdline);
1380 if (len == 0) {
1382 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1384 for (i = 0; i < MAX_SERVO_RULES; i++) {
1385 if (masterConfig.customServoMixer[i].rate == 0)
1386 break;
1388 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1390 masterConfig.customServoMixer[i].targetChannel,
1391 masterConfig.customServoMixer[i].inputSource,
1392 masterConfig.customServoMixer[i].rate,
1393 masterConfig.customServoMixer[i].speed,
1394 masterConfig.customServoMixer[i].min,
1395 masterConfig.customServoMixer[i].max,
1396 masterConfig.customServoMixer[i].box
1399 cliPrintf("\r\n");
1400 return;
1401 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1402 // erase custom mixer
1403 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1404 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1405 masterConfig.servoConf[i].reversedSources = 0;
1407 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1408 ptr = strchr(cmdline, ' ');
1409 if (ptr) {
1410 len = strlen(++ptr);
1411 for (i = 0; ; i++) {
1412 if (mixerNames[i] == NULL) {
1413 cliPrintf("Invalid name\r\n");
1414 break;
1416 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1417 servoMixerLoadMix(i, masterConfig.customServoMixer);
1418 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1419 cliServoMix("");
1420 break;
1424 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1425 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1426 int servoIndex, inputSource;
1427 ptr = strchr(cmdline, ' ');
1429 len = strlen(ptr);
1430 if (len == 0) {
1431 cliPrintf("s");
1432 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1433 cliPrintf("\ti%d", inputSource);
1434 cliPrintf("\r\n");
1436 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1437 cliPrintf("%d", servoIndex);
1438 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1439 cliPrintf("\t%s ", (masterConfig.servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1440 cliPrintf("\r\n");
1442 return;
1445 ptr = strtok(ptr, " ");
1446 while (ptr != NULL && check < ARGS_COUNT - 1) {
1447 args[check++] = atoi(ptr);
1448 ptr = strtok(NULL, " ");
1451 if (ptr == NULL || check != ARGS_COUNT - 1) {
1452 cliShowParseError();
1453 return;
1456 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1457 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1458 && (*ptr == 'r' || *ptr == 'n')) {
1459 if (*ptr == 'r')
1460 masterConfig.servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1461 else
1462 masterConfig.servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1463 } else
1464 cliShowParseError();
1466 cliServoMix("reverse");
1467 } else {
1468 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1469 ptr = strtok(cmdline, " ");
1470 while (ptr != NULL && check < ARGS_COUNT) {
1471 args[check++] = atoi(ptr);
1472 ptr = strtok(NULL, " ");
1475 if (ptr != NULL || check != ARGS_COUNT) {
1476 cliShowParseError();
1477 return;
1480 i = args[RULE];
1481 if (i >= 0 && i < MAX_SERVO_RULES &&
1482 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1483 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1484 args[RATE] >= -100 && args[RATE] <= 100 &&
1485 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1486 args[MIN] >= 0 && args[MIN] <= 100 &&
1487 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1488 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1489 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1490 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1491 masterConfig.customServoMixer[i].rate = args[RATE];
1492 masterConfig.customServoMixer[i].speed = args[SPEED];
1493 masterConfig.customServoMixer[i].min = args[MIN];
1494 masterConfig.customServoMixer[i].max = args[MAX];
1495 masterConfig.customServoMixer[i].box = args[BOX];
1496 cliServoMix("");
1497 } else {
1498 cliShowParseError();
1502 #endif
1504 #ifdef USE_SDCARD
1506 static void cliWriteBytes(const uint8_t *buffer, int count)
1508 while (count > 0) {
1509 cliWrite(*buffer);
1510 buffer++;
1511 count--;
1515 static void cliSdInfo(char *cmdline) {
1516 UNUSED(cmdline);
1518 cliPrint("SD card: ");
1520 if (!sdcard_isInserted()) {
1521 cliPrint("None inserted\r\n");
1522 return;
1525 if (!sdcard_isInitialized()) {
1526 cliPrint("Startup failed\r\n");
1527 return;
1530 const sdcardMetadata_t *metadata = sdcard_getMetadata();
1532 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1533 metadata->manufacturerID,
1534 metadata->numBlocks / 2, /* One block is half a kB */
1535 metadata->productionMonth,
1536 metadata->productionYear,
1537 metadata->productRevisionMajor,
1538 metadata->productRevisionMinor
1541 cliWriteBytes((uint8_t*)metadata->productName, sizeof(metadata->productName));
1543 cliPrint("'\r\n" "Filesystem: ");
1545 switch (afatfs_getFilesystemState()) {
1546 case AFATFS_FILESYSTEM_STATE_READY:
1547 cliPrint("Ready");
1548 break;
1549 case AFATFS_FILESYSTEM_STATE_INITIALIZATION:
1550 cliPrint("Initializing");
1551 break;
1552 case AFATFS_FILESYSTEM_STATE_UNKNOWN:
1553 case AFATFS_FILESYSTEM_STATE_FATAL:
1554 cliPrint("Fatal");
1556 switch (afatfs_getLastError()) {
1557 case AFATFS_ERROR_BAD_MBR:
1558 cliPrint(" - no FAT MBR partitions");
1559 break;
1560 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER:
1561 cliPrint(" - bad FAT header");
1562 break;
1563 case AFATFS_ERROR_GENERIC:
1564 case AFATFS_ERROR_NONE:
1565 ; // Nothing more detailed to print
1566 break;
1569 cliPrint("\r\n");
1570 break;
1574 #endif
1576 #ifdef USE_FLASHFS
1578 static void cliFlashInfo(char *cmdline)
1580 const flashGeometry_t *layout = flashfsGetGeometry();
1582 UNUSED(cmdline);
1584 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1585 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1588 static void cliFlashErase(char *cmdline)
1590 UNUSED(cmdline);
1592 cliPrintf("Erasing...\r\n");
1593 flashfsEraseCompletely();
1595 while (!flashfsIsReady()) {
1596 delay(100);
1599 cliPrintf("Done.\r\n");
1602 #ifdef USE_FLASH_TOOLS
1604 static void cliFlashWrite(char *cmdline)
1606 uint32_t address = atoi(cmdline);
1607 char *text = strchr(cmdline, ' ');
1609 if (!text) {
1610 cliShowParseError();
1611 } else {
1612 flashfsSeekAbs(address);
1613 flashfsWrite((uint8_t*)text, strlen(text), true);
1614 flashfsFlushSync();
1616 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1620 static void cliFlashRead(char *cmdline)
1622 uint32_t address = atoi(cmdline);
1623 uint32_t length;
1624 int i;
1626 uint8_t buffer[32];
1628 char *nextArg = strchr(cmdline, ' ');
1630 if (!nextArg) {
1631 cliShowParseError();
1632 } else {
1633 length = atoi(nextArg);
1635 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1637 while (length > 0) {
1638 int bytesRead;
1640 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1642 for (i = 0; i < bytesRead; i++) {
1643 cliWrite(buffer[i]);
1646 length -= bytesRead;
1647 address += bytesRead;
1649 if (bytesRead == 0) {
1650 //Assume we reached the end of the volume or something fatal happened
1651 break;
1654 cliPrintf("\r\n");
1658 #endif
1659 #endif
1661 static void dumpValues(uint16_t valueSection)
1663 uint32_t i;
1664 const clivalue_t *value;
1665 for (i = 0; i < VALUE_COUNT; i++) {
1666 value = &valueTable[i];
1668 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1669 continue;
1672 cliPrintf("set %s = ", valueTable[i].name);
1673 cliPrintVar(value, 0);
1674 cliPrint("\r\n");
1678 typedef enum {
1679 DUMP_MASTER = (1 << 0),
1680 DUMP_PROFILE = (1 << 1),
1681 } dumpFlags_e;
1683 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE)
1686 static const char* const sectionBreak = "\r\n";
1688 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1690 static void cliDump(char *cmdline)
1692 unsigned int i;
1693 char buf[16];
1694 uint32_t mask;
1696 #ifndef USE_QUAD_MIXER_ONLY
1697 float thr, roll, pitch, yaw;
1698 #endif
1700 uint8_t dumpMask = DUMP_ALL;
1701 if (strcasecmp(cmdline, "master") == 0) {
1702 dumpMask = DUMP_MASTER; // only
1704 if (strcasecmp(cmdline, "profile") == 0) {
1705 dumpMask = DUMP_PROFILE; // only
1708 if (dumpMask & DUMP_MASTER) {
1710 cliPrint("\r\n# version\r\n");
1711 cliVersion(NULL);
1713 cliPrint("\r\n# dump master\r\n");
1714 cliPrint("\r\n# mixer\r\n");
1716 #ifndef USE_QUAD_MIXER_ONLY
1717 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1719 cliPrintf("mmix reset\r\n");
1721 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1722 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1723 break;
1724 thr = masterConfig.customMotorMixer[i].throttle;
1725 roll = masterConfig.customMotorMixer[i].roll;
1726 pitch = masterConfig.customMotorMixer[i].pitch;
1727 yaw = masterConfig.customMotorMixer[i].yaw;
1728 cliPrintf("mmix %d", i);
1729 if (thr < 0)
1730 cliWrite(' ');
1731 cliPrintf("%s", ftoa(thr, buf));
1732 if (roll < 0)
1733 cliWrite(' ');
1734 cliPrintf("%s", ftoa(roll, buf));
1735 if (pitch < 0)
1736 cliWrite(' ');
1737 cliPrintf("%s", ftoa(pitch, buf));
1738 if (yaw < 0)
1739 cliWrite(' ');
1740 cliPrintf("%s\r\n", ftoa(yaw, buf));
1743 #ifdef USE_SERVOS
1744 // print custom servo mixer if exists
1745 cliPrintf("smix reset\r\n");
1747 for (i = 0; i < MAX_SERVO_RULES; i++) {
1749 if (masterConfig.customServoMixer[i].rate == 0)
1750 break;
1752 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1754 masterConfig.customServoMixer[i].targetChannel,
1755 masterConfig.customServoMixer[i].inputSource,
1756 masterConfig.customServoMixer[i].rate,
1757 masterConfig.customServoMixer[i].speed,
1758 masterConfig.customServoMixer[i].min,
1759 masterConfig.customServoMixer[i].max,
1760 masterConfig.customServoMixer[i].box
1764 #endif
1765 #endif
1767 cliPrint("\r\n\r\n# feature\r\n");
1769 mask = featureMask();
1770 for (i = 0; ; i++) { // disable all feature first
1771 if (featureNames[i] == NULL)
1772 break;
1773 cliPrintf("feature -%s\r\n", featureNames[i]);
1775 for (i = 0; ; i++) { // reenable what we want.
1776 if (featureNames[i] == NULL)
1777 break;
1778 if (mask & (1 << i))
1779 cliPrintf("feature %s\r\n", featureNames[i]);
1782 cliPrint("\r\n\r\n# map\r\n");
1784 for (i = 0; i < 8; i++)
1785 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1786 buf[i] = '\0';
1787 cliPrintf("map %s\r\n", buf);
1789 cliPrint("\r\n\r\n# serial\r\n");
1790 cliSerial("");
1792 #ifdef LED_STRIP
1793 cliPrint("\r\n\r\n# led\r\n");
1794 cliLed("");
1796 cliPrint("\r\n\r\n# color\r\n");
1797 cliColor("");
1798 #endif
1800 cliPrint("\r\n# aux\r\n");
1802 cliAux("");
1804 cliPrint("\r\n# adjrange\r\n");
1806 cliAdjustmentRange("");
1808 cliPrintf("\r\n# rxrange\r\n");
1810 cliRxRange("");
1812 #ifdef USE_SERVOS
1813 cliPrint("\r\n# servo\r\n");
1815 cliServo("");
1817 // print servo directions
1818 unsigned int channel;
1820 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1821 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
1822 if (servoDirection(i, channel) < 0) {
1823 cliPrintf("smix reverse %d %d r\r\n", i , channel);
1827 #endif
1829 printSectionBreak();
1830 dumpValues(MASTER_VALUE);
1832 cliPrint("\r\n# rxfail\r\n");
1833 cliRxFail("");
1836 if (dumpMask & DUMP_PROFILE) {
1837 cliPrint("\r\n# dump profile\r\n");
1839 cliPrint("\r\n# profile\r\n");
1840 cliProfile("");
1842 printSectionBreak();
1844 dumpValues(PROFILE_VALUE);
1848 void cliEnter(serialPort_t *serialPort)
1850 cliMode = 1;
1851 cliPort = serialPort;
1852 setPrintfSerialPort(cliPort);
1853 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
1854 (bufWrite_t)serialWriteBufShim, serialPort);
1856 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1857 cliPrompt();
1858 ENABLE_ARMING_FLAG(PREVENT_ARMING);
1861 static void cliExit(char *cmdline)
1863 UNUSED(cmdline);
1865 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1866 bufWriterFlush(cliWriter);
1868 *cliBuffer = '\0';
1869 bufferIndex = 0;
1870 cliMode = 0;
1871 // incase a motor was left running during motortest, clear it here
1872 mixerResetDisarmedMotors();
1873 cliReboot();
1875 cliWriter = NULL;
1878 static void cliFeature(char *cmdline)
1880 uint32_t i;
1881 uint32_t len;
1882 uint32_t mask;
1884 len = strlen(cmdline);
1885 mask = featureMask();
1887 if (len == 0) {
1888 cliPrint("Enabled: ");
1889 for (i = 0; ; i++) {
1890 if (featureNames[i] == NULL)
1891 break;
1892 if (mask & (1 << i))
1893 cliPrintf("%s ", featureNames[i]);
1895 cliPrint("\r\n");
1896 } else if (strncasecmp(cmdline, "list", len) == 0) {
1897 cliPrint("Available: ");
1898 for (i = 0; ; i++) {
1899 if (featureNames[i] == NULL)
1900 break;
1901 cliPrintf("%s ", featureNames[i]);
1903 cliPrint("\r\n");
1904 return;
1905 } else {
1906 bool remove = false;
1907 if (cmdline[0] == '-') {
1908 // remove feature
1909 remove = true;
1910 cmdline++; // skip over -
1911 len--;
1914 for (i = 0; ; i++) {
1915 if (featureNames[i] == NULL) {
1916 cliPrint("Invalid name\r\n");
1917 break;
1920 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
1922 mask = 1 << i;
1923 #ifndef GPS
1924 if (mask & FEATURE_GPS) {
1925 cliPrint("unavailable\r\n");
1926 break;
1928 #endif
1929 #ifndef SONAR
1930 if (mask & FEATURE_SONAR) {
1931 cliPrint("unavailable\r\n");
1932 break;
1934 #endif
1935 if (remove) {
1936 featureClear(mask);
1937 cliPrint("Disabled");
1938 } else {
1939 featureSet(mask);
1940 cliPrint("Enabled");
1942 cliPrintf(" %s\r\n", featureNames[i]);
1943 break;
1949 #ifdef GPS
1950 static void cliGpsPassthrough(char *cmdline)
1952 UNUSED(cmdline);
1954 gpsEnablePassthrough(cliPort);
1956 #endif
1958 static void cliHelp(char *cmdline)
1960 uint32_t i = 0;
1962 UNUSED(cmdline);
1964 for (i = 0; i < CMD_COUNT; i++) {
1965 cliPrint(cmdTable[i].name);
1966 #ifndef SKIP_CLI_COMMAND_HELP
1967 if (cmdTable[i].description) {
1968 cliPrintf(" - %s", cmdTable[i].description);
1970 if (cmdTable[i].args) {
1971 cliPrintf("\r\n\t%s", cmdTable[i].args);
1973 #endif
1974 cliPrint("\r\n");
1978 static void cliMap(char *cmdline)
1980 uint32_t len;
1981 uint32_t i;
1982 char out[9];
1984 len = strlen(cmdline);
1986 if (len == 8) {
1987 // uppercase it
1988 for (i = 0; i < 8; i++)
1989 cmdline[i] = toupper((unsigned char)cmdline[i]);
1990 for (i = 0; i < 8; i++) {
1991 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
1992 continue;
1993 cliShowParseError();
1994 return;
1996 parseRcChannels(cmdline, &masterConfig.rxConfig);
1998 cliPrint("Map: ");
1999 for (i = 0; i < 8; i++)
2000 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2001 out[i] = '\0';
2002 cliPrintf("%s\r\n", out);
2005 #ifndef USE_QUAD_MIXER_ONLY
2006 static void cliMixer(char *cmdline)
2008 int i;
2009 int len;
2011 len = strlen(cmdline);
2013 if (len == 0) {
2014 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2015 return;
2016 } else if (strncasecmp(cmdline, "list", len) == 0) {
2017 cliPrint("Available mixers: ");
2018 for (i = 0; ; i++) {
2019 if (mixerNames[i] == NULL)
2020 break;
2021 cliPrintf("%s ", mixerNames[i]);
2023 cliPrint("\r\n");
2024 return;
2027 for (i = 0; ; i++) {
2028 if (mixerNames[i] == NULL) {
2029 cliPrint("Invalid name\r\n");
2030 return;
2032 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2033 masterConfig.mixerMode = i + 1;
2034 break;
2038 cliMixer("");
2040 #endif
2042 static void cliMotor(char *cmdline)
2044 int motor_index = 0;
2045 int motor_value = 0;
2046 int index = 0;
2047 char *pch = NULL;
2048 char *saveptr;
2050 if (isEmpty(cmdline)) {
2051 cliShowParseError();
2052 return;
2055 pch = strtok_r(cmdline, " ", &saveptr);
2056 while (pch != NULL) {
2057 switch (index) {
2058 case 0:
2059 motor_index = atoi(pch);
2060 break;
2061 case 1:
2062 motor_value = atoi(pch);
2063 break;
2065 index++;
2066 pch = strtok_r(NULL, " ", &saveptr);
2069 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2070 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2071 return;
2074 if (index == 2) {
2075 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2076 cliShowArgumentRangeError("value", 1000, 2000);
2077 return;
2078 } else {
2079 motor_disarmed[motor_index] = motor_value;
2083 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2086 static void cliPlaySound(char *cmdline)
2088 #if FLASH_SIZE <= 64
2089 UNUSED(cmdline);
2090 #else
2091 int i;
2092 const char *name;
2093 static int lastSoundIdx = -1;
2095 if (isEmpty(cmdline)) {
2096 i = lastSoundIdx + 1; //next sound index
2097 if ((name=beeperNameForTableIndex(i)) == NULL) {
2098 while (true) { //no name for index; try next one
2099 if (++i >= beeperTableEntryCount())
2100 i = 0; //if end then wrap around to first entry
2101 if ((name=beeperNameForTableIndex(i)) != NULL)
2102 break; //if name OK then play sound below
2103 if (i == lastSoundIdx + 1) { //prevent infinite loop
2104 cliPrintf("Error playing sound\r\n");
2105 return;
2109 } else { //index value was given
2110 i = atoi(cmdline);
2111 if ((name=beeperNameForTableIndex(i)) == NULL) {
2112 cliPrintf("No sound for index %d\r\n", i);
2113 return;
2116 lastSoundIdx = i;
2117 beeperSilence();
2118 cliPrintf("Playing sound %d: %s\r\n", i, name);
2119 beeper(beeperModeForTableIndex(i));
2120 #endif
2123 static void cliProfile(char *cmdline)
2125 int i;
2127 if (isEmpty(cmdline)) {
2128 cliPrintf("profile %d\r\n", getCurrentProfile());
2129 return;
2130 } else {
2131 i = atoi(cmdline);
2132 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2133 masterConfig.current_profile_index = i;
2134 writeEEPROM();
2135 readEEPROM();
2136 cliProfile("");
2141 static void cliReboot(void) {
2142 cliPrint("\r\nRebooting");
2143 bufWriterFlush(cliWriter);
2144 waitForSerialPortToFinishTransmitting(cliPort);
2145 stopMotors();
2146 handleOneshotFeatureChangeOnRestart();
2147 systemReset();
2150 static void cliSave(char *cmdline)
2152 UNUSED(cmdline);
2154 cliPrint("Saving");
2155 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2156 writeEEPROM();
2157 cliReboot();
2160 static void cliDefaults(char *cmdline)
2162 UNUSED(cmdline);
2164 cliPrint("Resetting to defaults");
2165 resetEEPROM();
2166 cliReboot();
2169 static void cliPrint(const char *str)
2171 while (*str)
2172 bufWriterAppend(cliWriter, *str++);
2175 static void cliPutp(void *p, char ch)
2177 bufWriterAppend(p, ch);
2180 static void cliPrintf(const char *fmt, ...)
2182 va_list va;
2183 va_start(va, fmt);
2184 tfp_format(cliWriter, cliPutp, fmt, va);
2185 va_end(va);
2188 static void cliWrite(uint8_t ch)
2190 bufWriterAppend(cliWriter, ch);
2193 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2195 int32_t value = 0;
2196 char buf[8];
2198 void *ptr = var->ptr;
2199 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2200 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2203 switch (var->type & VALUE_TYPE_MASK) {
2204 case VAR_UINT8:
2205 value = *(uint8_t *)ptr;
2206 break;
2208 case VAR_INT8:
2209 value = *(int8_t *)ptr;
2210 break;
2212 case VAR_UINT16:
2213 value = *(uint16_t *)ptr;
2214 break;
2216 case VAR_INT16:
2217 value = *(int16_t *)ptr;
2218 break;
2220 case VAR_UINT32:
2221 value = *(uint32_t *)ptr;
2222 break;
2224 case VAR_FLOAT:
2225 cliPrintf("%s", ftoa(*(float *)ptr, buf));
2226 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2227 cliPrintf(" %s", ftoa((float)var->config.minmax.min, buf));
2228 cliPrintf(" %s", ftoa((float)var->config.minmax.max, buf));
2230 return; // return from case for float only
2233 switch(var->type & VALUE_MODE_MASK) {
2234 case MODE_DIRECT:
2235 cliPrintf("%d", value);
2236 if (full) {
2237 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2239 break;
2240 case MODE_LOOKUP:
2241 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2242 break;
2246 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2248 void *ptr = var->ptr;
2249 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2250 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2253 switch (var->type & VALUE_TYPE_MASK) {
2254 case VAR_UINT8:
2255 case VAR_INT8:
2256 *(int8_t *)ptr = value.int_value;
2257 break;
2259 case VAR_UINT16:
2260 case VAR_INT16:
2261 *(int16_t *)ptr = value.int_value;
2262 break;
2264 case VAR_UINT32:
2265 *(uint32_t *)ptr = value.int_value;
2266 break;
2268 case VAR_FLOAT:
2269 *(float *)ptr = (float)value.float_value;
2270 break;
2274 static void cliSet(char *cmdline)
2276 uint32_t i;
2277 uint32_t len;
2278 const clivalue_t *val;
2279 char *eqptr = NULL;
2281 len = strlen(cmdline);
2283 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2284 cliPrint("Current settings: \r\n");
2285 for (i = 0; i < VALUE_COUNT; i++) {
2286 val = &valueTable[i];
2287 cliPrintf("%s = ", valueTable[i].name);
2288 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2289 cliPrint("\r\n");
2291 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2292 // has equals
2294 char *lastNonSpaceCharacter = eqptr;
2295 while (*(lastNonSpaceCharacter - 1) == ' ') {
2296 lastNonSpaceCharacter--;
2298 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2300 // skip the '=' and any ' ' characters
2301 eqptr++;
2302 while (*(eqptr) == ' ') {
2303 eqptr++;
2306 for (i = 0; i < VALUE_COUNT; i++) {
2307 val = &valueTable[i];
2308 // ensure exact match when setting to prevent setting variables with shorter names
2309 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2311 bool changeValue = false;
2312 int_float_value_t tmp;
2313 switch (valueTable[i].type & VALUE_MODE_MASK) {
2314 case MODE_DIRECT: {
2315 int32_t value = 0;
2316 float valuef = 0;
2318 value = atoi(eqptr);
2319 valuef = fastA2F(eqptr);
2321 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2323 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2324 tmp.float_value = valuef;
2325 else
2326 tmp.int_value = value;
2328 changeValue = true;
2331 break;
2332 case MODE_LOOKUP: {
2333 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2334 bool matched = false;
2335 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2336 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2338 if (matched) {
2339 tmp.int_value = tableValueIndex;
2340 changeValue = true;
2344 break;
2347 if (changeValue) {
2348 cliSetVar(val, tmp);
2350 cliPrintf("%s set to ", valueTable[i].name);
2351 cliPrintVar(val, 0);
2352 } else {
2353 cliPrint("Invalid value\r\n");
2356 return;
2359 cliPrint("Invalid name\r\n");
2360 } else {
2361 // no equals, check for matching variables.
2362 cliGet(cmdline);
2366 static void cliGet(char *cmdline)
2368 uint32_t i;
2369 const clivalue_t *val;
2370 int matchedCommands = 0;
2372 for (i = 0; i < VALUE_COUNT; i++) {
2373 if (strstr(valueTable[i].name, cmdline)) {
2374 val = &valueTable[i];
2375 cliPrintf("%s = ", valueTable[i].name);
2376 cliPrintVar(val, 0);
2377 cliPrint("\r\n");
2379 matchedCommands++;
2384 if (matchedCommands) {
2385 return;
2388 cliPrint("Invalid name\r\n");
2391 static void cliStatus(char *cmdline)
2393 UNUSED(cmdline);
2395 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
2396 millis() / 1000,
2397 vbat,
2398 batteryCellCount,
2399 getBatteryStateString(),
2400 constrain(averageSystemLoadPercent, 0, 100)
2403 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2405 #ifndef CJMCU
2406 uint8_t i;
2407 uint32_t mask;
2408 uint32_t detectedSensorsMask = sensorsMask();
2410 for (i = 0; ; i++) {
2412 if (sensorTypeNames[i] == NULL)
2413 break;
2415 mask = (1 << i);
2416 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2417 const char *sensorHardware;
2418 uint8_t sensorHardwareIndex = detectedSensors[i];
2419 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2421 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2423 if (mask == SENSOR_ACC && acc.revisionCode) {
2424 cliPrintf(".%c", acc.revisionCode);
2428 #endif
2429 cliPrint("\r\n");
2431 #ifdef USE_I2C
2432 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2433 #else
2434 uint16_t i2cErrorCounter = 0;
2435 #endif
2437 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2440 #ifndef SKIP_TASK_STATISTICS
2441 static void cliTasks(char *cmdline)
2443 UNUSED(cmdline);
2445 cfTaskId_e taskId;
2446 cfTaskInfo_t taskInfo;
2448 cliPrintf("Task list:\r\n");
2449 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2450 getTaskInfo(taskId, &taskInfo);
2451 if (taskInfo.isEnabled) {
2452 cliPrintf("%d - %s, max = %d us, avg = %d us, total = %d ms\r\n", taskId, taskInfo.taskName, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskInfo.totalExecutionTime / 1000);
2456 #endif
2458 static void cliVersion(char *cmdline)
2460 UNUSED(cmdline);
2462 cliPrintf("# BetaFlight/%s %s %s / %s (%s)",
2463 targetName,
2464 FC_VERSION_STRING,
2465 buildDate,
2466 buildTime,
2467 shortGitRevision
2471 void cliProcess(void)
2473 if (!cliWriter) {
2474 return;
2477 // Be a little bit tricky. Flush the last inputs buffer, if any.
2478 bufWriterFlush(cliWriter);
2480 while (serialRxBytesWaiting(cliPort)) {
2481 uint8_t c = serialRead(cliPort);
2482 if (c == '\t' || c == '?') {
2483 // do tab completion
2484 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2485 uint32_t i = bufferIndex;
2486 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2487 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2488 continue;
2489 if (!pstart)
2490 pstart = cmd;
2491 pend = cmd;
2493 if (pstart) { /* Buffer matches one or more commands */
2494 for (; ; bufferIndex++) {
2495 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2496 break;
2497 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2498 /* Unambiguous -- append a space */
2499 cliBuffer[bufferIndex++] = ' ';
2500 cliBuffer[bufferIndex] = '\0';
2501 break;
2503 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2506 if (!bufferIndex || pstart != pend) {
2507 /* Print list of ambiguous matches */
2508 cliPrint("\r\033[K");
2509 for (cmd = pstart; cmd <= pend; cmd++) {
2510 cliPrint(cmd->name);
2511 cliWrite('\t');
2513 cliPrompt();
2514 i = 0; /* Redraw prompt */
2516 for (; i < bufferIndex; i++)
2517 cliWrite(cliBuffer[i]);
2518 } else if (!bufferIndex && c == 4) { // CTRL-D
2519 cliExit(cliBuffer);
2520 return;
2521 } else if (c == 12) { // NewPage / CTRL-L
2522 // clear screen
2523 cliPrint("\033[2J\033[1;1H");
2524 cliPrompt();
2525 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2526 // enter pressed
2527 cliPrint("\r\n");
2529 // Strip comment starting with # from line
2530 char *p = cliBuffer;
2531 p = strchr(p, '#');
2532 if (NULL != p) {
2533 bufferIndex = (uint32_t)(p - cliBuffer);
2536 // Strip trailing whitespace
2537 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2538 bufferIndex--;
2541 // Process non-empty lines
2542 if (bufferIndex > 0) {
2543 cliBuffer[bufferIndex] = 0; // null terminate
2545 const clicmd_t *cmd;
2546 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2547 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2548 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2549 break;
2551 if(cmd < cmdTable + CMD_COUNT)
2552 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2553 else
2554 cliPrint("Unknown command, try 'help'");
2555 bufferIndex = 0;
2558 memset(cliBuffer, 0, sizeof(cliBuffer));
2560 // 'exit' will reset this flag, so we don't need to print prompt again
2561 if (!cliMode)
2562 return;
2564 cliPrompt();
2565 } else if (c == 127) {
2566 // backspace
2567 if (bufferIndex) {
2568 cliBuffer[--bufferIndex] = 0;
2569 cliPrint("\010 \010");
2571 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2572 if (!bufferIndex && c == ' ')
2573 continue; // Ignore leading spaces
2574 cliBuffer[bufferIndex++] = c;
2575 cliWrite(c);
2580 void cliInit(serialConfig_t *serialConfig)
2582 UNUSED(serialConfig);
2584 #endif