Merge pull request #194 from iNavFlight/sbas-none
[betaflight.git] / src / main / io / serial_cli.c
blob19ea8bece627497adee5f4ca8c34522df1b33bd2
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
19 #include <stdint.h>
20 #include <stdlib.h>
21 #include <stdarg.h>
22 #include <string.h>
23 #include <math.h>
24 #include <ctype.h>
26 #include "platform.h"
27 #include "version.h"
29 #include "scheduler/scheduler.h"
31 #include "build_config.h"
33 #include "common/axis.h"
34 #include "common/maths.h"
35 #include "common/color.h"
36 #include "common/typeconversion.h"
38 #include "drivers/system.h"
40 #include "drivers/sensor.h"
41 #include "drivers/accgyro.h"
42 #include "drivers/compass.h"
44 #include "drivers/serial.h"
45 #include "drivers/bus_i2c.h"
46 #include "drivers/gpio.h"
47 #include "drivers/timer.h"
48 #include "drivers/pwm_rx.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"
61 #include "rx/rx.h"
62 #include "rx/spektrum.h"
64 #include "sensors/battery.h"
65 #include "sensors/boardalignment.h"
66 #include "sensors/sensors.h"
67 #include "sensors/acceleration.h"
68 #include "sensors/gyro.h"
69 #include "sensors/compass.h"
70 #include "sensors/barometer.h"
72 #include "flight/pid.h"
73 #include "flight/imu.h"
74 #include "flight/mixer.h"
75 #include "flight/navigation_rewrite.h"
76 #include "flight/failsafe.h"
78 #include "telemetry/telemetry.h"
79 #include "telemetry/frsky.h"
81 #include "config/runtime_config.h"
82 #include "config/config.h"
83 #include "config/config_profile.h"
84 #include "config/config_master.h"
86 #include "common/printf.h"
88 #include "serial_cli.h"
90 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
91 // signal that we're in cli mode
92 uint8_t cliMode = 0;
94 #ifdef USE_CLI
96 extern uint16_t cycleTime; // FIXME dependency on mw.c
98 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
100 static serialPort_t *cliPort;
101 static bufWriter_t *cliWriter;
102 static uint8_t cliWriteBuffer[sizeof(*cliWriter) + 16];
104 static void cliAux(char *cmdline);
105 static void cliRxFail(char *cmdline);
106 static void cliAdjustmentRange(char *cmdline);
107 static void cliMotorMix(char *cmdline);
108 static void cliDefaults(char *cmdline);
109 static void cliDump(char *cmdLine);
110 static void cliExit(char *cmdline);
111 static void cliFeature(char *cmdline);
112 static void cliMotor(char *cmdline);
113 static void cliPlaySound(char *cmdline);
114 static void cliProfile(char *cmdline);
115 static void cliRateProfile(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);
133 static void cliPFlags(char *cmdline);
136 #ifdef GPS
137 static void cliGpsPassthrough(char *cmdline);
138 #endif
140 static void cliHelp(char *cmdline);
141 static void cliMap(char *cmdline);
143 #ifdef LED_STRIP
144 static void cliLed(char *cmdline);
145 static void cliColor(char *cmdline);
146 #endif
148 #ifndef USE_QUAD_MIXER_ONLY
149 static void cliMixer(char *cmdline);
150 #endif
152 #ifdef USE_FLASHFS
153 static void cliFlashInfo(char *cmdline);
154 static void cliFlashErase(char *cmdline);
155 #ifdef USE_FLASH_TOOLS
156 static void cliFlashWrite(char *cmdline);
157 static void cliFlashRead(char *cmdline);
158 #endif
159 #endif
161 #ifdef BEEPER
162 static void cliBeeper(char *cmdline);
163 #endif
165 // buffer
166 static char cliBuffer[48];
167 static uint32_t bufferIndex = 0;
169 #ifndef USE_QUAD_MIXER_ONLY
170 // this with mixerMode_e
171 static const char * const mixerNames[] = {
172 "TRI", "QUADP", "QUADX", "BI",
173 "GIMBAL", "Y6", "HEX6",
174 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
175 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
176 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
177 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
179 #endif
181 // sync this with features_e
182 static const char * const featureNames[] = {
183 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
184 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
185 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
186 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
187 "BLACKBOX", "CHANNEL_FORWARDING", NULL
190 // sync this with rxFailsafeChannelMode_e
191 static const char rxFailsafeModeCharacters[] = "ahs";
193 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
194 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
195 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
198 #ifndef CJMCU
199 // sync this with sensors_e
200 static const char * const sensorTypeNames[] = {
201 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
204 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
206 static const char * const sensorHardwareNames[4][11] = {
207 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
208 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
209 { "", "None", "BMP085", "MS5611", "BMP280", "FAKE", NULL },
210 { "", "None", "HMC5883", "AK8975", "FAKE", NULL }
212 #endif
214 typedef struct {
215 const char *name;
216 #ifndef SKIP_CLI_COMMAND_HELP
217 const char *description;
218 const char *args;
219 #endif
220 void (*func)(char *cmdline);
221 } clicmd_t;
223 #ifndef SKIP_CLI_COMMAND_HELP
224 #define CLI_COMMAND_DEF(name, description, args, method) \
226 name , \
227 description , \
228 args , \
229 method \
231 #else
232 #define CLI_COMMAND_DEF(name, description, args, method) \
234 name, \
235 method \
237 #endif
239 // should be sorted a..z for bsearch()
240 const clicmd_t cmdTable[] = {
241 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
242 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
243 #ifdef LED_STRIP
244 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
245 #endif
246 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
247 CLI_COMMAND_DEF("dump", "dump configuration",
248 "[master|profile]", cliDump),
249 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
250 CLI_COMMAND_DEF("feature", "configure features",
251 "list\r\n"
252 "\t<+|->[name]", cliFeature),
253 #ifdef USE_FLASHFS
254 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
255 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
256 #ifdef USE_FLASH_TOOLS
257 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
258 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
259 #endif
260 #endif
261 CLI_COMMAND_DEF("get", "get variable value",
262 "[name]", cliGet),
263 #ifdef GPS
264 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
265 #endif
266 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
267 #ifdef LED_STRIP
268 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
269 #endif
270 CLI_COMMAND_DEF("map", "configure rc channel order",
271 "[<map>]", cliMap),
272 #ifndef USE_QUAD_MIXER_ONLY
273 CLI_COMMAND_DEF("mixer", "configure mixer",
274 "list\r\n"
275 "\t<name>", cliMixer),
276 #endif
277 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
278 CLI_COMMAND_DEF("motor", "get/set motor",
279 "<index> [<value>]", cliMotor),
280 CLI_COMMAND_DEF("play_sound", NULL,
281 "[<index>]\r\n", cliPlaySound),
282 CLI_COMMAND_DEF("profile", "change profile",
283 "[<index>]", cliProfile),
284 CLI_COMMAND_DEF("rateprofile", "change rate profile",
285 "[<index>]", cliRateProfile),
286 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
287 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
288 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
289 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
290 #ifdef USE_SERVOS
291 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
292 #endif
293 CLI_COMMAND_DEF("set", "change setting",
294 "[<name>=<value>]", cliSet),
295 CLI_COMMAND_DEF("pflags", "get persistent flags", NULL, cliPFlags),
296 #ifdef USE_SERVOS
297 CLI_COMMAND_DEF("smix", "servo mixer",
298 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
299 "\treset\r\n"
300 "\tload <mixer>\r\n"
301 "\treverse <servo> <source> r|n", cliServoMix),
302 #endif
303 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
304 #ifndef SKIP_TASK_STATISTICS
305 CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
306 #endif
307 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
308 #ifdef BEEPER
309 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
310 "\t<+|->[name]", cliBeeper),
311 #endif
313 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
315 static const char * const lookupTableOffOn[] = {
316 "OFF", "ON"
319 static const char * const lookupTableUnit[] = {
320 "IMPERIAL", "METRIC"
323 static const char * const lookupTableAlignment[] = {
324 "DEFAULT",
325 "CW0",
326 "CW90",
327 "CW180",
328 "CW270",
329 "CW0FLIP",
330 "CW90FLIP",
331 "CW180FLIP",
332 "CW270FLIP"
335 #ifdef GPS
336 static const char * const lookupTableGPSProvider[] = {
337 "NMEA", "UBLOX", "I2C-NAV", "NAZA"
340 static const char * const lookupTableGPSSBASMode[] = {
341 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"
344 static const char * const lookupTableGpsModel[] = {
345 "PEDESTRIAN", "AIR_1G", "AIR_4G"
347 #endif
349 static const char * const lookupTableCurrentSensor[] = {
350 "NONE", "ADC", "VIRTUAL"
353 static const char * const lookupTableGimbalMode[] = {
354 "NORMAL", "MIXTILT"
357 static const char * const lookupTablePidController[] = {
358 "UNUSED", "MWREWRITE", "LUX"
361 static const char * const lookupTableBlackboxDevice[] = {
362 "SERIAL", "SPIFLASH"
365 static const char * const lookupTableSerialRX[] = {
366 "SPEK1024",
367 "SPEK2048",
368 "SBUS",
369 "SUMD",
370 "SUMH",
371 "XB-B",
372 "XB-B-RJ01",
373 "IBUS"
376 static const char * const lookupTableGyroFilter[] = {
377 "OFF", "LOW", "MEDIUM", "HIGH"
380 static const char * const lookupTableGyroLpf[] = {
381 "256HZ",
382 "188HZ",
383 "98HZ",
384 "42HZ",
385 "20HZ",
386 "10HZ"
389 static const char * const lookupTableFailsafeProcedure[] = {
390 "SET-THR", "DROP", "RTH"
393 #ifdef NAV
394 static const char * const lookupTableNavControlMode[] = {
395 "ATTI", "CRUISE"
398 static const char * const lookupTableNavRthAltMode[] = {
399 "CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST"
401 #endif
403 typedef struct lookupTableEntry_s {
404 const char * const *values;
405 const uint8_t valueCount;
406 } lookupTableEntry_t;
408 typedef enum {
409 TABLE_OFF_ON = 0,
410 TABLE_UNIT,
411 TABLE_ALIGNMENT,
412 #ifdef GPS
413 TABLE_GPS_PROVIDER,
414 TABLE_GPS_SBAS_MODE,
415 TABLE_GPS_DYN_MODEL,
416 #endif
417 #ifdef BLACKBOX
418 TABLE_BLACKBOX_DEVICE,
419 #endif
420 TABLE_CURRENT_SENSOR,
421 TABLE_GIMBAL_MODE,
422 TABLE_PID_CONTROLLER,
423 TABLE_SERIAL_RX,
424 TABLE_GYRO_LPF,
425 TABLE_FAILSAFE_PROCEDURE,
426 #ifdef NAV
427 TABLE_NAV_USER_CTL_MODE,
428 TABLE_NAV_RTH_ALT_MODE,
429 #endif
430 } lookupTableIndex_e;
432 static const lookupTableEntry_t lookupTables[] = {
433 { lookupTableOffOn, sizeof(lookupTableOffOn) / sizeof(char *) },
434 { lookupTableUnit, sizeof(lookupTableUnit) / sizeof(char *) },
435 { lookupTableAlignment, sizeof(lookupTableAlignment) / sizeof(char *) },
436 #ifdef GPS
437 { lookupTableGPSProvider, sizeof(lookupTableGPSProvider) / sizeof(char *) },
438 { lookupTableGPSSBASMode, sizeof(lookupTableGPSSBASMode) / sizeof(char *) },
439 { lookupTableGpsModel, sizeof(lookupTableGpsModel) / sizeof(char *) },
440 #endif
441 #ifdef BLACKBOX
442 { lookupTableBlackboxDevice, sizeof(lookupTableBlackboxDevice) / sizeof(char *) },
443 #endif
444 { lookupTableCurrentSensor, sizeof(lookupTableCurrentSensor) / sizeof(char *) },
445 { lookupTableGimbalMode, sizeof(lookupTableGimbalMode) / sizeof(char *) },
446 { lookupTablePidController, sizeof(lookupTablePidController) / sizeof(char *) },
447 { lookupTableSerialRX, sizeof(lookupTableSerialRX) / sizeof(char *) },
448 { lookupTableGyroLpf, sizeof(lookupTableGyroLpf) / sizeof(char *) },
449 { lookupTableFailsafeProcedure, sizeof(lookupTableFailsafeProcedure) / sizeof(char *) },
450 #ifdef NAV
451 { lookupTableNavControlMode, sizeof(lookupTableNavControlMode) / sizeof(char *) },
452 { lookupTableNavRthAltMode, sizeof(lookupTableNavRthAltMode) / sizeof(char *) },
453 #endif
456 #define VALUE_TYPE_OFFSET 0
457 #define VALUE_SECTION_OFFSET 4
458 #define VALUE_MODE_OFFSET 6
460 typedef enum {
461 // value type
462 VAR_UINT8 = (0 << VALUE_TYPE_OFFSET),
463 VAR_INT8 = (1 << VALUE_TYPE_OFFSET),
464 VAR_UINT16 = (2 << VALUE_TYPE_OFFSET),
465 VAR_INT16 = (3 << VALUE_TYPE_OFFSET),
466 VAR_UINT32 = (4 << VALUE_TYPE_OFFSET),
467 VAR_FLOAT = (5 << VALUE_TYPE_OFFSET),
469 // value section
470 MASTER_VALUE = (0 << VALUE_SECTION_OFFSET),
471 PROFILE_VALUE = (1 << VALUE_SECTION_OFFSET),
472 CONTROL_RATE_VALUE = (2 << 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 const persistent_flags_e pflags_to_set;
504 } clivalue_t;
506 const clivalue_t valueTable[] = {
507 { "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, .config.minmax = {0, 9000}, 0 },
508 { "emf_avoidance", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.emf_avoidance, .config.lookup = { TABLE_OFF_ON }, 0 },
509 { "i2c_overclock", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.i2c_overclock, .config.lookup = { TABLE_OFF_ON }, 0 },
510 { "gyro_sync", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyroSync, .config.lookup = { TABLE_OFF_ON } },
511 { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroSyncDenominator, .config.minmax = { 1, 32 } },
513 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, .config.minmax = { 1200, 1700 }, 0 },
514 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
515 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
516 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, .config.minmax = { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT }, 0 },
517 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, .config.minmax = { RSSI_SCALE_MIN, RSSI_SCALE_MAX }, 0 },
518 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON }, 0 },
519 { "rc_smoothing", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.rcSmoothing, .config.lookup = { TABLE_OFF_ON }, 0 },
520 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON }, 0 },
522 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
523 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
524 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
525 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
527 { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 }, // FIXME upper limit should match code in the mixer, 1500 currently
528 { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 }, // FIXME lower limit should match code in the mixer, 1500 currently,
529 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
530 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX }, 0 },
532 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, .config.minmax = { 50, 32000 }, 0 },
533 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, .config.minmax = { 50, 498 }, 0 },
535 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.disarm_kill_switch, .config.lookup = { TABLE_OFF_ON }, 0 },
536 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, .config.minmax = { 0, 60 }, 0 },
537 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, .config.minmax = { 0, 180 }, 0 },
539 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, .config.minmax = { 48, 126 }, 0 },
541 #ifdef GPS
542 { "gps_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.provider, .config.lookup = { TABLE_GPS_PROVIDER }, 0 },
543 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.sbasMode, .config.lookup = { TABLE_GPS_SBAS_MODE }, 0 },
544 { "gps_dyn_model", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.dynModel, .config.lookup = { TABLE_GPS_DYN_MODEL }, 0 },
545 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoConfig, .config.lookup = { TABLE_OFF_ON }, 0 },
546 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gpsConfig.autoBaud, .config.lookup = { TABLE_OFF_ON }, 0 },
547 #endif
549 #ifdef NAV
550 { "nav_alt_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], .config.minmax = { 0, 255 }, 0 },
551 { "nav_alt_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], .config.minmax = { 0, 255 }, 0 },
552 { "nav_alt_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], .config.minmax = { 0, 255 }, 0 },
554 { "nav_vel_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], .config.minmax = { 0, 255 }, 0 },
555 { "nav_vel_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], .config.minmax = { 0, 255 }, 0 },
556 { "nav_vel_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], .config.minmax = { 0, 255 }, 0 },
558 { "nav_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], .config.minmax = { 0, 255 }, 0 },
559 { "nav_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], .config.minmax = { 0, 255 }, 0 },
560 { "nav_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], .config.minmax = { 0, 255 }, 0 },
561 { "nav_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], .config.minmax = { 0, 255 }, 0 },
562 { "nav_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], .config.minmax = { 0, 255 }, 0 },
563 { "nav_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], .config.minmax = { 0, 255 }, 0 },
564 { "nav_navr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], .config.minmax = { 0, 255 }, 0 },
565 { "nav_navr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], .config.minmax = { 0, 255 }, 0 },
566 { "nav_navr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], .config.minmax = { 0, 255 }, 0 },
568 #if defined(NAV_AUTO_MAG_DECLINATION)
569 { "inav_auto_mag_decl", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.inav.automatic_mag_declination, .config.lookup = { TABLE_OFF_ON }, 0 },
570 #endif
572 { "inav_accz_unarmedcal", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.inav.accz_unarmed_cal, .config.lookup = { TABLE_OFF_ON }, 0 },
573 { "inav_use_gps_velned", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.inav.use_gps_velned, .config.lookup = { TABLE_OFF_ON }, 0 },
574 { "inav_gps_delay", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.inav.gps_delay_ms, .config.minmax = { 0, 500 }, 0 },
575 { "inav_gps_min_sats", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.inav.gps_min_sats, .config.minmax = { 5, 10}, 0 },
577 { "inav_w_z_baro_p", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_z_baro_p, .config.minmax = { 0, 10 }, 0 },
578 { "inav_w_z_gps_p", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_z_gps_p, .config.minmax = { 0, 10 }, 0 },
579 { "inav_w_z_gps_v", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_z_gps_v, .config.minmax = { 0, 10 }, 0 },
580 { "inav_w_xy_gps_p", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_xy_gps_p, .config.minmax = { 0, 10 }, 0 },
581 { "inav_w_xy_gps_v", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_xy_gps_v, .config.minmax = { 0, 10 }, 0 },
582 { "inav_w_z_res_v", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_z_res_v, .config.minmax = { 0, 10 }, 0 },
583 { "inav_w_xy_res_v", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_xy_res_v, .config.minmax = { 0, 10 }, 0 },
584 { "inav_w_acc_bias", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.w_acc_bias, .config.minmax = { 0, 1 }, 0 },
586 { "inav_max_eph_epv", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.max_eph_epv, .config.minmax = { 0, 9999 }, 0 },
587 { "inav_baro_epv", VAR_FLOAT | MASTER_VALUE, &masterConfig.navConfig.inav.baro_epv, .config.minmax = { 0, 9999 }, 0 },
589 { "nav_disarm_on_landing", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.disarm_on_landing, .config.lookup = { TABLE_OFF_ON }, 0 },
590 { "nav_use_midthr_for_althold", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.use_thr_mid_for_althold, .config.lookup = { TABLE_OFF_ON }, 0 },
591 { "nav_extra_arming_safety", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.extra_arming_safety, .config.lookup = { TABLE_OFF_ON }, 0 },
592 { "nav_user_control_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.user_control_mode, .config.lookup = { TABLE_NAV_USER_CTL_MODE }, 0 },
593 { "nav_position_timeout", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.pos_failure_timeout, .config.minmax = { 0, 10 }, 0 },
594 { "nav_wp_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.waypoint_radius, .config.minmax = { 10, 10000 }, 0 },
595 { "nav_max_speed", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.max_speed, .config.minmax = { 10, 2000 }, 0 },
596 { "nav_manual_speed", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.max_manual_speed, .config.minmax = { 10, 2000 }, 0 },
597 { "nav_manual_climb_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.max_manual_climb_rate, .config.minmax = { 10, 2000 }, 0 },
598 { "nav_landing_speed", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.land_descent_rate, .config.minmax = { 100, 2000 }, 0 },
599 { "nav_land_slowdown_minalt", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.land_slowdown_minalt, .config.minmax = { 50, 1000 }, 0 },
600 { "nav_land_slowdown_maxalt", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.land_slowdown_maxalt, .config.minmax = { 500, 4000 }, 0 },
601 { "nav_emerg_landing_speed", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.emerg_descent_rate, .config.minmax = { 100, 2000 }, 0 },
602 { "nav_min_rth_distance", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.min_rth_distance, .config.minmax = { 0, 5000 }, 0 },
603 { "nav_rth_tail_first", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.rth_tail_first, .config.lookup = { TABLE_OFF_ON }, 0 },
604 { "nav_rth_alt_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.navConfig.flags.rth_alt_control_style, .config.lookup = { TABLE_NAV_RTH_ALT_MODE }, 0 },
605 { "nav_rth_altitude", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.rth_altitude, .config.minmax = { 100, 65000 }, 0 },
607 { "nav_mc_bank_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.mc_max_bank_angle, .config.minmax = { 15, 45 }, 0 },
608 { "nav_mc_hover_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_hover_throttle, .config.minmax = { 1000, 2000 }, 0 },
609 { "nav_mc_min_fly_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.mc_min_fly_throttle, .config.minmax = { 1000, 2000 }, 0 },
611 { "nav_fw_cruise_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_cruise_throttle, .config.minmax = { 1000, 2000 }, 0 },
612 { "nav_fw_min_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_min_throttle, .config.minmax = { 1000, 2000 }, 0 },
613 { "nav_fw_max_thr", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_max_throttle, .config.minmax = { 1000, 2000 }, 0 },
614 { "nav_fw_bank_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.fw_max_bank_angle, .config.minmax = { 5, 45 }, 0 },
615 { "nav_fw_climb_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.fw_max_climb_angle, .config.minmax = { 5, 45 }, 0 },
616 { "nav_fw_dive_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.fw_max_dive_angle, .config.minmax = { 5, 45 }, 0 },
617 { "nav_fw_pitch2thr", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.fw_pitch_to_throttle, .config.minmax = { 0, 100 }, 0 },
618 { "nav_fw_roll2pitch", VAR_UINT8 | MASTER_VALUE, &masterConfig.navConfig.fw_roll_to_pitch, .config.minmax = { 0, 200 }, 0 },
619 { "nav_fw_loiter_radius", VAR_UINT16 | MASTER_VALUE, &masterConfig.navConfig.fw_loiter_radius, .config.minmax = { 0, 10000 }, 0 },
620 #endif
622 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.rxConfig.serialrx_provider, .config.lookup = { TABLE_SERIAL_RX }, 0 },
623 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, .config.minmax = { SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX}, 0 },
625 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_switch, .config.lookup = { TABLE_OFF_ON }, 0 },
626 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.telemetry_inversion, .config.lookup = { TABLE_OFF_ON }, 0 },
627 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, .config.minmax = { -90.0, 90.0 }, 0 },
628 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, .config.minmax = { -180.0, 180.0 }, 0 },
629 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, .config.minmax = { 0, FRSKY_FORMAT_NMEA }, 0 },
630 { "frsky_unit", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.telemetryConfig.frsky_unit, .config.lookup = { TABLE_UNIT }, 0 },
631 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, .config.minmax = { FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH }, 0 },
632 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, .config.minmax = { 0, 120 }, 0 },
634 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, .config.minmax = { 0, 20000 }, 0 },
635 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, .config.minmax = { VBAT_SCALE_MIN, VBAT_SCALE_MAX }, 0 },
636 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, .config.minmax = { 10, 50 }, 0 },
637 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, .config.minmax = { 10, 50 }, 0 },
638 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, .config.minmax = { 10, 50 }, 0 },
639 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, .config.minmax = { -10000, 10000 }, 0 },
640 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, .config.minmax = { 0, 3300 }, 0 },
641 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, .config.lookup = { TABLE_OFF_ON }, 0 },
642 { "current_meter_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.batteryConfig.currentMeterType, .config.lookup = { TABLE_CURRENT_SENSOR }, 0 },
644 { "align_gyro", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.gyro_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
645 { "align_acc", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.acc_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
646 { "align_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.sensorAlignmentConfig.mag_align, .config.lookup = { TABLE_ALIGNMENT }, 0 },
648 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDeciDegrees, .config.minmax = { -1800, 3600 }, 0 },
649 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDeciDegrees, .config.minmax = { -1800, 3600 }, 0 },
650 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDeciDegrees, .config.minmax = { -1800, 3600 }, 0 },
652 { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } },
653 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, .config.minmax = { 0, 128 }, 0 },
655 { "imu_dcm_kp", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp_acc, .config.minmax = { 0, 65535 }, 0 },
656 { "imu_dcm_ki", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki_acc, .config.minmax = { 0, 65535 }, 0 },
657 { "imu_dcm_kp_mag", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_kp_mag, .config.minmax = { 0, 65535 }, 0 },
658 { "imu_dcm_ki_mag", VAR_UINT16 | MASTER_VALUE, &masterConfig.dcm_ki_mag, .config.minmax = { 0, 65535 }, 0 },
660 { "deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.deadband, .config.minmax = { 0, 32 }, 0 },
661 { "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.yaw_deadband, .config.minmax = { 0, 100 }, 0 },
662 { "pos_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.profile[0].rcControlsConfig.pos_hold_deadband, .config.minmax = { 10, 250 }, 0 },
663 { "alt_hold_deadband", VAR_UINT8 | MASTER_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_deadband, .config.minmax = { 10, 250 }, 0 },
665 { "throttle_tilt_comp_str", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].throttle_tilt_compensation_strength, .config.minmax = { 0, 100 }, 0 },
667 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, .config.minmax = { -1, 1 }, 0 },
669 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, .config.minmax = { -1, 1 }, 0 },
670 { "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 }, 0 },
671 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX }, 0 },
673 #ifdef USE_SERVOS
674 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON }, 0 },
675 { "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, .config.minmax = { 10, 400}, 0 },
676 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.mixerConfig.servo_lowpass_enable, .config.lookup = { TABLE_OFF_ON }, 0 },
677 #endif
679 { "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, .config.minmax = { 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 }, 0 },
680 { "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, .config.minmax = { 0, 250 }, 0 },
681 { "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, .config.minmax = { 0, 100 }, 0 },
682 { "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, .config.minmax = { 0, 100 }, 0 },
683 { "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, .config.minmax = { 0, 100 }, 0 },
684 { "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, .config.minmax = { 0, 100 }, 0 },
685 { "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, 0 },
686 { "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], .config.minmax = { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX }, 0 },
687 { "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], .config.minmax = { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX }, 0 },
688 { "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, .config.minmax = { 0, CONTROL_RATE_CONFIG_TPA_MAX}, 0 },
689 { "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX}, 0 },
691 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, .config.minmax = { 0, 200 }, 0 },
692 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, .config.minmax = { 0, 200 }, 0 },
693 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, .config.minmax = { PWM_RANGE_MIN, PWM_RANGE_MAX }, 0 },
694 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_kill_switch, .config.lookup = { TABLE_OFF_ON }, 0 },
695 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, .config.minmax = { 0, 300 }, 0 },
696 { "failsafe_procedure", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.failsafeConfig.failsafe_procedure, .config.lookup = { TABLE_FAILSAFE_PROCEDURE }, 0 },
698 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 },
699 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, .config.minmax = { PWM_PULSE_MIN, PWM_PULSE_MAX }, 0 },
701 #ifdef USE_SERVOS
702 { "gimbal_mode", VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, &masterConfig.profile[0].gimbalConfig.mode, .config.lookup = { TABLE_GIMBAL_MODE }, 0 },
703 #endif
705 { "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_hardware, .config.minmax = { 0, ACC_MAX }, 0 },
707 { "baro_use_median_filter", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.barometerConfig.use_median_filtering, .config.lookup = { TABLE_OFF_ON }, 0 },
708 { "baro_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.baro_hardware, .config.minmax = { 0, BARO_MAX }, 0 },
710 { "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.mag_hardware, .config.minmax = { 0, MAG_MAX }, 0 },
711 { "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, .config.minmax = { -18000, 18000 }, 0 },
713 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 }, 0 },
714 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 }, 0 },
715 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], .config.minmax = { 0, 200 }, 0 },
716 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], .config.minmax = { 0, 200 }, 0 },
717 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], .config.minmax = { 0, 200 }, 0 },
718 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], .config.minmax = { 0, 200 }, 0 },
719 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], .config.minmax = { 0, 200 }, 0 },
720 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], .config.minmax = { 0, 200 }, 0 },
721 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], .config.minmax = { 0, 200 }, 0 },
723 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], .config.minmax = { 0, 255 }, 0 },
724 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], .config.minmax = { 0, 100 }, 0 },
725 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], .config.minmax = { 0, 100 }, 0 },
727 { "max_angle_inclination_rll", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.max_angle_inclination[FD_ROLL], .config.minmax = { 100, 900 }, 0 },
728 { "max_angle_inclination_pit", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.max_angle_inclination[FD_PITCH], .config.minmax = { 100, 900 }, 0 },
730 { "gyro_soft_lpf_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gyro_soft_lpf_hz, .config.minmax = {0, 200 } },
731 { "acc_soft_lpf_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.acc_soft_lpf_hz, .config.minmax = {0, 200 } },
732 { "dterm_lpf_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_lpf_hz, .config.minmax = {0, 200 } },
734 #ifdef BLACKBOX
735 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, .config.minmax = { 1, 32 }, 0 },
736 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, .config.minmax = { 1, 32 }, 0 },
737 { "blackbox_device", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.blackbox_device, .config.lookup = { TABLE_BLACKBOX_DEVICE }, 0 },
738 #endif
740 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], .config.minmax = { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE },
741 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], .config.minmax = { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE },
742 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], .config.minmax = { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE },
744 { "acczero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.accZero.raw[X], .config.minmax = { -32768, 32767 }, 0 },
745 { "acczero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.accZero.raw[Y], .config.minmax = { -32768, 32767 }, 0 },
746 { "acczero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.accZero.raw[Z], .config.minmax = { -32768, 32767 }, 0 },
748 { "accgain_x", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[X], .config.minmax = { 1, 8192 }, 0 },
749 { "accgain_y", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Y], .config.minmax = { 1, 8192 }, 0 },
750 { "accgain_z", VAR_INT16 | MASTER_VALUE, &masterConfig.accGain.raw[Z], .config.minmax = { 1, 8192 }, 0 },
753 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
756 typedef union {
757 int32_t int_value;
758 float float_value;
759 } int_float_value_t;
761 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
762 static void cliPrintVar(const clivalue_t *var, uint32_t full);
763 static void cliPrint(const char *str);
764 static void cliPrintf(const char *fmt, ...);
765 static void cliWrite(uint8_t ch);
767 static void cliPrompt(void)
769 cliPrint("\r\n# ");
770 bufWriterFlush(cliWriter);
773 static void cliShowParseError(void)
775 cliPrint("Parse error\r\n");
778 static void cliShowArgumentRangeError(char *name, int min, int max)
780 cliPrintf("%s must be between %d and %d\r\n", name, min, max);
783 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
785 int val;
787 for (int argIndex = 0; argIndex < 2; argIndex++) {
788 ptr = strchr(ptr, ' ');
789 if (ptr) {
790 val = atoi(++ptr);
791 val = CHANNEL_VALUE_TO_STEP(val);
792 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
793 if (argIndex == 0) {
794 range->startStep = val;
795 } else {
796 range->endStep = val;
798 (*validArgumentCount)++;
803 return ptr;
806 // Check if a string's length is zero
807 static bool isEmpty(const char *string)
809 return *string == '\0';
812 static void cliRxFail(char *cmdline)
814 uint8_t channel;
815 char buf[3];
817 if (isEmpty(cmdline)) {
818 // print out rxConfig failsafe settings
819 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
820 cliRxFail(itoa(channel, buf, 10));
822 } else {
823 char *ptr = cmdline;
824 channel = atoi(ptr++);
825 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
827 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
829 uint16_t value;
830 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
831 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
832 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
834 ptr = strchr(ptr, ' ');
835 if (ptr) {
836 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
837 if (p) {
838 uint8_t requestedMode = p - rxFailsafeModeCharacters;
839 mode = rxFailsafeModesTable[type][requestedMode];
840 } else {
841 mode = RX_FAILSAFE_MODE_INVALID;
843 if (mode == RX_FAILSAFE_MODE_INVALID) {
844 cliShowParseError();
845 return;
848 requireValue = mode == RX_FAILSAFE_MODE_SET;
850 ptr = strchr(ptr, ' ');
851 if (ptr) {
852 if (!requireValue) {
853 cliShowParseError();
854 return;
856 value = atoi(++ptr);
857 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
858 if (value > MAX_RXFAIL_RANGE_STEP) {
859 cliPrint("Value out of range\r\n");
860 return;
863 channelFailsafeConfiguration->step = value;
864 } else if (requireValue) {
865 cliShowParseError();
866 return;
868 channelFailsafeConfiguration->mode = mode;
872 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
874 // triple use of cliPrintf below
875 // 1. acknowledge interpretation on command,
876 // 2. query current setting on single item,
877 // 3. recursive use for full list.
879 if (requireValue) {
880 cliPrintf("rxfail %u %c %d\r\n",
881 channel,
882 modeCharacter,
883 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
885 } else {
886 cliPrintf("rxfail %u %c\r\n",
887 channel,
888 modeCharacter
891 } else {
892 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
897 static void cliAux(char *cmdline)
899 int i, val = 0;
900 char *ptr;
902 if (isEmpty(cmdline)) {
903 // print out aux channel settings
904 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
905 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
906 cliPrintf("aux %u %u %u %u %u\r\n",
908 mac->modeId,
909 mac->auxChannelIndex,
910 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
911 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
914 } else {
915 ptr = cmdline;
916 i = atoi(ptr++);
917 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
918 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
919 uint8_t validArgumentCount = 0;
920 ptr = strchr(ptr, ' ');
921 if (ptr) {
922 val = atoi(++ptr);
923 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
924 mac->modeId = val;
925 validArgumentCount++;
928 ptr = strchr(ptr, ' ');
929 if (ptr) {
930 val = atoi(++ptr);
931 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
932 mac->auxChannelIndex = val;
933 validArgumentCount++;
936 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
938 if (validArgumentCount != 4) {
939 memset(mac, 0, sizeof(modeActivationCondition_t));
941 } else {
942 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
947 static void cliSerial(char *cmdline)
949 int i, val;
950 char *ptr;
952 if (isEmpty(cmdline)) {
953 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
954 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
955 continue;
957 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
958 masterConfig.serialConfig.portConfigs[i].identifier,
959 masterConfig.serialConfig.portConfigs[i].functionMask,
960 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
961 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
962 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
963 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
966 return;
969 serialPortConfig_t portConfig;
970 memset(&portConfig, 0 , sizeof(portConfig));
972 serialPortConfig_t *currentConfig;
974 uint8_t validArgumentCount = 0;
976 ptr = cmdline;
978 val = atoi(ptr++);
979 currentConfig = serialFindPortConfiguration(val);
980 if (currentConfig) {
981 portConfig.identifier = val;
982 validArgumentCount++;
985 ptr = strchr(ptr, ' ');
986 if (ptr) {
987 val = atoi(++ptr);
988 portConfig.functionMask = val & 0xFFFF;
989 validArgumentCount++;
992 for (i = 0; i < 4; i ++) {
993 ptr = strchr(ptr, ' ');
994 if (!ptr) {
995 break;
998 val = atoi(++ptr);
1000 uint8_t baudRateIndex = lookupBaudRateIndex(val);
1001 if (baudRates[baudRateIndex] != (uint32_t) val) {
1002 break;
1005 switch(i) {
1006 case 0:
1007 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1008 continue;
1010 portConfig.msp_baudrateIndex = baudRateIndex;
1011 break;
1012 case 1:
1013 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
1014 continue;
1016 portConfig.gps_baudrateIndex = baudRateIndex;
1017 break;
1018 case 2:
1019 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
1020 continue;
1022 portConfig.telemetry_baudrateIndex = baudRateIndex;
1023 break;
1024 case 3:
1025 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
1026 continue;
1028 portConfig.blackbox_baudrateIndex = baudRateIndex;
1029 break;
1032 validArgumentCount++;
1035 if (validArgumentCount < 6) {
1036 cliShowParseError();
1037 return;
1040 memcpy(currentConfig, &portConfig, sizeof(portConfig));
1044 static void cliAdjustmentRange(char *cmdline)
1046 int i, val = 0;
1047 char *ptr;
1049 if (isEmpty(cmdline)) {
1050 // print out adjustment ranges channel settings
1051 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
1052 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
1053 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1055 ar->adjustmentIndex,
1056 ar->auxChannelIndex,
1057 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
1058 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
1059 ar->adjustmentFunction,
1060 ar->auxSwitchChannelIndex
1063 } else {
1064 ptr = cmdline;
1065 i = atoi(ptr++);
1066 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
1067 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
1068 uint8_t validArgumentCount = 0;
1070 ptr = strchr(ptr, ' ');
1071 if (ptr) {
1072 val = atoi(++ptr);
1073 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
1074 ar->adjustmentIndex = val;
1075 validArgumentCount++;
1078 ptr = strchr(ptr, ' ');
1079 if (ptr) {
1080 val = atoi(++ptr);
1081 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1082 ar->auxChannelIndex = val;
1083 validArgumentCount++;
1087 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
1089 ptr = strchr(ptr, ' ');
1090 if (ptr) {
1091 val = atoi(++ptr);
1092 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
1093 ar->adjustmentFunction = val;
1094 validArgumentCount++;
1097 ptr = strchr(ptr, ' ');
1098 if (ptr) {
1099 val = atoi(++ptr);
1100 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
1101 ar->auxSwitchChannelIndex = val;
1102 validArgumentCount++;
1106 if (validArgumentCount != 6) {
1107 memset(ar, 0, sizeof(adjustmentRange_t));
1108 cliShowParseError();
1110 } else {
1111 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
1116 static void cliMotorMix(char *cmdline)
1118 #ifdef USE_QUAD_MIXER_ONLY
1119 UNUSED(cmdline);
1120 #else
1121 int i, check = 0;
1122 int num_motors = 0;
1123 uint8_t len;
1124 char ftoaBuffer[FTOA_BUFFER_SIZE];
1125 char *ptr;
1127 if (isEmpty(cmdline)) {
1128 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1129 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1130 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1131 break;
1132 num_motors++;
1133 cliPrintf("#%d:\t", i);
1134 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, ftoaBuffer));
1135 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, ftoaBuffer));
1136 cliPrintf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, ftoaBuffer));
1137 cliPrintf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, ftoaBuffer));
1139 return;
1140 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1141 // erase custom mixer
1142 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
1143 masterConfig.customMotorMixer[i].throttle = 0.0f;
1144 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1145 ptr = strchr(cmdline, ' ');
1146 if (ptr) {
1147 len = strlen(++ptr);
1148 for (i = 0; ; i++) {
1149 if (mixerNames[i] == NULL) {
1150 cliPrint("Invalid name\r\n");
1151 break;
1153 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1154 mixerLoadMix(i, masterConfig.customMotorMixer);
1155 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1156 cliMotorMix("");
1157 break;
1161 } else {
1162 ptr = cmdline;
1163 i = atoi(ptr); // get motor number
1164 if (i < MAX_SUPPORTED_MOTORS) {
1165 ptr = strchr(ptr, ' ');
1166 if (ptr) {
1167 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
1168 check++;
1170 ptr = strchr(ptr, ' ');
1171 if (ptr) {
1172 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
1173 check++;
1175 ptr = strchr(ptr, ' ');
1176 if (ptr) {
1177 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
1178 check++;
1180 ptr = strchr(ptr, ' ');
1181 if (ptr) {
1182 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
1183 check++;
1185 if (check != 4) {
1186 cliShowParseError();
1187 } else {
1188 cliMotorMix("");
1190 } else {
1191 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
1194 #endif
1197 static void cliRxRange(char *cmdline)
1199 int i, validArgumentCount = 0;
1200 char *ptr;
1202 if (isEmpty(cmdline)) {
1203 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
1204 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1205 cliPrintf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
1207 } else if (strcasecmp(cmdline, "reset") == 0) {
1208 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
1209 } else {
1210 ptr = cmdline;
1211 i = atoi(ptr);
1212 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
1213 int rangeMin, rangeMax;
1215 ptr = strchr(ptr, ' ');
1216 if (ptr) {
1217 rangeMin = atoi(++ptr);
1218 validArgumentCount++;
1221 ptr = strchr(ptr, ' ');
1222 if (ptr) {
1223 rangeMax = atoi(++ptr);
1224 validArgumentCount++;
1227 if (validArgumentCount != 2) {
1228 cliShowParseError();
1229 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1230 cliShowParseError();
1231 } else {
1232 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1233 channelRangeConfiguration->min = rangeMin;
1234 channelRangeConfiguration->max = rangeMax;
1236 } else {
1237 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1242 #ifdef LED_STRIP
1243 static void cliLed(char *cmdline)
1245 int i;
1246 char *ptr;
1247 char ledConfigBuffer[20];
1249 if (isEmpty(cmdline)) {
1250 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1251 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1252 cliPrintf("led %u %s\r\n", i, ledConfigBuffer);
1254 } else {
1255 ptr = cmdline;
1256 i = atoi(ptr);
1257 if (i < MAX_LED_STRIP_LENGTH) {
1258 ptr = strchr(cmdline, ' ');
1259 if (!parseLedStripConfig(i, ++ptr)) {
1260 cliShowParseError();
1262 } else {
1263 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1268 static void cliColor(char *cmdline)
1270 int i;
1271 char *ptr;
1273 if (isEmpty(cmdline)) {
1274 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1275 cliPrintf("color %u %d,%u,%u\r\n",
1277 masterConfig.colors[i].h,
1278 masterConfig.colors[i].s,
1279 masterConfig.colors[i].v
1282 } else {
1283 ptr = cmdline;
1284 i = atoi(ptr);
1285 if (i < CONFIGURABLE_COLOR_COUNT) {
1286 ptr = strchr(cmdline, ' ');
1287 if (!parseColor(i, ++ptr)) {
1288 cliShowParseError();
1290 } else {
1291 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1295 #endif
1297 #ifdef USE_SERVOS
1298 static void cliServo(char *cmdline)
1300 enum { SERVO_ARGUMENT_COUNT = 8 };
1301 int16_t arguments[SERVO_ARGUMENT_COUNT];
1303 servoParam_t *servo;
1305 int i;
1306 char *ptr;
1308 if (isEmpty(cmdline)) {
1309 // print out servo settings
1310 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1311 servo = &currentProfile->servoConf[i];
1313 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1315 servo->min,
1316 servo->max,
1317 servo->middle,
1318 servo->angleAtMin,
1319 servo->angleAtMax,
1320 servo->rate,
1321 servo->forwardFromChannel
1324 } else {
1325 int validArgumentCount = 0;
1327 ptr = cmdline;
1329 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1331 // If command line doesn't fit the format, don't modify the config
1332 while (*ptr) {
1333 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1334 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1335 cliShowParseError();
1336 return;
1339 arguments[validArgumentCount++] = atoi(ptr);
1341 do {
1342 ptr++;
1343 } while (*ptr >= '0' && *ptr <= '9');
1344 } else if (*ptr == ' ') {
1345 ptr++;
1346 } else {
1347 cliShowParseError();
1348 return;
1352 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1354 i = arguments[INDEX];
1356 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1357 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1358 cliShowParseError();
1359 return;
1362 servo = &currentProfile->servoConf[i];
1364 if (
1365 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1366 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1367 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1368 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1369 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1370 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1371 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1372 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1374 cliShowParseError();
1375 return;
1378 servo->min = arguments[1];
1379 servo->max = arguments[2];
1380 servo->middle = arguments[3];
1381 servo->angleAtMin = arguments[4];
1382 servo->angleAtMax = arguments[5];
1383 servo->rate = arguments[6];
1384 servo->forwardFromChannel = arguments[7];
1387 #endif
1389 #ifdef USE_SERVOS
1390 static void cliServoMix(char *cmdline)
1392 int i;
1393 uint8_t len;
1394 char *ptr;
1395 int args[8], check = 0;
1396 len = strlen(cmdline);
1398 if (len == 0) {
1400 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1402 for (i = 0; i < MAX_SERVO_RULES; i++) {
1403 if (masterConfig.customServoMixer[i].rate == 0)
1404 break;
1406 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1408 masterConfig.customServoMixer[i].targetChannel,
1409 masterConfig.customServoMixer[i].inputSource,
1410 masterConfig.customServoMixer[i].rate,
1411 masterConfig.customServoMixer[i].speed,
1412 masterConfig.customServoMixer[i].min,
1413 masterConfig.customServoMixer[i].max,
1414 masterConfig.customServoMixer[i].box
1417 cliPrintf("\r\n");
1418 return;
1419 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1420 // erase custom mixer
1421 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1422 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1423 currentProfile->servoConf[i].reversedSources = 0;
1425 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1426 ptr = strchr(cmdline, ' ');
1427 if (ptr) {
1428 len = strlen(++ptr);
1429 for (i = 0; ; i++) {
1430 if (mixerNames[i] == NULL) {
1431 cliPrintf("Invalid name\r\n");
1432 break;
1434 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1435 servoMixerLoadMix(i, masterConfig.customServoMixer);
1436 cliPrintf("Loaded %s\r\n", mixerNames[i]);
1437 cliServoMix("");
1438 break;
1442 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1443 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1444 int servoIndex, inputSource;
1445 ptr = strchr(cmdline, ' ');
1447 len = strlen(ptr);
1448 if (len == 0) {
1449 cliPrintf("s");
1450 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1451 cliPrintf("\ti%d", inputSource);
1452 cliPrintf("\r\n");
1454 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1455 cliPrintf("%d", servoIndex);
1456 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1457 cliPrintf("\t%s ", (currentProfile->servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1458 cliPrintf("\r\n");
1460 return;
1463 ptr = strtok(ptr, " ");
1464 while (ptr != NULL && check < ARGS_COUNT - 1) {
1465 args[check++] = atoi(ptr);
1466 ptr = strtok(NULL, " ");
1469 if (ptr == NULL || check != ARGS_COUNT - 1) {
1470 cliShowParseError();
1471 return;
1474 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1475 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1476 && (*ptr == 'r' || *ptr == 'n')) {
1477 if (*ptr == 'r')
1478 currentProfile->servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1479 else
1480 currentProfile->servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1481 } else
1482 cliShowParseError();
1484 cliServoMix("reverse");
1485 } else {
1486 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1487 ptr = strtok(cmdline, " ");
1488 while (ptr != NULL && check < ARGS_COUNT) {
1489 args[check++] = atoi(ptr);
1490 ptr = strtok(NULL, " ");
1493 if (ptr != NULL || check != ARGS_COUNT) {
1494 cliShowParseError();
1495 return;
1498 i = args[RULE];
1499 if (i >= 0 && i < MAX_SERVO_RULES &&
1500 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1501 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1502 args[RATE] >= -100 && args[RATE] <= 100 &&
1503 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1504 args[MIN] >= 0 && args[MIN] <= 100 &&
1505 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1506 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1507 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1508 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1509 masterConfig.customServoMixer[i].rate = args[RATE];
1510 masterConfig.customServoMixer[i].speed = args[SPEED];
1511 masterConfig.customServoMixer[i].min = args[MIN];
1512 masterConfig.customServoMixer[i].max = args[MAX];
1513 masterConfig.customServoMixer[i].box = args[BOX];
1514 cliServoMix("");
1515 } else {
1516 cliShowParseError();
1520 #endif
1523 #ifdef USE_FLASHFS
1525 static void cliFlashInfo(char *cmdline)
1527 const flashGeometry_t *layout = flashfsGetGeometry();
1529 UNUSED(cmdline);
1531 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1532 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1535 static void cliFlashErase(char *cmdline)
1537 UNUSED(cmdline);
1539 cliPrintf("Erasing...\r\n");
1540 flashfsEraseCompletely();
1542 while (!flashfsIsReady()) {
1543 delay(100);
1546 cliPrintf("Done.\r\n");
1549 #ifdef USE_FLASH_TOOLS
1551 static void cliFlashWrite(char *cmdline)
1553 uint32_t address = atoi(cmdline);
1554 char *text = strchr(cmdline, ' ');
1556 if (!text) {
1557 cliShowParseError();
1558 } else {
1559 flashfsSeekAbs(address);
1560 flashfsWrite((uint8_t*)text, strlen(text), true);
1561 flashfsFlushSync();
1563 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1567 static void cliFlashRead(char *cmdline)
1569 uint32_t address = atoi(cmdline);
1570 uint32_t length;
1571 int i;
1573 uint8_t buffer[32];
1575 char *nextArg = strchr(cmdline, ' ');
1577 if (!nextArg) {
1578 cliShowParseError();
1579 } else {
1580 length = atoi(nextArg);
1582 cliPrintf("Reading %u bytes at %u:\r\n", length, address);
1584 while (length > 0) {
1585 int bytesRead;
1587 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1589 for (i = 0; i < bytesRead; i++) {
1590 cliWrite(buffer[i]);
1593 length -= bytesRead;
1594 address += bytesRead;
1596 if (bytesRead == 0) {
1597 //Assume we reached the end of the volume or something fatal happened
1598 break;
1601 cliPrintf("\r\n");
1605 #endif
1606 #endif
1608 static void dumpValues(uint16_t valueSection)
1610 uint32_t i;
1611 const clivalue_t *value;
1612 for (i = 0; i < VALUE_COUNT; i++) {
1613 value = &valueTable[i];
1615 if ((value->type & VALUE_SECTION_MASK) != valueSection) {
1616 continue;
1619 cliPrintf("set %s = ", valueTable[i].name);
1620 cliPrintVar(value, 0);
1621 cliPrint("\r\n");
1625 typedef enum {
1626 DUMP_MASTER = (1 << 0),
1627 DUMP_PROFILE = (1 << 1),
1628 DUMP_CONTROL_RATE_PROFILE = (1 << 2)
1629 } dumpFlags_e;
1631 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
1634 static const char* const sectionBreak = "\r\n";
1636 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1638 static void cliDump(char *cmdline)
1640 unsigned int i;
1641 char buf[16];
1642 uint32_t mask;
1644 #ifndef USE_QUAD_MIXER_ONLY
1645 float thr, roll, pitch, yaw;
1646 #endif
1648 uint8_t dumpMask = DUMP_ALL;
1649 if (strcasecmp(cmdline, "master") == 0) {
1650 dumpMask = DUMP_MASTER; // only
1652 if (strcasecmp(cmdline, "profile") == 0) {
1653 dumpMask = DUMP_PROFILE; // only
1655 if (strcasecmp(cmdline, "rates") == 0) {
1656 dumpMask = DUMP_CONTROL_RATE_PROFILE; // only
1659 if (dumpMask & DUMP_MASTER) {
1661 cliPrint("\r\n# version\r\n");
1662 cliVersion(NULL);
1664 cliPrint("\r\n# pflags\r\n");
1665 cliPFlags("");
1667 cliPrint("\r\n# dump master\r\n");
1668 cliPrint("\r\n# mixer\r\n");
1670 #ifndef USE_QUAD_MIXER_ONLY
1671 cliPrintf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1673 cliPrintf("mmix reset\r\n");
1675 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1676 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1677 break;
1678 thr = masterConfig.customMotorMixer[i].throttle;
1679 roll = masterConfig.customMotorMixer[i].roll;
1680 pitch = masterConfig.customMotorMixer[i].pitch;
1681 yaw = masterConfig.customMotorMixer[i].yaw;
1682 cliPrintf("mmix %d", i);
1683 if (thr < 0)
1684 cliWrite(' ');
1685 cliPrintf("%s", ftoa(thr, buf));
1686 if (roll < 0)
1687 cliWrite(' ');
1688 cliPrintf("%s", ftoa(roll, buf));
1689 if (pitch < 0)
1690 cliWrite(' ');
1691 cliPrintf("%s", ftoa(pitch, buf));
1692 if (yaw < 0)
1693 cliWrite(' ');
1694 cliPrintf("%s\r\n", ftoa(yaw, buf));
1697 // print custom servo mixer if exists
1698 cliPrintf("smix reset\r\n");
1700 for (i = 0; i < MAX_SERVO_RULES; i++) {
1702 if (masterConfig.customServoMixer[i].rate == 0)
1703 break;
1705 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1707 masterConfig.customServoMixer[i].targetChannel,
1708 masterConfig.customServoMixer[i].inputSource,
1709 masterConfig.customServoMixer[i].rate,
1710 masterConfig.customServoMixer[i].speed,
1711 masterConfig.customServoMixer[i].min,
1712 masterConfig.customServoMixer[i].max,
1713 masterConfig.customServoMixer[i].box
1717 #endif
1719 cliPrint("\r\n\r\n# feature\r\n");
1721 mask = featureMask();
1722 for (i = 0; ; i++) { // disable all feature first
1723 if (featureNames[i] == NULL)
1724 break;
1725 cliPrintf("feature -%s\r\n", featureNames[i]);
1727 for (i = 0; ; i++) { // reenable what we want.
1728 if (featureNames[i] == NULL)
1729 break;
1730 if (mask & (1 << i))
1731 cliPrintf("feature %s\r\n", featureNames[i]);
1735 #ifdef BEEPER
1736 cliPrint("\r\n\r\n# beeper\r\n");
1738 uint8_t beeperCount = beeperTableEntryCount();
1739 mask = getBeeperOffMask();
1740 for (int i = 0; i < (beeperCount-2); i++) {
1741 if (mask & (1 << i))
1742 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i));
1743 else
1744 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i));
1746 #endif
1749 cliPrint("\r\n\r\n# map\r\n");
1751 for (i = 0; i < 8; i++)
1752 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1753 buf[i] = '\0';
1754 cliPrintf("map %s\r\n", buf);
1756 cliPrint("\r\n\r\n# serial\r\n");
1757 cliSerial("");
1759 #ifdef LED_STRIP
1760 cliPrint("\r\n\r\n# led\r\n");
1761 cliLed("");
1763 cliPrint("\r\n\r\n# color\r\n");
1764 cliColor("");
1765 #endif
1766 printSectionBreak();
1767 dumpValues(MASTER_VALUE);
1769 cliPrint("\r\n# rxfail\r\n");
1770 cliRxFail("");
1773 if (dumpMask & DUMP_PROFILE) {
1774 cliPrint("\r\n# dump profile\r\n");
1776 cliPrint("\r\n# profile\r\n");
1777 cliProfile("");
1779 cliPrint("\r\n# aux\r\n");
1781 cliAux("");
1783 cliPrint("\r\n# adjrange\r\n");
1785 cliAdjustmentRange("");
1787 cliPrintf("\r\n# rxrange\r\n");
1789 cliRxRange("");
1791 #ifdef USE_SERVOS
1792 cliPrint("\r\n# servo\r\n");
1794 cliServo("");
1796 // print servo directions
1797 unsigned int channel;
1799 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1800 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
1801 if (servoDirection(i, channel) < 0) {
1802 cliPrintf("smix reverse %d %d r\r\n", i , channel);
1806 #endif
1808 printSectionBreak();
1810 dumpValues(PROFILE_VALUE);
1813 if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
1814 cliPrint("\r\n# dump rates\r\n");
1816 cliPrint("\r\n# rateprofile\r\n");
1817 cliRateProfile("");
1819 printSectionBreak();
1821 dumpValues(CONTROL_RATE_VALUE);
1825 void cliEnter(serialPort_t *serialPort)
1827 cliMode = 1;
1828 cliPort = serialPort;
1829 setPrintfSerialPort(cliPort);
1830 cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer),
1831 (bufWrite_t)serialWriteBufShim, serialPort);
1833 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1834 cliPrompt();
1835 ENABLE_ARMING_FLAG(PREVENT_ARMING);
1838 static void cliExit(char *cmdline)
1840 UNUSED(cmdline);
1842 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1843 bufWriterFlush(cliWriter);
1845 *cliBuffer = '\0';
1846 bufferIndex = 0;
1847 cliMode = 0;
1848 // incase a motor was left running during motortest, clear it here
1849 mixerResetDisarmedMotors();
1850 cliReboot();
1852 cliWriter = NULL;
1855 static void cliFeature(char *cmdline)
1857 uint32_t i;
1858 uint32_t len;
1859 uint32_t mask;
1861 len = strlen(cmdline);
1862 mask = featureMask();
1864 if (len == 0) {
1865 cliPrint("Enabled: ");
1866 for (i = 0; ; i++) {
1867 if (featureNames[i] == NULL)
1868 break;
1869 if (mask & (1 << i))
1870 cliPrintf("%s ", featureNames[i]);
1872 cliPrint("\r\n");
1873 } else if (strncasecmp(cmdline, "list", len) == 0) {
1874 cliPrint("Available: ");
1875 for (i = 0; ; i++) {
1876 if (featureNames[i] == NULL)
1877 break;
1878 cliPrintf("%s ", featureNames[i]);
1880 cliPrint("\r\n");
1881 return;
1882 } else {
1883 bool remove = false;
1884 if (cmdline[0] == '-') {
1885 // remove feature
1886 remove = true;
1887 cmdline++; // skip over -
1888 len--;
1891 for (i = 0; ; i++) {
1892 if (featureNames[i] == NULL) {
1893 cliPrint("Invalid name\r\n");
1894 break;
1897 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
1899 mask = 1 << i;
1900 #ifndef GPS
1901 if (mask & FEATURE_GPS) {
1902 cliPrint("unavailable\r\n");
1903 break;
1905 #endif
1906 #ifndef SONAR
1907 if (mask & FEATURE_SONAR) {
1908 cliPrint("unavailable\r\n");
1909 break;
1911 #endif
1912 if (remove) {
1913 featureClear(mask);
1914 cliPrint("Disabled");
1915 } else {
1916 featureSet(mask);
1917 cliPrint("Enabled");
1919 cliPrintf(" %s\r\n", featureNames[i]);
1920 break;
1926 #ifdef BEEPER
1927 static void cliBeeper(char *cmdline)
1929 uint32_t i;
1930 uint32_t len = strlen(cmdline);;
1931 uint8_t beeperCount = beeperTableEntryCount();
1932 uint32_t mask = getBeeperOffMask();
1934 if (len == 0) {
1935 cliPrintf("Disabled:");
1936 for (int i = 0; ; i++) {
1937 if (i == beeperCount-2){
1938 if (mask == 0)
1939 cliPrint(" none");
1940 break;
1942 if (mask & (1 << i))
1943 cliPrintf(" %s", beeperNameForTableIndex(i));
1945 cliPrint("\r\n");
1946 } else if (strncasecmp(cmdline, "list", len) == 0) {
1947 cliPrint("Available:");
1948 for (i = 0; i < beeperCount; i++)
1949 cliPrintf(" %s", beeperNameForTableIndex(i));
1950 cliPrint("\r\n");
1951 return;
1952 } else {
1953 bool remove = false;
1954 if (cmdline[0] == '-') {
1955 remove = true; // this is for beeper OFF condition
1956 cmdline++;
1957 len--;
1960 for (i = 0; ; i++) {
1961 if (i == beeperCount) {
1962 cliPrint("Invalid name\r\n");
1963 break;
1965 if (strncasecmp(cmdline, beeperNameForTableIndex(i), len) == 0) {
1966 if (remove) { // beeper off
1967 if (i == BEEPER_ALL-1)
1968 beeperOffSetAll(beeperCount-2);
1969 else
1970 if (i == BEEPER_PREFERENCE-1)
1971 setBeeperOffMask(getPreferedBeeperOffMask());
1972 else {
1973 mask = 1 << i;
1974 beeperOffSet(mask);
1976 cliPrint("Disabled");
1978 else { // beeper on
1979 if (i == BEEPER_ALL-1)
1980 beeperOffClearAll();
1981 else
1982 if (i == BEEPER_PREFERENCE-1)
1983 setPreferedBeeperOffMask(getBeeperOffMask());
1984 else {
1985 mask = 1 << i;
1986 beeperOffClear(mask);
1988 cliPrint("Enabled");
1990 cliPrintf(" %s\r\n", beeperNameForTableIndex(i));
1991 break;
1996 #endif
1999 #ifdef GPS
2000 static void cliGpsPassthrough(char *cmdline)
2002 UNUSED(cmdline);
2004 gpsEnablePassthrough(cliPort);
2006 #endif
2008 static void cliHelp(char *cmdline)
2010 uint32_t i = 0;
2012 UNUSED(cmdline);
2014 for (i = 0; i < CMD_COUNT; i++) {
2015 cliPrint(cmdTable[i].name);
2016 #ifndef SKIP_CLI_COMMAND_HELP
2017 if (cmdTable[i].description) {
2018 cliPrintf(" - %s", cmdTable[i].description);
2020 if (cmdTable[i].args) {
2021 cliPrintf("\r\n\t%s", cmdTable[i].args);
2023 #endif
2024 cliPrint("\r\n");
2028 static void cliMap(char *cmdline)
2030 uint32_t len;
2031 uint32_t i;
2032 char out[9];
2034 len = strlen(cmdline);
2036 if (len == 8) {
2037 // uppercase it
2038 for (i = 0; i < 8; i++)
2039 cmdline[i] = toupper((unsigned char)cmdline[i]);
2040 for (i = 0; i < 8; i++) {
2041 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
2042 continue;
2043 cliShowParseError();
2044 return;
2046 parseRcChannels(cmdline, &masterConfig.rxConfig);
2048 cliPrint("Map: ");
2049 for (i = 0; i < 8; i++)
2050 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
2051 out[i] = '\0';
2052 cliPrintf("%s\r\n", out);
2055 #ifndef USE_QUAD_MIXER_ONLY
2056 static void cliMixer(char *cmdline)
2058 int i;
2059 int len;
2061 len = strlen(cmdline);
2063 if (len == 0) {
2064 cliPrintf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
2065 return;
2066 } else if (strncasecmp(cmdline, "list", len) == 0) {
2067 cliPrint("Available mixers: ");
2068 for (i = 0; ; i++) {
2069 if (mixerNames[i] == NULL)
2070 break;
2071 cliPrintf("%s ", mixerNames[i]);
2073 cliPrint("\r\n");
2074 return;
2077 for (i = 0; ; i++) {
2078 if (mixerNames[i] == NULL) {
2079 cliPrint("Invalid name\r\n");
2080 return;
2082 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
2083 masterConfig.mixerMode = i + 1;
2084 break;
2088 cliMixer("");
2090 #endif
2092 static void cliMotor(char *cmdline)
2094 int motor_index = 0;
2095 int motor_value = 0;
2096 int index = 0;
2097 char *pch = NULL;
2098 char *saveptr;
2100 if (isEmpty(cmdline)) {
2101 cliShowParseError();
2102 return;
2105 pch = strtok_r(cmdline, " ", &saveptr);
2106 while (pch != NULL) {
2107 switch (index) {
2108 case 0:
2109 motor_index = atoi(pch);
2110 break;
2111 case 1:
2112 motor_value = atoi(pch);
2113 break;
2115 index++;
2116 pch = strtok_r(NULL, " ", &saveptr);
2119 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
2120 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS - 1);
2121 return;
2124 if (index == 2) {
2125 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
2126 cliShowArgumentRangeError("value", 1000, 2000);
2127 return;
2128 } else {
2129 motor_disarmed[motor_index] = motor_value;
2133 cliPrintf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
2136 static void cliPlaySound(char *cmdline)
2138 #if FLASH_SIZE <= 64
2139 UNUSED(cmdline);
2140 #else
2141 int i;
2142 const char *name;
2143 static int lastSoundIdx = -1;
2145 if (isEmpty(cmdline)) {
2146 i = lastSoundIdx + 1; //next sound index
2147 if ((name=beeperNameForTableIndex(i)) == NULL) {
2148 while (true) { //no name for index; try next one
2149 if (++i >= beeperTableEntryCount())
2150 i = 0; //if end then wrap around to first entry
2151 if ((name=beeperNameForTableIndex(i)) != NULL)
2152 break; //if name OK then play sound below
2153 if (i == lastSoundIdx + 1) { //prevent infinite loop
2154 cliPrintf("Error playing sound\r\n");
2155 return;
2159 } else { //index value was given
2160 i = atoi(cmdline);
2161 if ((name=beeperNameForTableIndex(i)) == NULL) {
2162 cliPrintf("No sound for index %d\r\n", i);
2163 return;
2166 lastSoundIdx = i;
2167 beeperSilence();
2168 cliPrintf("Playing sound %d: %s\r\n", i, name);
2169 beeper(beeperModeForTableIndex(i));
2170 #endif
2173 static void cliProfile(char *cmdline)
2175 int i;
2177 if (isEmpty(cmdline)) {
2178 cliPrintf("profile %d\r\n", getCurrentProfile());
2179 return;
2180 } else {
2181 i = atoi(cmdline);
2182 if (i >= 0 && i < MAX_PROFILE_COUNT) {
2183 masterConfig.current_profile_index = i;
2184 writeEEPROM();
2185 readEEPROM();
2186 cliProfile("");
2191 static void cliRateProfile(char *cmdline)
2193 int i;
2195 if (isEmpty(cmdline)) {
2196 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2197 return;
2198 } else {
2199 i = atoi(cmdline);
2200 if (i >= 0 && i < MAX_CONTROL_RATE_PROFILE_COUNT) {
2201 changeControlRateProfile(i);
2202 cliRateProfile("");
2207 static void cliReboot(void) {
2208 cliPrint("\r\nRebooting");
2209 bufWriterFlush(cliWriter);
2210 waitForSerialPortToFinishTransmitting(cliPort);
2211 stopMotors();
2212 handleOneshotFeatureChangeOnRestart();
2213 systemReset();
2216 static void cliSave(char *cmdline)
2218 UNUSED(cmdline);
2220 cliPrint("Saving");
2221 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2222 writeEEPROM();
2223 cliReboot();
2226 static void cliDefaults(char *cmdline)
2228 UNUSED(cmdline);
2230 cliPrint("Resetting to defaults");
2231 resetEEPROM();
2232 cliReboot();
2235 static void cliPrint(const char *str)
2237 while (*str)
2238 bufWriterAppend(cliWriter, *str++);
2241 static void cliPutp(void *p, char ch)
2243 bufWriterAppend(p, ch);
2246 static void cliPrintf(const char *fmt, ...)
2248 va_list va;
2249 va_start(va, fmt);
2250 tfp_format(cliWriter, cliPutp, fmt, va);
2251 va_end(va);
2254 static void cliWrite(uint8_t ch)
2256 bufWriterAppend(cliWriter, ch);
2259 static void cliPrintVar(const clivalue_t *var, uint32_t full)
2261 int32_t value = 0;
2262 char ftoaBuffer[FTOA_BUFFER_SIZE];
2264 void *ptr = var->ptr;
2265 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2266 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2268 if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
2269 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2272 switch (var->type & VALUE_TYPE_MASK) {
2273 case VAR_UINT8:
2274 value = *(uint8_t *)ptr;
2275 break;
2277 case VAR_INT8:
2278 value = *(int8_t *)ptr;
2279 break;
2281 case VAR_UINT16:
2282 value = *(uint16_t *)ptr;
2283 break;
2285 case VAR_INT16:
2286 value = *(int16_t *)ptr;
2287 break;
2289 case VAR_UINT32:
2290 value = *(uint32_t *)ptr;
2291 break;
2293 case VAR_FLOAT:
2294 cliPrintf("%s", ftoa(*(float *)ptr, ftoaBuffer));
2295 if (full && (var->type & VALUE_MODE_MASK) == MODE_DIRECT) {
2296 cliPrintf(" %s", ftoa((float)var->config.minmax.min, ftoaBuffer));
2297 cliPrintf(" %s", ftoa((float)var->config.minmax.max, ftoaBuffer));
2299 return; // return from case for float only
2302 switch(var->type & VALUE_MODE_MASK) {
2303 case MODE_DIRECT:
2304 cliPrintf("%d", value);
2305 if (full) {
2306 cliPrintf(" %d %d", var->config.minmax.min, var->config.minmax.max);
2308 break;
2309 case MODE_LOOKUP:
2310 cliPrintf(lookupTables[var->config.lookup.tableIndex].values[value]);
2311 break;
2315 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
2317 void *ptr = var->ptr;
2318 if ((var->type & VALUE_SECTION_MASK) == PROFILE_VALUE) {
2319 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
2321 if ((var->type & VALUE_SECTION_MASK) == CONTROL_RATE_VALUE) {
2322 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
2325 switch (var->type & VALUE_TYPE_MASK) {
2326 case VAR_UINT8:
2327 case VAR_INT8:
2328 *(int8_t *)ptr = value.int_value;
2329 break;
2331 case VAR_UINT16:
2332 case VAR_INT16:
2333 *(int16_t *)ptr = value.int_value;
2334 break;
2336 case VAR_UINT32:
2337 *(uint32_t *)ptr = value.int_value;
2338 break;
2340 case VAR_FLOAT:
2341 *(float *)ptr = (float)value.float_value;
2342 break;
2345 if (var->pflags_to_set) {
2346 persistentFlagSet(var->pflags_to_set);
2350 static void cliSet(char *cmdline)
2352 uint32_t i;
2353 uint32_t len;
2354 const clivalue_t *val;
2355 char *eqptr = NULL;
2357 len = strlen(cmdline);
2359 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2360 cliPrint("Current settings: \r\n");
2361 for (i = 0; i < VALUE_COUNT; i++) {
2362 val = &valueTable[i];
2363 cliPrintf("%s = ", valueTable[i].name);
2364 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2365 cliPrint("\r\n");
2367 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2368 // has equals
2370 char *lastNonSpaceCharacter = eqptr;
2371 while (*(lastNonSpaceCharacter - 1) == ' ') {
2372 lastNonSpaceCharacter--;
2374 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2376 // skip the '=' and any ' ' characters
2377 eqptr++;
2378 while (*(eqptr) == ' ') {
2379 eqptr++;
2382 for (i = 0; i < VALUE_COUNT; i++) {
2383 val = &valueTable[i];
2384 // ensure exact match when setting to prevent setting variables with shorter names
2385 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2387 bool changeValue = false;
2388 int_float_value_t tmp;
2389 switch (valueTable[i].type & VALUE_MODE_MASK) {
2390 case MODE_DIRECT: {
2391 int32_t value = 0;
2392 float valuef = 0;
2394 value = atoi(eqptr);
2395 valuef = fastA2F(eqptr);
2397 if (valuef >= valueTable[i].config.minmax.min && valuef <= valueTable[i].config.minmax.max) { // note: compare float value
2399 if ((valueTable[i].type & VALUE_TYPE_MASK) == VAR_FLOAT)
2400 tmp.float_value = valuef;
2401 else
2402 tmp.int_value = value;
2404 changeValue = true;
2407 break;
2408 case MODE_LOOKUP: {
2409 const lookupTableEntry_t *tableEntry = &lookupTables[valueTable[i].config.lookup.tableIndex];
2410 bool matched = false;
2411 for (uint8_t tableValueIndex = 0; tableValueIndex < tableEntry->valueCount && !matched; tableValueIndex++) {
2412 matched = strcasecmp(tableEntry->values[tableValueIndex], eqptr) == 0;
2414 if (matched) {
2415 tmp.int_value = tableValueIndex;
2416 changeValue = true;
2420 break;
2423 if (changeValue) {
2424 cliSetVar(val, tmp);
2426 cliPrintf("%s set to ", valueTable[i].name);
2427 cliPrintVar(val, 0);
2428 } else {
2429 cliPrint("Invalid value\r\n");
2432 return;
2435 cliPrint("Invalid name\r\n");
2436 } else {
2437 // no equals, check for matching variables.
2438 cliGet(cmdline);
2442 static void cliGet(char *cmdline)
2444 uint32_t i;
2445 const clivalue_t *val;
2446 int matchedCommands = 0;
2448 for (i = 0; i < VALUE_COUNT; i++) {
2449 if (strstr(valueTable[i].name, cmdline)) {
2450 val = &valueTable[i];
2451 cliPrintf("%s = ", valueTable[i].name);
2452 cliPrintVar(val, 0);
2453 cliPrint("\r\n");
2455 matchedCommands++;
2460 if (matchedCommands) {
2461 return;
2464 cliPrint("Invalid name\r\n");
2467 static void cliStatus(char *cmdline)
2469 UNUSED(cmdline);
2471 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), System load: %d.%02d\r\n",
2472 millis() / 1000, vbat, batteryCellCount, getBatteryStateString(), averageSystemLoadPercent / 100, averageSystemLoadPercent % 100);
2474 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2476 #ifndef CJMCU
2477 uint8_t i;
2478 uint32_t mask;
2479 uint32_t detectedSensorsMask = sensorsMask();
2481 for (i = 0; ; i++) {
2483 if (sensorTypeNames[i] == NULL)
2484 break;
2486 mask = (1 << i);
2487 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2488 const char *sensorHardware;
2489 uint8_t sensorHardwareIndex = detectedSensors[i];
2490 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2492 cliPrintf(", %s=%s", sensorTypeNames[i], sensorHardware);
2494 if (mask == SENSOR_ACC && acc.revisionCode) {
2495 cliPrintf(".%c", acc.revisionCode);
2499 #endif
2500 cliPrint("\r\n");
2502 #ifdef USE_I2C
2503 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2504 #else
2505 uint16_t i2cErrorCounter = 0;
2506 #endif
2508 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2511 #ifndef SKIP_TASK_STATISTICS
2512 static void cliTasks(char *cmdline)
2514 UNUSED(cmdline);
2516 cfTaskId_e taskId;
2517 cfTaskInfo_t taskInfo;
2519 cliPrintf("Task list max/us avg/us rate/hz total/ms\r\n");
2520 for (taskId = 0; taskId < TASK_COUNT; taskId++) {
2521 getTaskInfo(taskId, &taskInfo);
2522 if (taskInfo.isEnabled) {
2523 const uint16_t taskFrequency = (uint16_t)(1.0f / ((float)taskInfo.latestDeltaTime * 0.000001f));
2524 cliPrintf("%2d - %12s, %6d, %5d, %5d, %8d\r\n",
2525 taskId, taskInfo.taskName, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, taskFrequency, taskInfo.totalExecutionTime / 1000);
2529 #endif
2531 static void cliVersion(char *cmdline)
2533 UNUSED(cmdline);
2535 cliPrintf("# %s/%s %s %s / %s (%s)",
2536 FC_NAME,
2537 targetName,
2538 FC_VERSION_STRING,
2539 buildDate,
2540 buildTime,
2541 shortGitRevision
2545 static void cliPFlags(char *cmdline)
2547 UNUSED(cmdline);
2549 cliPrintf("# Persistent config flags: 0x%08x", masterConfig.persistentFlags );
2552 void cliProcess(void)
2554 if (!cliWriter) {
2555 return;
2558 // Be a little bit tricky. Flush the last inputs buffer, if any.
2559 bufWriterFlush(cliWriter);
2561 while (serialRxBytesWaiting(cliPort)) {
2562 uint8_t c = serialRead(cliPort);
2563 if (c == '\t' || c == '?') {
2564 // do tab completion
2565 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2566 uint32_t i = bufferIndex;
2567 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2568 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2569 continue;
2570 if (!pstart)
2571 pstart = cmd;
2572 pend = cmd;
2574 if (pstart) { /* Buffer matches one or more commands */
2575 for (; ; bufferIndex++) {
2576 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2577 break;
2578 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2579 /* Unambiguous -- append a space */
2580 cliBuffer[bufferIndex++] = ' ';
2581 cliBuffer[bufferIndex] = '\0';
2582 break;
2584 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2587 if (!bufferIndex || pstart != pend) {
2588 /* Print list of ambiguous matches */
2589 cliPrint("\r\033[K");
2590 for (cmd = pstart; cmd <= pend; cmd++) {
2591 cliPrint(cmd->name);
2592 cliWrite('\t');
2594 cliPrompt();
2595 i = 0; /* Redraw prompt */
2597 for (; i < bufferIndex; i++)
2598 cliWrite(cliBuffer[i]);
2599 } else if (!bufferIndex && c == 4) { // CTRL-D
2600 cliExit(cliBuffer);
2601 return;
2602 } else if (c == 12) { // NewPage / CTRL-L
2603 // clear screen
2604 cliPrint("\033[2J\033[1;1H");
2605 cliPrompt();
2606 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2607 // enter pressed
2608 cliPrint("\r\n");
2610 // Strip comment starting with # from line
2611 char *p = cliBuffer;
2612 p = strchr(p, '#');
2613 if (NULL != p) {
2614 bufferIndex = (uint32_t)(p - cliBuffer);
2617 // Strip trailing whitespace
2618 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2619 bufferIndex--;
2622 // Process non-empty lines
2623 if (bufferIndex > 0) {
2624 cliBuffer[bufferIndex] = 0; // null terminate
2626 const clicmd_t *cmd;
2627 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2628 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2629 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2630 break;
2632 if(cmd < cmdTable + CMD_COUNT)
2633 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2634 else
2635 cliPrint("Unknown command, try 'help'");
2636 bufferIndex = 0;
2639 memset(cliBuffer, 0, sizeof(cliBuffer));
2641 // 'exit' will reset this flag, so we don't need to print prompt again
2642 if (!cliMode)
2643 return;
2645 cliPrompt();
2646 } else if (c == 127) {
2647 // backspace
2648 if (bufferIndex) {
2649 cliBuffer[--bufferIndex] = 0;
2650 cliPrint("\010 \010");
2652 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2653 if (!bufferIndex && c == ' ')
2654 continue; // Ignore leading spaces
2655 cliBuffer[bufferIndex++] = c;
2656 cliWrite(c);
2661 void cliInit(serialConfig_t *serialConfig)
2663 UNUSED(serialConfig);
2665 #endif