Remove unused pointes if SKIP_CLI_COMMAND_HELP is defiend
[betaflight.git] / src / main / io / serial_cli.c
blob31645c587e2f5fa6da217aa30c5a759757443955
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 "build_config.h"
31 #include "common/axis.h"
32 #include "common/maths.h"
33 #include "common/color.h"
34 #include "common/typeconversion.h"
36 #include "drivers/system.h"
38 #include "drivers/sensor.h"
39 #include "drivers/accgyro.h"
40 #include "drivers/compass.h"
42 #include "drivers/serial.h"
43 #include "drivers/bus_i2c.h"
44 #include "drivers/gpio.h"
45 #include "drivers/timer.h"
46 #include "drivers/pwm_rx.h"
49 #include "io/escservo.h"
50 #include "io/gps.h"
51 #include "io/gimbal.h"
52 #include "io/rc_controls.h"
53 #include "io/serial.h"
54 #include "io/ledstrip.h"
55 #include "io/flashfs.h"
56 #include "io/beeper.h"
58 #include "rx/rx.h"
59 #include "rx/spektrum.h"
61 #include "sensors/battery.h"
62 #include "sensors/boardalignment.h"
63 #include "sensors/sensors.h"
64 #include "sensors/acceleration.h"
65 #include "sensors/gyro.h"
66 #include "sensors/compass.h"
67 #include "sensors/barometer.h"
69 #include "flight/pid.h"
70 #include "flight/imu.h"
71 #include "flight/mixer.h"
72 #include "flight/navigation.h"
73 #include "flight/failsafe.h"
75 #include "telemetry/telemetry.h"
76 #include "telemetry/frsky.h"
78 #include "config/runtime_config.h"
79 #include "config/config.h"
80 #include "config/config_profile.h"
81 #include "config/config_master.h"
83 #include "common/printf.h"
85 #include "serial_cli.h"
87 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
88 // signal that we're in cli mode
89 uint8_t cliMode = 0;
91 #ifdef USE_CLI
93 extern uint16_t cycleTime; // FIXME dependency on mw.c
95 void gpsEnablePassthrough(serialPort_t *gpsPassthroughPort);
97 static serialPort_t *cliPort;
99 static void cliAux(char *cmdline);
100 static void cliRxFail(char *cmdline);
101 static void cliAdjustmentRange(char *cmdline);
102 static void cliMotorMix(char *cmdline);
103 static void cliDefaults(char *cmdline);
104 static void cliDump(char *cmdLine);
105 static void cliExit(char *cmdline);
106 static void cliFeature(char *cmdline);
107 static void cliMotor(char *cmdline);
108 static void cliPlaySound(char *cmdline);
109 static void cliProfile(char *cmdline);
110 static void cliRateProfile(char *cmdline);
111 static void cliReboot(void);
112 static void cliSave(char *cmdline);
113 static void cliSerial(char *cmdline);
115 #ifdef USE_SERVOS
116 static void cliServo(char *cmdline);
117 static void cliServoMix(char *cmdline);
118 #endif
120 static void cliSet(char *cmdline);
121 static void cliGet(char *cmdline);
122 static void cliStatus(char *cmdline);
123 static void cliVersion(char *cmdline);
124 static void cliRxRange(char *cmdline);
126 #ifdef GPS
127 static void cliGpsPassthrough(char *cmdline);
128 #endif
130 static void cliHelp(char *cmdline);
131 static void cliMap(char *cmdline);
133 #ifdef LED_STRIP
134 static void cliLed(char *cmdline);
135 static void cliColor(char *cmdline);
136 #endif
138 #ifndef USE_QUAD_MIXER_ONLY
139 static void cliMixer(char *cmdline);
140 #endif
142 #ifdef USE_FLASHFS
143 static void cliFlashInfo(char *cmdline);
144 static void cliFlashErase(char *cmdline);
145 #ifdef USE_FLASH_TOOLS
146 static void cliFlashWrite(char *cmdline);
147 static void cliFlashRead(char *cmdline);
148 #endif
149 #endif
151 // buffer
152 static char cliBuffer[48];
153 static uint32_t bufferIndex = 0;
155 #ifndef USE_QUAD_MIXER_ONLY
156 // sync this with mixerMode_e
157 static const char * const mixerNames[] = {
158 "TRI", "QUADP", "QUADX", "BI",
159 "GIMBAL", "Y6", "HEX6",
160 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
161 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
162 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
163 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
165 #endif
167 // sync this with features_e
168 static const char * const featureNames[] = {
169 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
170 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
171 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
172 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
173 "BLACKBOX", "CHANNEL_FORWARDING", NULL
176 // sync this with rxFailsafeChannelMode_e
177 static const char rxFailsafeModeCharacters[] = "ahs";
179 static const rxFailsafeChannelMode_e rxFailsafeModesTable[RX_FAILSAFE_TYPE_COUNT][RX_FAILSAFE_MODE_COUNT] = {
180 { RX_FAILSAFE_MODE_AUTO, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_INVALID },
181 { RX_FAILSAFE_MODE_INVALID, RX_FAILSAFE_MODE_HOLD, RX_FAILSAFE_MODE_SET }
184 #ifndef CJMCU
185 // sync this with sensors_e
186 static const char * const sensorTypeNames[] = {
187 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
190 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
192 static const char * const sensorHardwareNames[4][11] = {
193 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL },
194 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL },
195 { "", "None", "BMP085", "MS5611", "BMP280", NULL },
196 { "", "None", "HMC5883", "AK8975", NULL }
198 #endif
200 typedef struct {
201 const char *name;
202 #ifndef SKIP_CLI_COMMAND_HELP
203 const char *description;
204 const char *args;
205 #endif
206 void (*func)(char *cmdline);
207 } clicmd_t;
209 #ifndef SKIP_CLI_COMMAND_HELP
210 #define CLI_COMMAND_DEF(name, description, args, method) \
212 name , \
213 description , \
214 args , \
215 method \
217 #else
218 #define CLI_COMMAND_DEF(name, description, args, method) \
220 name, \
221 method \
223 #endif
225 // should be sorted a..z for bsearch()
226 const clicmd_t cmdTable[] = {
227 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL, cliAdjustmentRange),
228 CLI_COMMAND_DEF("aux", "configure modes", NULL, cliAux),
229 #ifdef LED_STRIP
230 CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
231 #endif
232 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL, cliDefaults),
233 CLI_COMMAND_DEF("dump", "dump configuration",
234 "[master|profile]", cliDump),
235 CLI_COMMAND_DEF("exit", NULL, NULL, cliExit),
236 CLI_COMMAND_DEF("feature", "configure features",
237 "list\r\n"
238 "\t<+|->[name]", cliFeature),
239 #ifdef USE_FLASHFS
240 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL, cliFlashErase),
241 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
242 #ifdef USE_FLASH_TOOLS
243 CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
244 CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
245 #endif
246 #endif
247 CLI_COMMAND_DEF("get", "get variable value",
248 "[name]", cliGet),
249 #ifdef GPS
250 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL, cliGpsPassthrough),
251 #endif
252 CLI_COMMAND_DEF("help", NULL, NULL, cliHelp),
253 #ifdef LED_STRIP
254 CLI_COMMAND_DEF("led", "configure leds", NULL, cliLed),
255 #endif
256 CLI_COMMAND_DEF("map", "configure rc channel order",
257 "[<map>]", cliMap),
258 #ifndef USE_QUAD_MIXER_ONLY
259 CLI_COMMAND_DEF("mixer", "configure mixer",
260 "list\r\n"
261 "\t<name>", cliMixer),
262 #endif
263 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL, cliMotorMix),
264 CLI_COMMAND_DEF("motor", "get/set motor",
265 "<index> [<value>]", cliMotor),
266 CLI_COMMAND_DEF("play_sound", NULL,
267 "[<index>]\r\n", cliPlaySound),
268 CLI_COMMAND_DEF("profile", "change profile",
269 "[<index>]", cliProfile),
270 CLI_COMMAND_DEF("rateprofile", "change rate profile",
271 "[<index>]", cliRateProfile),
272 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL, cliRxRange),
273 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL, cliRxFail),
274 CLI_COMMAND_DEF("save", "save and reboot", NULL, cliSave),
275 CLI_COMMAND_DEF("serial", "configure serial ports", NULL, cliSerial),
276 #ifdef USE_SERVOS
277 CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
278 #endif
279 CLI_COMMAND_DEF("set", "change setting",
280 "[<name>=<value>]", cliSet),
281 #ifdef USE_SERVOS
282 CLI_COMMAND_DEF("smix", "servo mixer",
283 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
284 "\treset\r\n"
285 "\tload <mixer>\r\n"
286 "\treverse <servo> <source> r|n", cliServoMix),
287 #endif
288 CLI_COMMAND_DEF("status", "show status", NULL, cliStatus),
289 CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
291 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
293 typedef enum {
294 VAR_UINT8 = (1 << 0),
295 VAR_INT8 = (1 << 1),
296 VAR_UINT16 = (1 << 2),
297 VAR_INT16 = (1 << 3),
298 VAR_UINT32 = (1 << 4),
299 VAR_FLOAT = (1 << 5),
301 MASTER_VALUE = (1 << 6),
302 PROFILE_VALUE = (1 << 7),
303 CONTROL_RATE_VALUE = (1 << 8)
304 } cliValueFlag_e;
306 #define VALUE_TYPE_MASK (VAR_UINT8 | VAR_INT8 | VAR_UINT16 | VAR_INT16 | VAR_UINT32 | VAR_FLOAT)
307 #define SECTION_MASK (MASTER_VALUE | PROFILE_VALUE | CONTROL_RATE_VALUE)
309 typedef struct {
310 const char *name;
311 const uint16_t type; // cliValueFlag_e - specify one of each from VALUE_TYPE_MASK and SECTION_MASK
312 void *ptr;
313 const int32_t min;
314 const int32_t max;
315 } clivalue_t;
317 const clivalue_t valueTable[] = {
318 { "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 9000 },
319 { "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 },
321 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, 1200, 1700 },
322 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
323 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
324 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
325 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
326 { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_ppm_invert, 0, 1 },
327 { "rc_smoothing", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rcSmoothing, 0, 1 },
328 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE, &masterConfig.inputFilteringMode, 0, 1 },
330 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
331 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
332 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
333 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, PWM_RANGE_ZERO, PWM_RANGE_MAX },
335 { "3d_deadband_low", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_low, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME upper limit should match code in the mixer, 1500 currently
336 { "3d_deadband_high", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_high, PWM_RANGE_ZERO, PWM_RANGE_MAX }, // FIXME lower limit should match code in the mixer, 1500 currently,
337 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
338 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
340 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, 50, 32000 },
341 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, 50, 498 },
343 { "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
344 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
345 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
346 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
348 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, -1, 1 },
350 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
352 #ifdef GPS
353 { "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
354 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
355 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoConfig, GPS_AUTOCONFIG_OFF, GPS_AUTOCONFIG_ON },
356 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoBaud, GPS_AUTOBAUD_OFF, GPS_AUTOBAUD_ON },
358 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 },
359 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], 0, 200 },
360 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], 0, 200 },
361 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], 0, 200 },
362 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], 0, 200 },
363 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], 0, 200 },
364 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], 0, 200 },
365 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], 0, 200 },
366 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], 0, 200 },
367 { "gps_wp_radius", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.gps_wp_radius, 0, 2000 },
368 { "nav_controls_heading", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_controls_heading, 0, 1 },
369 { "nav_speed_min", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_min, 10, 2000 },
370 { "nav_speed_max", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_max, 10, 2000 },
371 { "nav_slew_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_slew_rate, 0, 100 },
372 #endif
374 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
375 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX},
377 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
378 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_inversion, 0, 1 },
379 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, -90.0, 90.0 },
380 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, -180.0, 180.0 },
381 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, 0, FRSKY_FORMAT_NMEA },
382 { "frsky_unit", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_unit, 0, FRSKY_UNIT_IMPERIALS },
383 { "frsky_vfas_precision", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_vfas_precision, FRSKY_VFAS_PRECISION_LOW, FRSKY_VFAS_PRECISION_HIGH },
384 { "hott_alarm_sound_interval", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.hottAlarmSoundInterval, 0, 120 },
386 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, 0, 20000 },
387 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX },
388 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
389 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
390 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, 10, 50 },
391 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, -10000, 10000 },
392 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 3300 },
393 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
394 { "current_meter_type", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterType, 0, CURRENT_SENSOR_MAX },
396 { "align_gyro", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
397 { "align_acc", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },
398 { "align_mag", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.mag_align, 0, 8 },
400 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, -180, 360 },
401 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, -180, 360 },
402 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, -180, 360 },
404 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, 100, 900 },
406 { "gyro_lpf", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_lpf, 0, 256 },
407 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
408 { "gyro_cmpf_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpf_factor, 100, 1000 },
409 { "gyro_cmpfm_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
411 { "alt_hold_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_deadband, 1, 250 },
412 { "alt_hold_fast_change", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_fast_change, 0, 1 },
413 { "deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.deadband, 0, 32 },
414 { "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.yaw_deadband, 0, 100 },
416 { "throttle_correction_value", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_value, 0, 150 },
417 { "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_angle, 1, 900 },
419 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
421 { "pid_at_min_throttle", VAR_UINT8 | MASTER_VALUE, &masterConfig.mixerConfig.pid_at_min_throttle, 0, 1 },
422 { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_motor_direction, -1, 1 },
423 { "yaw_jump_prevention_limit", VAR_UINT16 | MASTER_VALUE, &masterConfig.mixerConfig.yaw_jump_prevention_limit, YAW_JUMP_PREVENTION_LIMIT_LOW, YAW_JUMP_PREVENTION_LIMIT_HIGH },
424 #ifdef USE_SERVOS
425 { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.tri_unarmed_servo, 0, 1 },
426 { "servo_lowpass_freq", VAR_INT16 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_freq, 10, 400},
427 { "servo_lowpass_enable", VAR_INT8 | MASTER_VALUE, &masterConfig.mixerConfig.servo_lowpass_enable, 0, 1 },
428 #endif
430 { "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },
431 { "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, 0, 250 },
432 { "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
433 { "rc_yaw_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcYawExpo8, 0, 100 },
434 { "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, 0, 100 },
435 { "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, 0, 100 },
436 { "roll_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_ROLL], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX },
437 { "pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_PITCH], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX },
438 { "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rates[FD_YAW], 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX },
439 { "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, CONTROL_RATE_CONFIG_TPA_MAX},
440 { "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
442 { "failsafe_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_delay, 0, 200 },
443 { "failsafe_off_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_off_delay, 0, 200 },
444 { "failsafe_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
445 { "failsafe_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_kill_switch, 0, 1 },
446 { "failsafe_throttle_low_delay",VAR_UINT16 | MASTER_VALUE, &masterConfig.failsafeConfig.failsafe_throttle_low_delay, 0, 300 },
448 { "rx_min_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_min_usec, PWM_PULSE_MIN, PWM_PULSE_MAX },
449 { "rx_max_usec", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.rx_max_usec, PWM_PULSE_MIN, PWM_PULSE_MAX },
451 #ifdef USE_SERVOS
452 { "gimbal_mode", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.mode, 0, GIMBAL_MODE_MAX},
453 #endif
455 { "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_hardware, 0, ACC_MAX },
456 { "acc_lpf_factor", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].acc_lpf_factor, 0, 250 },
457 { "accxy_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.xy, 0, 100 },
458 { "accz_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.z, 0, 100 },
459 { "accz_lpf_cutoff", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].accz_lpf_cutoff, 1, 20 },
460 { "acc_unarmedcal", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].acc_unarmedcal, 0, 1 },
461 { "acc_trim_pitch", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.pitch, -300, 300 },
462 { "acc_trim_roll", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.roll, -300, 300 },
464 { "baro_tab_size", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
465 { "baro_noise_lpf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_noise_lpf, 0, 1 },
466 { "baro_cf_vel", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_vel, 0, 1 },
467 { "baro_cf_alt", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_alt, 0, 1 },
468 { "baro_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.baro_hardware, 0, BARO_MAX },
470 { "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.mag_hardware, 0, MAG_MAX },
471 { "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, -18000, 18000 },
473 { "pid_controller", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidController, 0, 5 },
475 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], 0, 200 },
476 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], 0, 200 },
477 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], 0, 200 },
478 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], 0, 200 },
479 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], 0, 200 },
480 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], 0, 200 },
481 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], 0, 200 },
482 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], 0, 200 },
483 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], 0, 200 },
485 { "p_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[PITCH], 0, 100 },
486 { "i_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[PITCH], 0, 100 },
487 { "d_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[PITCH], 0, 100 },
488 { "p_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[ROLL], 0, 100 },
489 { "i_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[ROLL], 0, 100 },
490 { "d_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[ROLL], 0, 100 },
491 { "p_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[YAW], 0, 100 },
492 { "i_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[YAW], 0, 100 },
493 { "d_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[YAW], 0, 100 },
495 { "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, 0, 10 },
496 { "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, 0, 10 },
497 { "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, 0, 250 },
499 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], 0, 200 },
500 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], 0, 200 },
501 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], 0, 200 },
503 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], 0, 200 },
504 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], 0, 200 },
505 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], 0, 200 },
507 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
508 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
509 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
511 { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX },
512 { "dterm_cut_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.dterm_cut_hz, 0, 200 },
513 { "pterm_cut_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pterm_cut_hz, 0, 200 },
514 { "gyro_cut_hz", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gyro_cut_hz, 0, 200 },
516 { "pid5_oldyw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pid5_oldyw, 0, 1 },
518 #ifdef GTUNE
519 { "gtune_loP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_ROLL], 10, 200 },
520 { "gtune_loP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_PITCH], 10, 200 },
521 { "gtune_loP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_lolimP[FD_YAW], 10, 200 },
522 { "gtune_hiP_rll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_ROLL], 0, 200 },
523 { "gtune_hiP_ptch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_PITCH], 0, 200 },
524 { "gtune_hiP_yw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_hilimP[FD_YAW], 0, 200 },
525 { "gtune_pwr", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_pwr, 0, 10 },
526 { "gtune_settle_time", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_settle_time, 200, 1000 },
527 { "gtune_average_cycles", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.gtune_average_cycles, 8, 128 },
528 #endif
530 #ifdef BLACKBOX
531 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
532 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
533 { "blackbox_device", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_device, 0, 1 },
534 #endif
536 { "magzero_x", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[X], -32768, 32767 },
537 { "magzero_y", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Y], -32768, 32767 },
538 { "magzero_z", VAR_INT16 | MASTER_VALUE, &masterConfig.magZero.raw[Z], -32768, 32767 },
541 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
544 typedef union {
545 int32_t int_value;
546 float float_value;
547 } int_float_value_t;
549 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
550 static void cliPrintVar(const clivalue_t *var, uint32_t full);
551 static void cliPrint(const char *str);
552 static void cliWrite(uint8_t ch);
554 static void cliPrompt(void)
556 cliPrint("\r\n# ");
559 static void cliShowParseError(void)
561 cliPrint("Parse error\r\n");
564 static void cliShowArgumentRangeError(char *name, int min, int max)
566 printf("%s must be between %d and %d\r\n", name, min, max);
569 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
571 int val;
573 for (int argIndex = 0; argIndex < 2; argIndex++) {
574 ptr = strchr(ptr, ' ');
575 if (ptr) {
576 val = atoi(++ptr);
577 val = CHANNEL_VALUE_TO_STEP(val);
578 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
579 if (argIndex == 0) {
580 range->startStep = val;
581 } else {
582 range->endStep = val;
584 (*validArgumentCount)++;
589 return ptr;
592 // Check if a string's length is zero
593 static bool isEmpty(const char *string)
595 return *string == '\0';
598 static void cliRxFail(char *cmdline)
600 uint8_t channel;
601 char buf[3];
603 if (isEmpty(cmdline)) {
604 // print out rxConfig failsafe settings
605 for (channel = 0; channel < MAX_SUPPORTED_RC_CHANNEL_COUNT; channel++) {
606 cliRxFail(itoa(channel, buf, 10));
608 } else {
609 char *ptr = cmdline;
610 channel = atoi(ptr++);
611 if ((channel < MAX_SUPPORTED_RC_CHANNEL_COUNT)) {
613 rxFailsafeChannelConfiguration_t *channelFailsafeConfiguration = &masterConfig.rxConfig.failsafe_channel_configurations[channel];
615 uint16_t value;
616 rxFailsafeChannelType_e type = (channel < NON_AUX_CHANNEL_COUNT) ? RX_FAILSAFE_TYPE_FLIGHT : RX_FAILSAFE_TYPE_AUX;
617 rxFailsafeChannelMode_e mode = channelFailsafeConfiguration->mode;
618 bool requireValue = channelFailsafeConfiguration->mode == RX_FAILSAFE_MODE_SET;
620 ptr = strchr(ptr, ' ');
621 if (ptr) {
622 char *p = strchr(rxFailsafeModeCharacters, *(++ptr));
623 if (p) {
624 uint8_t requestedMode = p - rxFailsafeModeCharacters;
625 mode = rxFailsafeModesTable[type][requestedMode];
626 } else {
627 mode = RX_FAILSAFE_MODE_INVALID;
629 if (mode == RX_FAILSAFE_MODE_INVALID) {
630 cliShowParseError();
631 return;
634 requireValue = mode == RX_FAILSAFE_MODE_SET;
636 ptr = strchr(ptr, ' ');
637 if (ptr) {
638 if (!requireValue) {
639 cliShowParseError();
640 return;
642 value = atoi(++ptr);
643 value = CHANNEL_VALUE_TO_RXFAIL_STEP(value);
644 if (value > MAX_RXFAIL_RANGE_STEP) {
645 cliPrint("Value out of range\r\n");
646 return;
649 channelFailsafeConfiguration->step = value;
650 } else if (requireValue) {
651 cliShowParseError();
652 return;
654 channelFailsafeConfiguration->mode = mode;
658 char modeCharacter = rxFailsafeModeCharacters[channelFailsafeConfiguration->mode];
660 // triple use of printf below
661 // 1. acknowledge interpretation on command,
662 // 2. query current setting on single item,
663 // 3. recursive use for full list.
665 if (requireValue) {
666 printf("rxfail %u %c %d\r\n",
667 channel,
668 modeCharacter,
669 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration->step)
671 } else {
672 printf("rxfail %u %c\r\n",
673 channel,
674 modeCharacter
677 } else {
678 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT - 1);
683 static void cliAux(char *cmdline)
685 int i, val = 0;
686 char *ptr;
688 if (isEmpty(cmdline)) {
689 // print out aux channel settings
690 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
691 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
692 printf("aux %u %u %u %u %u\r\n",
694 mac->modeId,
695 mac->auxChannelIndex,
696 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
697 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
700 } else {
701 ptr = cmdline;
702 i = atoi(ptr++);
703 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
704 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
705 uint8_t validArgumentCount = 0;
706 ptr = strchr(ptr, ' ');
707 if (ptr) {
708 val = atoi(++ptr);
709 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
710 mac->modeId = val;
711 validArgumentCount++;
714 ptr = strchr(ptr, ' ');
715 if (ptr) {
716 val = atoi(++ptr);
717 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
718 mac->auxChannelIndex = val;
719 validArgumentCount++;
722 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
724 if (validArgumentCount != 4) {
725 memset(mac, 0, sizeof(modeActivationCondition_t));
727 } else {
728 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT - 1);
733 static void cliSerial(char *cmdline)
735 int i, val;
736 char *ptr;
738 if (isEmpty(cmdline)) {
739 for (i = 0; i < SERIAL_PORT_COUNT; i++) {
740 if (!serialIsPortAvailable(masterConfig.serialConfig.portConfigs[i].identifier)) {
741 continue;
743 printf("serial %d %d %ld %ld %ld %ld\r\n" ,
744 masterConfig.serialConfig.portConfigs[i].identifier,
745 masterConfig.serialConfig.portConfigs[i].functionMask,
746 baudRates[masterConfig.serialConfig.portConfigs[i].msp_baudrateIndex],
747 baudRates[masterConfig.serialConfig.portConfigs[i].gps_baudrateIndex],
748 baudRates[masterConfig.serialConfig.portConfigs[i].telemetry_baudrateIndex],
749 baudRates[masterConfig.serialConfig.portConfigs[i].blackbox_baudrateIndex]
752 return;
755 serialPortConfig_t portConfig;
756 memset(&portConfig, 0 , sizeof(portConfig));
758 serialPortConfig_t *currentConfig;
760 uint8_t validArgumentCount = 0;
762 ptr = cmdline;
764 val = atoi(ptr++);
765 currentConfig = serialFindPortConfiguration(val);
766 if (currentConfig) {
767 portConfig.identifier = val;
768 validArgumentCount++;
771 ptr = strchr(ptr, ' ');
772 if (ptr) {
773 val = atoi(++ptr);
774 portConfig.functionMask = val & 0xFFFF;
775 validArgumentCount++;
778 for (i = 0; i < 4; i ++) {
779 ptr = strchr(ptr, ' ');
780 if (!ptr) {
781 break;
784 val = atoi(++ptr);
786 uint8_t baudRateIndex = lookupBaudRateIndex(val);
787 if (baudRates[baudRateIndex] != (uint32_t) val) {
788 break;
791 switch(i) {
792 case 0:
793 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
794 continue;
796 portConfig.msp_baudrateIndex = baudRateIndex;
797 break;
798 case 1:
799 if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
800 continue;
802 portConfig.gps_baudrateIndex = baudRateIndex;
803 break;
804 case 2:
805 if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
806 continue;
808 portConfig.telemetry_baudrateIndex = baudRateIndex;
809 break;
810 case 3:
811 if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
812 continue;
814 portConfig.blackbox_baudrateIndex = baudRateIndex;
815 break;
818 validArgumentCount++;
821 if (validArgumentCount < 6) {
822 cliShowParseError();
823 return;
826 memcpy(currentConfig, &portConfig, sizeof(portConfig));
830 static void cliAdjustmentRange(char *cmdline)
832 int i, val = 0;
833 char *ptr;
835 if (isEmpty(cmdline)) {
836 // print out adjustment ranges channel settings
837 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
838 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
839 printf("adjrange %u %u %u %u %u %u %u\r\n",
841 ar->adjustmentIndex,
842 ar->auxChannelIndex,
843 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
844 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
845 ar->adjustmentFunction,
846 ar->auxSwitchChannelIndex
849 } else {
850 ptr = cmdline;
851 i = atoi(ptr++);
852 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
853 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
854 uint8_t validArgumentCount = 0;
856 ptr = strchr(ptr, ' ');
857 if (ptr) {
858 val = atoi(++ptr);
859 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
860 ar->adjustmentIndex = val;
861 validArgumentCount++;
864 ptr = strchr(ptr, ' ');
865 if (ptr) {
866 val = atoi(++ptr);
867 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
868 ar->auxChannelIndex = val;
869 validArgumentCount++;
873 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
875 ptr = strchr(ptr, ' ');
876 if (ptr) {
877 val = atoi(++ptr);
878 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
879 ar->adjustmentFunction = val;
880 validArgumentCount++;
883 ptr = strchr(ptr, ' ');
884 if (ptr) {
885 val = atoi(++ptr);
886 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
887 ar->auxSwitchChannelIndex = val;
888 validArgumentCount++;
892 if (validArgumentCount != 6) {
893 memset(ar, 0, sizeof(adjustmentRange_t));
894 cliShowParseError();
896 } else {
897 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT - 1);
902 static void cliMotorMix(char *cmdline)
904 #ifdef USE_QUAD_MIXER_ONLY
905 UNUSED(cmdline);
906 #else
907 int i, check = 0;
908 int num_motors = 0;
909 uint8_t len;
910 char buf[16];
911 char *ptr;
913 if (isEmpty(cmdline)) {
914 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
915 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
916 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
917 break;
918 num_motors++;
919 printf("#%d:\t", i);
920 printf("%s\t", ftoa(masterConfig.customMotorMixer[i].throttle, buf));
921 printf("%s\t", ftoa(masterConfig.customMotorMixer[i].roll, buf));
922 printf("%s\t", ftoa(masterConfig.customMotorMixer[i].pitch, buf));
923 printf("%s\r\n", ftoa(masterConfig.customMotorMixer[i].yaw, buf));
925 return;
926 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
927 // erase custom mixer
928 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
929 masterConfig.customMotorMixer[i].throttle = 0.0f;
930 } else if (strncasecmp(cmdline, "load", 4) == 0) {
931 ptr = strchr(cmdline, ' ');
932 if (ptr) {
933 len = strlen(++ptr);
934 for (i = 0; ; i++) {
935 if (mixerNames[i] == NULL) {
936 cliPrint("Invalid name\r\n");
937 break;
939 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
940 mixerLoadMix(i, masterConfig.customMotorMixer);
941 printf("Loaded %s\r\n", mixerNames[i]);
942 cliMotorMix("");
943 break;
947 } else {
948 ptr = cmdline;
949 i = atoi(ptr); // get motor number
950 if (i < MAX_SUPPORTED_MOTORS) {
951 ptr = strchr(ptr, ' ');
952 if (ptr) {
953 masterConfig.customMotorMixer[i].throttle = fastA2F(++ptr);
954 check++;
956 ptr = strchr(ptr, ' ');
957 if (ptr) {
958 masterConfig.customMotorMixer[i].roll = fastA2F(++ptr);
959 check++;
961 ptr = strchr(ptr, ' ');
962 if (ptr) {
963 masterConfig.customMotorMixer[i].pitch = fastA2F(++ptr);
964 check++;
966 ptr = strchr(ptr, ' ');
967 if (ptr) {
968 masterConfig.customMotorMixer[i].yaw = fastA2F(++ptr);
969 check++;
971 if (check != 4) {
972 cliShowParseError();
973 } else {
974 cliMotorMix("");
976 } else {
977 cliShowArgumentRangeError("index", 1, MAX_SUPPORTED_MOTORS);
980 #endif
983 static void cliRxRange(char *cmdline)
985 int i, validArgumentCount = 0;
986 char *ptr;
988 if (isEmpty(cmdline)) {
989 for (i = 0; i < NON_AUX_CHANNEL_COUNT; i++) {
990 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
991 printf("rxrange %u %u %u\r\n", i, channelRangeConfiguration->min, channelRangeConfiguration->max);
993 } else if (strcasecmp(cmdline, "reset") == 0) {
994 resetAllRxChannelRangeConfigurations(masterConfig.rxConfig.channelRanges);
995 } else {
996 ptr = cmdline;
997 i = atoi(ptr);
998 if (i >= 0 && i < NON_AUX_CHANNEL_COUNT) {
999 int rangeMin, rangeMax;
1001 ptr = strchr(ptr, ' ');
1002 if (ptr) {
1003 rangeMin = atoi(++ptr);
1004 validArgumentCount++;
1007 ptr = strchr(ptr, ' ');
1008 if (ptr) {
1009 rangeMax = atoi(++ptr);
1010 validArgumentCount++;
1013 if (validArgumentCount != 2) {
1014 cliShowParseError();
1015 } else if (rangeMin < PWM_PULSE_MIN || rangeMin > PWM_PULSE_MAX || rangeMax < PWM_PULSE_MIN || rangeMax > PWM_PULSE_MAX) {
1016 cliShowParseError();
1017 } else {
1018 rxChannelRangeConfiguration_t *channelRangeConfiguration = &masterConfig.rxConfig.channelRanges[i];
1019 channelRangeConfiguration->min = rangeMin;
1020 channelRangeConfiguration->max = rangeMax;
1022 } else {
1023 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT - 1);
1028 #ifdef LED_STRIP
1029 static void cliLed(char *cmdline)
1031 int i;
1032 char *ptr;
1033 char ledConfigBuffer[20];
1035 if (isEmpty(cmdline)) {
1036 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
1037 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
1038 printf("led %u %s\r\n", i, ledConfigBuffer);
1040 } else {
1041 ptr = cmdline;
1042 i = atoi(ptr);
1043 if (i < MAX_LED_STRIP_LENGTH) {
1044 ptr = strchr(cmdline, ' ');
1045 if (!parseLedStripConfig(i, ++ptr)) {
1046 cliShowParseError();
1048 } else {
1049 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH - 1);
1054 static void cliColor(char *cmdline)
1056 int i;
1057 char *ptr;
1059 if (isEmpty(cmdline)) {
1060 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
1061 printf("color %u %d,%u,%u\r\n",
1063 masterConfig.colors[i].h,
1064 masterConfig.colors[i].s,
1065 masterConfig.colors[i].v
1068 } else {
1069 ptr = cmdline;
1070 i = atoi(ptr);
1071 if (i < CONFIGURABLE_COLOR_COUNT) {
1072 ptr = strchr(cmdline, ' ');
1073 if (!parseColor(i, ++ptr)) {
1074 cliShowParseError();
1076 } else {
1077 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT - 1);
1081 #endif
1083 #ifdef USE_SERVOS
1084 static void cliServo(char *cmdline)
1086 enum { SERVO_ARGUMENT_COUNT = 8 };
1087 int16_t arguments[SERVO_ARGUMENT_COUNT];
1089 servoParam_t *servo;
1091 int i;
1092 char *ptr;
1094 if (isEmpty(cmdline)) {
1095 // print out servo settings
1096 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1097 servo = &currentProfile->servoConf[i];
1099 printf("servo %u %d %d %d %d %d %d %d\r\n",
1101 servo->min,
1102 servo->max,
1103 servo->middle,
1104 servo->angleAtMin,
1105 servo->angleAtMax,
1106 servo->rate,
1107 servo->forwardFromChannel
1110 } else {
1111 int validArgumentCount = 0;
1113 ptr = cmdline;
1115 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1117 // If command line doesn't fit the format, don't modify the config
1118 while (*ptr) {
1119 if (*ptr == '-' || (*ptr >= '0' && *ptr <= '9')) {
1120 if (validArgumentCount >= SERVO_ARGUMENT_COUNT) {
1121 cliShowParseError();
1122 return;
1125 arguments[validArgumentCount++] = atoi(ptr);
1127 do {
1128 ptr++;
1129 } while (*ptr >= '0' && *ptr <= '9');
1130 } else if (*ptr == ' ') {
1131 ptr++;
1132 } else {
1133 cliShowParseError();
1134 return;
1138 enum {INDEX = 0, MIN, MAX, MIDDLE, ANGLE_AT_MIN, ANGLE_AT_MAX, RATE, FORWARD};
1140 i = arguments[INDEX];
1142 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1143 if (validArgumentCount != SERVO_ARGUMENT_COUNT || i < 0 || i >= MAX_SUPPORTED_SERVOS) {
1144 cliShowParseError();
1145 return;
1148 servo = &currentProfile->servoConf[i];
1150 if (
1151 arguments[MIN] < PWM_PULSE_MIN || arguments[MIN] > PWM_PULSE_MAX ||
1152 arguments[MAX] < PWM_PULSE_MIN || arguments[MAX] > PWM_PULSE_MAX ||
1153 arguments[MIDDLE] < arguments[MIN] || arguments[MIDDLE] > arguments[MAX] ||
1154 arguments[MIN] > arguments[MAX] || arguments[MAX] < arguments[MIN] ||
1155 arguments[RATE] < -100 || arguments[RATE] > 100 ||
1156 arguments[FORWARD] >= MAX_SUPPORTED_RC_CHANNEL_COUNT ||
1157 arguments[ANGLE_AT_MIN] < 0 || arguments[ANGLE_AT_MIN] > 180 ||
1158 arguments[ANGLE_AT_MAX] < 0 || arguments[ANGLE_AT_MAX] > 180
1160 cliShowParseError();
1161 return;
1164 servo->min = arguments[1];
1165 servo->max = arguments[2];
1166 servo->middle = arguments[3];
1167 servo->angleAtMin = arguments[4];
1168 servo->angleAtMax = arguments[5];
1169 servo->rate = arguments[6];
1170 servo->forwardFromChannel = arguments[7];
1173 #endif
1175 #ifdef USE_SERVOS
1176 static void cliServoMix(char *cmdline)
1178 int i;
1179 uint8_t len;
1180 char *ptr;
1181 int args[8], check = 0;
1182 len = strlen(cmdline);
1184 if (len == 0) {
1186 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1188 for (i = 0; i < MAX_SERVO_RULES; i++) {
1189 if (masterConfig.customServoMixer[i].rate == 0)
1190 break;
1192 printf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1194 masterConfig.customServoMixer[i].targetChannel,
1195 masterConfig.customServoMixer[i].inputSource,
1196 masterConfig.customServoMixer[i].rate,
1197 masterConfig.customServoMixer[i].speed,
1198 masterConfig.customServoMixer[i].min,
1199 masterConfig.customServoMixer[i].max,
1200 masterConfig.customServoMixer[i].box
1203 printf("\r\n");
1204 return;
1205 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
1206 // erase custom mixer
1207 memset(masterConfig.customServoMixer, 0, sizeof(masterConfig.customServoMixer));
1208 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1209 currentProfile->servoConf[i].reversedSources = 0;
1211 } else if (strncasecmp(cmdline, "load", 4) == 0) {
1212 ptr = strchr(cmdline, ' ');
1213 if (ptr) {
1214 len = strlen(++ptr);
1215 for (i = 0; ; i++) {
1216 if (mixerNames[i] == NULL) {
1217 printf("Invalid name\r\n");
1218 break;
1220 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
1221 servoMixerLoadMix(i, masterConfig.customServoMixer);
1222 printf("Loaded %s\r\n", mixerNames[i]);
1223 cliServoMix("");
1224 break;
1228 } else if (strncasecmp(cmdline, "reverse", 7) == 0) {
1229 enum {SERVO = 0, INPUT, REVERSE, ARGS_COUNT};
1230 int servoIndex, inputSource;
1231 ptr = strchr(cmdline, ' ');
1233 len = strlen(ptr);
1234 if (len == 0) {
1235 printf("s");
1236 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1237 printf("\ti%d", inputSource);
1238 printf("\r\n");
1240 for (servoIndex = 0; servoIndex < MAX_SUPPORTED_SERVOS; servoIndex++) {
1241 printf("%d", servoIndex);
1242 for (inputSource = 0; inputSource < INPUT_SOURCE_COUNT; inputSource++)
1243 printf("\t%s ", (currentProfile->servoConf[servoIndex].reversedSources & (1 << inputSource)) ? "r" : "n");
1244 printf("\r\n");
1246 return;
1249 ptr = strtok(ptr, " ");
1250 while (ptr != NULL && check < ARGS_COUNT - 1) {
1251 args[check++] = atoi(ptr);
1252 ptr = strtok(NULL, " ");
1255 if (ptr == NULL || check != ARGS_COUNT - 1) {
1256 cliShowParseError();
1257 return;
1260 if (args[SERVO] >= 0 && args[SERVO] < MAX_SUPPORTED_SERVOS
1261 && args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT
1262 && (*ptr == 'r' || *ptr == 'n')) {
1263 if (*ptr == 'r')
1264 currentProfile->servoConf[args[SERVO]].reversedSources |= 1 << args[INPUT];
1265 else
1266 currentProfile->servoConf[args[SERVO]].reversedSources &= ~(1 << args[INPUT]);
1267 } else
1268 cliShowParseError();
1270 cliServoMix("reverse");
1271 } else {
1272 enum {RULE = 0, TARGET, INPUT, RATE, SPEED, MIN, MAX, BOX, ARGS_COUNT};
1273 ptr = strtok(cmdline, " ");
1274 while (ptr != NULL && check < ARGS_COUNT) {
1275 args[check++] = atoi(ptr);
1276 ptr = strtok(NULL, " ");
1279 if (ptr != NULL || check != ARGS_COUNT) {
1280 cliShowParseError();
1281 return;
1284 i = args[RULE];
1285 if (i >= 0 && i < MAX_SERVO_RULES &&
1286 args[TARGET] >= 0 && args[TARGET] < MAX_SUPPORTED_SERVOS &&
1287 args[INPUT] >= 0 && args[INPUT] < INPUT_SOURCE_COUNT &&
1288 args[RATE] >= -100 && args[RATE] <= 100 &&
1289 args[SPEED] >= 0 && args[SPEED] <= MAX_SERVO_SPEED &&
1290 args[MIN] >= 0 && args[MIN] <= 100 &&
1291 args[MAX] >= 0 && args[MAX] <= 100 && args[MIN] < args[MAX] &&
1292 args[BOX] >= 0 && args[BOX] <= MAX_SERVO_BOXES) {
1293 masterConfig.customServoMixer[i].targetChannel = args[TARGET];
1294 masterConfig.customServoMixer[i].inputSource = args[INPUT];
1295 masterConfig.customServoMixer[i].rate = args[RATE];
1296 masterConfig.customServoMixer[i].speed = args[SPEED];
1297 masterConfig.customServoMixer[i].min = args[MIN];
1298 masterConfig.customServoMixer[i].max = args[MAX];
1299 masterConfig.customServoMixer[i].box = args[BOX];
1300 cliServoMix("");
1301 } else {
1302 cliShowParseError();
1306 #endif
1309 #ifdef USE_FLASHFS
1311 static void cliFlashInfo(char *cmdline)
1313 const flashGeometry_t *layout = flashfsGetGeometry();
1315 UNUSED(cmdline);
1317 printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1318 layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
1321 static void cliFlashErase(char *cmdline)
1323 UNUSED(cmdline);
1325 printf("Erasing...\r\n");
1326 flashfsEraseCompletely();
1328 while (!flashfsIsReady()) {
1329 delay(100);
1332 printf("Done.\r\n");
1335 #ifdef USE_FLASH_TOOLS
1337 static void cliFlashWrite(char *cmdline)
1339 uint32_t address = atoi(cmdline);
1340 char *text = strchr(cmdline, ' ');
1342 if (!text) {
1343 cliShowParseError();
1344 } else {
1345 flashfsSeekAbs(address);
1346 flashfsWrite((uint8_t*)text, strlen(text), true);
1347 flashfsFlushSync();
1349 printf("Wrote %u bytes at %u.\r\n", strlen(text), address);
1353 static void cliFlashRead(char *cmdline)
1355 uint32_t address = atoi(cmdline);
1356 uint32_t length;
1357 int i;
1359 uint8_t buffer[32];
1361 char *nextArg = strchr(cmdline, ' ');
1363 if (!nextArg) {
1364 cliShowParseError();
1365 } else {
1366 length = atoi(nextArg);
1368 printf("Reading %u bytes at %u:\r\n", length, address);
1370 while (length > 0) {
1371 int bytesRead;
1373 bytesRead = flashfsReadAbs(address, buffer, length < sizeof(buffer) ? length : sizeof(buffer));
1375 for (i = 0; i < bytesRead; i++) {
1376 cliWrite(buffer[i]);
1379 length -= bytesRead;
1380 address += bytesRead;
1382 if (bytesRead == 0) {
1383 //Assume we reached the end of the volume or something fatal happened
1384 break;
1387 printf("\r\n");
1391 #endif
1392 #endif
1394 static void dumpValues(uint16_t mask)
1396 uint32_t i;
1397 const clivalue_t *value;
1398 for (i = 0; i < VALUE_COUNT; i++) {
1399 value = &valueTable[i];
1401 if ((value->type & mask) == 0) {
1402 continue;
1405 printf("set %s = ", valueTable[i].name);
1406 cliPrintVar(value, 0);
1407 cliPrint("\r\n");
1411 typedef enum {
1412 DUMP_MASTER = (1 << 0),
1413 DUMP_PROFILE = (1 << 1),
1414 DUMP_CONTROL_RATE_PROFILE = (1 << 2)
1415 } dumpFlags_e;
1417 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
1420 static const char* const sectionBreak = "\r\n";
1422 #define printSectionBreak() printf((char *)sectionBreak)
1424 static void cliDump(char *cmdline)
1426 unsigned int i;
1427 char buf[16];
1428 uint32_t mask;
1430 #ifndef USE_QUAD_MIXER_ONLY
1431 float thr, roll, pitch, yaw;
1432 #endif
1434 uint8_t dumpMask = DUMP_ALL;
1435 if (strcasecmp(cmdline, "master") == 0) {
1436 dumpMask = DUMP_MASTER; // only
1438 if (strcasecmp(cmdline, "profile") == 0) {
1439 dumpMask = DUMP_PROFILE; // only
1441 if (strcasecmp(cmdline, "rates") == 0) {
1442 dumpMask = DUMP_CONTROL_RATE_PROFILE; // only
1445 if (dumpMask & DUMP_MASTER) {
1447 cliPrint("\r\n# version\r\n");
1448 cliVersion(NULL);
1450 cliPrint("\r\n# dump master\r\n");
1451 cliPrint("\r\n# mixer\r\n");
1453 #ifndef USE_QUAD_MIXER_ONLY
1454 printf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1456 printf("mmix reset\r\n");
1458 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
1459 if (masterConfig.customMotorMixer[i].throttle == 0.0f)
1460 break;
1461 thr = masterConfig.customMotorMixer[i].throttle;
1462 roll = masterConfig.customMotorMixer[i].roll;
1463 pitch = masterConfig.customMotorMixer[i].pitch;
1464 yaw = masterConfig.customMotorMixer[i].yaw;
1465 printf("mmix %d", i);
1466 if (thr < 0)
1467 cliWrite(' ');
1468 printf("%s", ftoa(thr, buf));
1469 if (roll < 0)
1470 cliWrite(' ');
1471 printf("%s", ftoa(roll, buf));
1472 if (pitch < 0)
1473 cliWrite(' ');
1474 printf("%s", ftoa(pitch, buf));
1475 if (yaw < 0)
1476 cliWrite(' ');
1477 printf("%s\r\n", ftoa(yaw, buf));
1480 // print custom servo mixer if exists
1481 printf("smix reset\r\n");
1483 for (i = 0; i < MAX_SERVO_RULES; i++) {
1485 if (masterConfig.customServoMixer[i].rate == 0)
1486 break;
1488 printf("smix %d %d %d %d %d %d %d %d\r\n",
1490 masterConfig.customServoMixer[i].targetChannel,
1491 masterConfig.customServoMixer[i].inputSource,
1492 masterConfig.customServoMixer[i].rate,
1493 masterConfig.customServoMixer[i].speed,
1494 masterConfig.customServoMixer[i].min,
1495 masterConfig.customServoMixer[i].max,
1496 masterConfig.customServoMixer[i].box
1500 #endif
1502 cliPrint("\r\n\r\n# feature\r\n");
1504 mask = featureMask();
1505 for (i = 0; ; i++) { // disable all feature first
1506 if (featureNames[i] == NULL)
1507 break;
1508 printf("feature -%s\r\n", featureNames[i]);
1510 for (i = 0; ; i++) { // reenable what we want.
1511 if (featureNames[i] == NULL)
1512 break;
1513 if (mask & (1 << i))
1514 printf("feature %s\r\n", featureNames[i]);
1517 cliPrint("\r\n\r\n# map\r\n");
1519 for (i = 0; i < 8; i++)
1520 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1521 buf[i] = '\0';
1522 printf("map %s\r\n", buf);
1524 cliPrint("\r\n\r\n# serial\r\n");
1525 cliSerial("");
1527 #ifdef LED_STRIP
1528 cliPrint("\r\n\r\n# led\r\n");
1529 cliLed("");
1531 cliPrint("\r\n\r\n# color\r\n");
1532 cliColor("");
1533 #endif
1534 printSectionBreak();
1535 dumpValues(MASTER_VALUE);
1537 cliPrint("\r\n# rxfail\r\n");
1538 cliRxFail("");
1541 if (dumpMask & DUMP_PROFILE) {
1542 cliPrint("\r\n# dump profile\r\n");
1544 cliPrint("\r\n# profile\r\n");
1545 cliProfile("");
1547 cliPrint("\r\n# aux\r\n");
1549 cliAux("");
1551 cliPrint("\r\n# adjrange\r\n");
1553 cliAdjustmentRange("");
1555 printf("\r\n# rxrange\r\n");
1557 cliRxRange("");
1559 #ifdef USE_SERVOS
1560 cliPrint("\r\n# servo\r\n");
1562 cliServo("");
1564 // print servo directions
1565 unsigned int channel;
1567 for (i = 0; i < MAX_SUPPORTED_SERVOS; i++) {
1568 for (channel = 0; channel < INPUT_SOURCE_COUNT; channel++) {
1569 if (servoDirection(i, channel) < 0) {
1570 printf("smix reverse %d %d r\r\n", i , channel);
1574 #endif
1576 printSectionBreak();
1578 dumpValues(PROFILE_VALUE);
1581 if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
1582 cliPrint("\r\n# dump rates\r\n");
1584 cliPrint("\r\n# rateprofile\r\n");
1585 cliRateProfile("");
1587 printSectionBreak();
1589 dumpValues(CONTROL_RATE_VALUE);
1593 void cliEnter(serialPort_t *serialPort)
1595 cliMode = 1;
1596 cliPort = serialPort;
1597 setPrintfSerialPort(cliPort);
1598 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1599 cliPrompt();
1600 ENABLE_ARMING_FLAG(PREVENT_ARMING);
1603 static void cliExit(char *cmdline)
1605 UNUSED(cmdline);
1607 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1608 *cliBuffer = '\0';
1609 bufferIndex = 0;
1610 cliMode = 0;
1611 // incase a motor was left running during motortest, clear it here
1612 mixerResetDisarmedMotors();
1613 cliReboot();
1615 cliPort = NULL;
1618 static void cliFeature(char *cmdline)
1620 uint32_t i;
1621 uint32_t len;
1622 uint32_t mask;
1624 len = strlen(cmdline);
1625 mask = featureMask();
1627 if (len == 0) {
1628 cliPrint("Enabled: ");
1629 for (i = 0; ; i++) {
1630 if (featureNames[i] == NULL)
1631 break;
1632 if (mask & (1 << i))
1633 printf("%s ", featureNames[i]);
1635 cliPrint("\r\n");
1636 } else if (strncasecmp(cmdline, "list", len) == 0) {
1637 cliPrint("Available: ");
1638 for (i = 0; ; i++) {
1639 if (featureNames[i] == NULL)
1640 break;
1641 printf("%s ", featureNames[i]);
1643 cliPrint("\r\n");
1644 return;
1645 } else {
1646 bool remove = false;
1647 if (cmdline[0] == '-') {
1648 // remove feature
1649 remove = true;
1650 cmdline++; // skip over -
1651 len--;
1654 for (i = 0; ; i++) {
1655 if (featureNames[i] == NULL) {
1656 cliPrint("Invalid name\r\n");
1657 break;
1660 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
1662 mask = 1 << i;
1663 #ifndef GPS
1664 if (mask & FEATURE_GPS) {
1665 cliPrint("unavailable\r\n");
1666 break;
1668 #endif
1669 #ifndef SONAR
1670 if (mask & FEATURE_SONAR) {
1671 cliPrint("unavailable\r\n");
1672 break;
1674 #endif
1675 if (remove) {
1676 featureClear(mask);
1677 cliPrint("Disabled");
1678 } else {
1679 featureSet(mask);
1680 cliPrint("Enabled");
1682 printf(" %s\r\n", featureNames[i]);
1683 break;
1689 #ifdef GPS
1690 static void cliGpsPassthrough(char *cmdline)
1692 UNUSED(cmdline);
1694 gpsEnablePassthrough(cliPort);
1696 #endif
1698 static void cliHelp(char *cmdline)
1700 uint32_t i = 0;
1702 UNUSED(cmdline);
1704 for (i = 0; i < CMD_COUNT; i++) {
1705 cliPrint(cmdTable[i].name);
1706 #ifndef SKIP_CLI_COMMAND_HELP
1707 if (cmdTable[i].description) {
1708 printf(" - %s", cmdTable[i].description);
1710 if (cmdTable[i].args) {
1711 printf("\r\n\t%s", cmdTable[i].args);
1713 #endif
1714 cliPrint("\r\n");
1718 static void cliMap(char *cmdline)
1720 uint32_t len;
1721 uint32_t i;
1722 char out[9];
1724 len = strlen(cmdline);
1726 if (len == 8) {
1727 // uppercase it
1728 for (i = 0; i < 8; i++)
1729 cmdline[i] = toupper((unsigned char)cmdline[i]);
1730 for (i = 0; i < 8; i++) {
1731 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
1732 continue;
1733 cliShowParseError();
1734 return;
1736 parseRcChannels(cmdline, &masterConfig.rxConfig);
1738 cliPrint("Map: ");
1739 for (i = 0; i < 8; i++)
1740 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1741 out[i] = '\0';
1742 printf("%s\r\n", out);
1745 #ifndef USE_QUAD_MIXER_ONLY
1746 static void cliMixer(char *cmdline)
1748 int i;
1749 int len;
1751 len = strlen(cmdline);
1753 if (len == 0) {
1754 printf("Mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1755 return;
1756 } else if (strncasecmp(cmdline, "list", len) == 0) {
1757 cliPrint("Available mixers: ");
1758 for (i = 0; ; i++) {
1759 if (mixerNames[i] == NULL)
1760 break;
1761 printf("%s ", mixerNames[i]);
1763 cliPrint("\r\n");
1764 return;
1767 for (i = 0; ; i++) {
1768 if (mixerNames[i] == NULL) {
1769 cliPrint("Invalid name\r\n");
1770 return;
1772 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
1773 masterConfig.mixerMode = i + 1;
1774 break;
1778 cliMixer("");
1780 #endif
1782 static void cliMotor(char *cmdline)
1784 int motor_index = 0;
1785 int motor_value = 0;
1786 int index = 0;
1787 char *pch = NULL;
1788 char *saveptr;
1790 if (isEmpty(cmdline)) {
1791 cliShowParseError();
1792 return;
1795 pch = strtok_r(cmdline, " ", &saveptr);
1796 while (pch != NULL) {
1797 switch (index) {
1798 case 0:
1799 motor_index = atoi(pch);
1800 break;
1801 case 1:
1802 motor_value = atoi(pch);
1803 break;
1805 index++;
1806 pch = strtok_r(NULL, " ", &saveptr);
1809 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
1810 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS);
1811 return;
1814 if (index == 2) {
1815 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
1816 cliShowArgumentRangeError("value", 1000, 2000);
1817 return;
1818 } else {
1819 motor_disarmed[motor_index] = motor_value;
1823 printf("motor %d: %d\r\n", motor_index, motor_disarmed[motor_index]);
1826 static void cliPlaySound(char *cmdline)
1828 #if FLASH_SIZE <= 64
1829 UNUSED(cmdline);
1830 #else
1831 int i;
1832 const char *name;
1833 static int lastSoundIdx = -1;
1835 if (isEmpty(cmdline)) {
1836 i = lastSoundIdx + 1; //next sound index
1837 if ((name=beeperNameForTableIndex(i)) == NULL) {
1838 while (true) { //no name for index; try next one
1839 if (++i >= beeperTableEntryCount())
1840 i = 0; //if end then wrap around to first entry
1841 if ((name=beeperNameForTableIndex(i)) != NULL)
1842 break; //if name OK then play sound below
1843 if (i == lastSoundIdx + 1) { //prevent infinite loop
1844 printf("Error playing sound\r\n");
1845 return;
1849 } else { //index value was given
1850 i = atoi(cmdline);
1851 if ((name=beeperNameForTableIndex(i)) == NULL) {
1852 printf("No sound for index %d\r\n", i);
1853 return;
1856 lastSoundIdx = i;
1857 beeperSilence();
1858 printf("Playing sound %d: %s\r\n", i, name);
1859 beeper(beeperModeForTableIndex(i));
1860 #endif
1863 static void cliProfile(char *cmdline)
1865 int i;
1867 if (isEmpty(cmdline)) {
1868 printf("profile %d\r\n", getCurrentProfile());
1869 return;
1870 } else {
1871 i = atoi(cmdline);
1872 if (i >= 0 && i < MAX_PROFILE_COUNT) {
1873 masterConfig.current_profile_index = i;
1874 writeEEPROM();
1875 readEEPROM();
1876 cliProfile("");
1881 static void cliRateProfile(char *cmdline)
1883 int i;
1885 if (isEmpty(cmdline)) {
1886 printf("rateprofile %d\r\n", getCurrentControlRateProfile());
1887 return;
1888 } else {
1889 i = atoi(cmdline);
1890 if (i >= 0 && i < MAX_CONTROL_RATE_PROFILE_COUNT) {
1891 changeControlRateProfile(i);
1892 cliRateProfile("");
1897 static void cliReboot(void) {
1898 cliPrint("\r\nRebooting");
1899 waitForSerialPortToFinishTransmitting(cliPort);
1900 stopMotors();
1901 handleOneshotFeatureChangeOnRestart();
1902 systemReset();
1905 static void cliSave(char *cmdline)
1907 UNUSED(cmdline);
1909 cliPrint("Saving");
1910 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
1911 writeEEPROM();
1912 cliReboot();
1915 static void cliDefaults(char *cmdline)
1917 UNUSED(cmdline);
1919 cliPrint("Resetting to defaults");
1920 resetEEPROM();
1921 cliReboot();
1924 static void cliPrint(const char *str)
1926 while (*str)
1927 serialWrite(cliPort, *(str++));
1930 static void cliWrite(uint8_t ch)
1932 serialWrite(cliPort, ch);
1935 static void cliPrintVar(const clivalue_t *var, uint32_t full)
1937 int32_t value = 0;
1938 char buf[8];
1940 void *ptr = var->ptr;
1941 if (var->type & PROFILE_VALUE) {
1942 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
1944 if (var->type & CONTROL_RATE_VALUE) {
1945 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
1948 switch (var->type & VALUE_TYPE_MASK) {
1949 case VAR_UINT8:
1950 value = *(uint8_t *)ptr;
1951 break;
1953 case VAR_INT8:
1954 value = *(int8_t *)ptr;
1955 break;
1957 case VAR_UINT16:
1958 value = *(uint16_t *)ptr;
1959 break;
1961 case VAR_INT16:
1962 value = *(int16_t *)ptr;
1963 break;
1965 case VAR_UINT32:
1966 value = *(uint32_t *)ptr;
1967 break;
1969 case VAR_FLOAT:
1970 printf("%s", ftoa(*(float *)ptr, buf));
1971 if (full) {
1972 printf(" %s", ftoa((float)var->min, buf));
1973 printf(" %s", ftoa((float)var->max, buf));
1975 return; // return from case for float only
1977 printf("%d", value);
1978 if (full)
1979 printf(" %d %d", var->min, var->max);
1982 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
1984 void *ptr = var->ptr;
1985 if (var->type & PROFILE_VALUE) {
1986 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
1988 if (var->type & CONTROL_RATE_VALUE) {
1989 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
1992 switch (var->type & VALUE_TYPE_MASK) {
1993 case VAR_UINT8:
1994 case VAR_INT8:
1995 *(int8_t *)ptr = value.int_value;
1996 break;
1998 case VAR_UINT16:
1999 case VAR_INT16:
2000 *(int16_t *)ptr = value.int_value;
2001 break;
2003 case VAR_UINT32:
2004 *(uint32_t *)ptr = value.int_value;
2005 break;
2007 case VAR_FLOAT:
2008 *(float *)ptr = (float)value.float_value;
2009 break;
2013 static void cliSet(char *cmdline)
2015 uint32_t i;
2016 uint32_t len;
2017 const clivalue_t *val;
2018 char *eqptr = NULL;
2019 int32_t value = 0;
2020 float valuef = 0;
2022 len = strlen(cmdline);
2024 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
2025 cliPrint("Current settings: \r\n");
2026 for (i = 0; i < VALUE_COUNT; i++) {
2027 val = &valueTable[i];
2028 printf("%s = ", valueTable[i].name);
2029 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2030 cliPrint("\r\n");
2032 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
2033 // has equal, set var
2034 char *lastNonSpaceCharacter = eqptr;
2035 while (*(lastNonSpaceCharacter - 1) == ' ') {
2036 lastNonSpaceCharacter--;
2038 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
2040 eqptr++;
2041 len--;
2042 value = atoi(eqptr);
2043 valuef = fastA2F(eqptr);
2044 for (i = 0; i < VALUE_COUNT; i++) {
2045 val = &valueTable[i];
2046 // ensure exact match when setting to prevent setting variables with shorter names
2047 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
2048 if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT?
2049 int_float_value_t tmp;
2050 if (valueTable[i].type & VAR_FLOAT)
2051 tmp.float_value = valuef;
2052 else
2053 tmp.int_value = value;
2054 cliSetVar(val, tmp);
2055 printf("%s set to ", valueTable[i].name);
2056 cliPrintVar(val, 0);
2057 } else {
2058 cliPrint("Value assignment out of range\r\n");
2060 return;
2063 cliPrint("Invalid name\r\n");
2064 } else {
2065 // no equals, check for matching variables.
2066 cliGet(cmdline);
2070 static void cliGet(char *cmdline)
2072 uint32_t i;
2073 const clivalue_t *val;
2074 int matchedCommands = 0;
2076 for (i = 0; i < VALUE_COUNT; i++) {
2077 if (strstr(valueTable[i].name, cmdline)) {
2078 val = &valueTable[i];
2079 printf("%s = ", valueTable[i].name);
2080 cliPrintVar(val, 0);
2081 cliPrint("\r\n");
2083 matchedCommands++;
2088 if (matchedCommands) {
2089 return;
2092 cliPrint("Invalid name\r\n");
2095 static void cliStatus(char *cmdline)
2097 UNUSED(cmdline);
2099 printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s)\r\n",
2100 millis() / 1000, vbat, batteryCellCount, getBatteryStateString());
2103 printf("CPU Clock=%dMHz", (SystemCoreClock / 1000000));
2105 #ifndef CJMCU
2106 uint8_t i;
2107 uint32_t mask;
2108 uint32_t detectedSensorsMask = sensorsMask();
2110 for (i = 0; ; i++) {
2112 if (sensorTypeNames[i] == NULL)
2113 break;
2115 mask = (1 << i);
2116 if ((detectedSensorsMask & mask) && (mask & SENSOR_NAMES_MASK)) {
2117 const char *sensorHardware;
2118 uint8_t sensorHardwareIndex = detectedSensors[i];
2119 sensorHardware = sensorHardwareNames[i][sensorHardwareIndex];
2121 printf(", %s=%s", sensorTypeNames[i], sensorHardware);
2123 if (mask == SENSOR_ACC && acc.revisionCode) {
2124 printf(".%c", acc.revisionCode);
2128 #endif
2129 cliPrint("\r\n");
2131 #ifdef USE_I2C
2132 uint16_t i2cErrorCounter = i2cGetErrorCounter();
2133 #else
2134 uint16_t i2cErrorCounter = 0;
2135 #endif
2137 printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
2140 static void cliVersion(char *cmdline)
2142 UNUSED(cmdline);
2144 printf("# Cleanflight/%s %s %s / %s (%s)",
2145 targetName,
2146 FC_VERSION_STRING,
2147 buildDate,
2148 buildTime,
2149 shortGitRevision
2153 void cliProcess(void)
2155 if (!cliPort) {
2156 return;
2159 while (serialRxBytesWaiting(cliPort)) {
2160 uint8_t c = serialRead(cliPort);
2161 if (c == '\t' || c == '?') {
2162 // do tab completion
2163 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
2164 uint32_t i = bufferIndex;
2165 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2166 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
2167 continue;
2168 if (!pstart)
2169 pstart = cmd;
2170 pend = cmd;
2172 if (pstart) { /* Buffer matches one or more commands */
2173 for (; ; bufferIndex++) {
2174 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
2175 break;
2176 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
2177 /* Unambiguous -- append a space */
2178 cliBuffer[bufferIndex++] = ' ';
2179 cliBuffer[bufferIndex] = '\0';
2180 break;
2182 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
2185 if (!bufferIndex || pstart != pend) {
2186 /* Print list of ambiguous matches */
2187 cliPrint("\r\033[K");
2188 for (cmd = pstart; cmd <= pend; cmd++) {
2189 cliPrint(cmd->name);
2190 cliWrite('\t');
2192 cliPrompt();
2193 i = 0; /* Redraw prompt */
2195 for (; i < bufferIndex; i++)
2196 cliWrite(cliBuffer[i]);
2197 } else if (!bufferIndex && c == 4) { // CTRL-D
2198 cliExit(cliBuffer);
2199 return;
2200 } else if (c == 12) { // NewPage / CTRL-L
2201 // clear screen
2202 cliPrint("\033[2J\033[1;1H");
2203 cliPrompt();
2204 } else if (bufferIndex && (c == '\n' || c == '\r')) {
2205 // enter pressed
2206 cliPrint("\r\n");
2208 // Strip comment starting with # from line
2209 char *p = cliBuffer;
2210 p = strchr(p, '#');
2211 if (NULL != p) {
2212 bufferIndex = (uint32_t)(p - cliBuffer);
2215 // Strip trailing whitespace
2216 while (bufferIndex > 0 && cliBuffer[bufferIndex - 1] == ' ') {
2217 bufferIndex--;
2220 // Process non-empty lines
2221 if (bufferIndex > 0) {
2222 cliBuffer[bufferIndex] = 0; // null terminate
2224 const clicmd_t *cmd;
2225 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
2226 if(!strncasecmp(cliBuffer, cmd->name, strlen(cmd->name)) // command names match
2227 && !isalnum((unsigned)cliBuffer[strlen(cmd->name)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2228 break;
2230 if(cmd < cmdTable + CMD_COUNT)
2231 cmd->func(cliBuffer + strlen(cmd->name) + 1);
2232 else
2233 cliPrint("Unknown command, try 'help'");
2234 bufferIndex = 0;
2237 memset(cliBuffer, 0, sizeof(cliBuffer));
2239 // 'exit' will reset this flag, so we don't need to print prompt again
2240 if (!cliMode)
2241 return;
2243 cliPrompt();
2244 } else if (c == 127) {
2245 // backspace
2246 if (bufferIndex) {
2247 cliBuffer[--bufferIndex] = 0;
2248 cliPrint("\010 \010");
2250 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
2251 if (!bufferIndex && c == ' ')
2252 continue; // Ignore leading spaces
2253 cliBuffer[bufferIndex++] = c;
2254 cliWrite(c);
2259 void cliInit(serialConfig_t *serialConfig)
2261 UNUSED(serialConfig);
2263 #endif