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/>.
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"
51 #include "io/gimbal.h"
52 #include "io/rc_controls.h"
53 #include "io/serial.h"
54 #include "io/serial_1wire.h"
55 #include "io/ledstrip.h"
56 #include "io/flashfs.h"
57 #include "io/beeper.h"
60 #include "rx/spektrum.h"
62 #include "sensors/battery.h"
63 #include "sensors/boardalignment.h"
64 #include "sensors/sensors.h"
65 #include "sensors/acceleration.h"
66 #include "sensors/gyro.h"
67 #include "sensors/compass.h"
68 #include "sensors/barometer.h"
70 #include "flight/pid.h"
71 #include "flight/imu.h"
72 #include "flight/mixer.h"
73 #include "flight/navigation.h"
74 #include "flight/failsafe.h"
76 #include "telemetry/telemetry.h"
77 #include "telemetry/frsky.h"
79 #include "config/runtime_config.h"
80 #include "config/config.h"
81 #include "config/config_profile.h"
82 #include "config/config_master.h"
84 #include "common/printf.h"
86 #include "serial_cli.h"
88 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
89 // signal that we're in cli mode
94 extern uint16_t cycleTime
; // FIXME dependency on mw.c
96 void gpsEnablePassthrough(serialPort_t
*gpsPassthroughPort
);
98 static serialPort_t
*cliPort
;
100 static void cliAux(char *cmdline
);
101 static void cliRxFail(char *cmdline
);
102 static void cliAdjustmentRange(char *cmdline
);
103 static void cliMotorMix(char *cmdline
);
104 static void cliDefaults(char *cmdline
);
105 static void cliDump(char *cmdLine
);
106 static void cliExit(char *cmdline
);
107 static void cliFeature(char *cmdline
);
108 static void cliMotor(char *cmdline
);
109 static void cliPlaySound(char *cmdline
);
110 static void cliProfile(char *cmdline
);
111 static void cliRateProfile(char *cmdline
);
112 static void cliReboot(void);
113 static void cliSave(char *cmdline
);
114 static void cliSerial(char *cmdline
);
117 static void cliServo(char *cmdline
);
118 static void cliServoMix(char *cmdline
);
121 static void cliSet(char *cmdline
);
122 static void cliGet(char *cmdline
);
123 static void cliStatus(char *cmdline
);
124 static void cliVersion(char *cmdline
);
125 static void cliRxRange(char *cmdline
);
128 static void cliGpsPassthrough(char *cmdline
);
131 static void cliHelp(char *cmdline
);
132 static void cliMap(char *cmdline
);
135 static void cliLed(char *cmdline
);
136 static void cliColor(char *cmdline
);
139 #ifndef USE_QUAD_MIXER_ONLY
140 static void cliMixer(char *cmdline
);
144 static void cliFlashInfo(char *cmdline
);
145 static void cliFlashErase(char *cmdline
);
146 #ifdef USE_FLASH_TOOLS
147 static void cliFlashWrite(char *cmdline
);
148 static void cliFlashRead(char *cmdline
);
152 #ifdef USE_SERIAL_1WIRE
153 static void cliUSB1Wire(char *cmdline
);
157 static char cliBuffer
[48];
158 static uint32_t bufferIndex
= 0;
160 #ifndef USE_QUAD_MIXER_ONLY
161 // sync this with mixerMode_e
162 static const char * const mixerNames
[] = {
163 "TRI", "QUADP", "QUADX", "BI",
164 "GIMBAL", "Y6", "HEX6",
165 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
166 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
167 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
168 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
172 // sync this with features_e
173 static const char * const featureNames
[] = {
174 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
175 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
176 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
177 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
178 "BLACKBOX", "CHANNEL_FORWARDING", NULL
181 // sync this with rxFailsafeChannelMode_e
182 static const char rxFailsafeModeCharacters
[] = "ahs";
184 static const rxFailsafeChannelMode_e rxFailsafeModesTable
[RX_FAILSAFE_TYPE_COUNT
][RX_FAILSAFE_MODE_COUNT
] = {
185 { RX_FAILSAFE_MODE_AUTO
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_INVALID
},
186 { RX_FAILSAFE_MODE_INVALID
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
}
190 // sync this with sensors_e
191 static const char * const sensorTypeNames
[] = {
192 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
195 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
197 static const char * const sensorHardwareNames
[4][11] = {
198 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "FAKE", NULL
},
199 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", NULL
},
200 { "", "None", "BMP085", "MS5611", NULL
},
201 { "", "None", "HMC5883", "AK8975", NULL
}
207 const char *description
;
210 void (*func
)(char *cmdline
);
213 #ifndef SKIP_CLI_COMMAND_HELP
214 #define CLI_COMMAND_DEF(name, description, args, method) \
222 #define CLI_COMMAND_DEF(name, description, args, method) \
231 // should be sorted a..z for bsearch()
232 const clicmd_t cmdTable
[] = {
233 #ifdef USE_SERIAL_1WIRE
234 CLI_COMMAND_DEF("1wire", "1-wire interface to escs", "<esc index>", cliUSB1Wire
),
236 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL
, cliAdjustmentRange
),
237 CLI_COMMAND_DEF("aux", "configure modes", NULL
, cliAux
),
239 CLI_COMMAND_DEF("color", "configure colors", NULL
, cliColor
),
241 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL
, cliDefaults
),
242 CLI_COMMAND_DEF("dump", "dump configuration",
243 "[master|profile]", cliDump
),
244 CLI_COMMAND_DEF("exit", NULL
, NULL
, cliExit
),
245 CLI_COMMAND_DEF("feature", "configure features",
247 "\t<+|->[name]", cliFeature
),
249 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL
, cliFlashErase
),
250 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL
, cliFlashInfo
),
251 #ifdef USE_FLASH_TOOLS
252 CLI_COMMAND_DEF("flash_read", NULL
, "<length> <address>", cliFlashRead
),
253 CLI_COMMAND_DEF("flash_write", NULL
, "<address> <message>", cliFlashWrite
),
256 CLI_COMMAND_DEF("get", "get variable value",
259 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL
, cliGpsPassthrough
),
261 CLI_COMMAND_DEF("help", NULL
, NULL
, cliHelp
),
263 CLI_COMMAND_DEF("led", "configure leds", NULL
, cliLed
),
265 CLI_COMMAND_DEF("map", "configure rc channel order",
267 #ifndef USE_QUAD_MIXER_ONLY
268 CLI_COMMAND_DEF("mixer", "configure mixer",
270 "\t<name>", cliMixer
),
272 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL
, cliMotorMix
),
273 CLI_COMMAND_DEF("motor", "get/set motor",
274 "<index> [<value>]", cliMotor
),
275 CLI_COMMAND_DEF("play_sound", NULL
,
276 "[<index>]\r\n", cliPlaySound
),
277 CLI_COMMAND_DEF("profile", "change profile",
278 "[<index>]", cliProfile
),
279 CLI_COMMAND_DEF("rateprofile", "change rate profile",
280 "[<index>]", cliRateProfile
),
281 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL
, cliRxRange
),
282 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL
, cliRxFail
),
283 CLI_COMMAND_DEF("save", "save and reboot", NULL
, cliSave
),
284 CLI_COMMAND_DEF("serial", "configure serial ports", NULL
, cliSerial
),
286 CLI_COMMAND_DEF("servo", "configure servos", NULL
, cliServo
),
288 CLI_COMMAND_DEF("set", "change setting",
289 "[<name>=<value>]", cliSet
),
291 CLI_COMMAND_DEF("smix", "servo mixer",
292 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
295 "\treverse <servo> <source> r|n", cliServoMix
),
297 CLI_COMMAND_DEF("status", "show status", NULL
, cliStatus
),
298 CLI_COMMAND_DEF("version", "show version", NULL
, cliVersion
),
300 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
303 VAR_UINT8
= (1 << 0),
305 VAR_UINT16
= (1 << 2),
306 VAR_INT16
= (1 << 3),
307 VAR_UINT32
= (1 << 4),
308 VAR_FLOAT
= (1 << 5),
310 MASTER_VALUE
= (1 << 6),
311 PROFILE_VALUE
= (1 << 7),
312 CONTROL_RATE_VALUE
= (1 << 8)
315 #define VALUE_TYPE_MASK (VAR_UINT8 | VAR_INT8 | VAR_UINT16 | VAR_INT16 | VAR_UINT32 | VAR_FLOAT)
316 #define SECTION_MASK (MASTER_VALUE | PROFILE_VALUE | CONTROL_RATE_VALUE)
320 const uint16_t type
; // cliValueFlag_e - specify one of each from VALUE_TYPE_MASK and SECTION_MASK
326 const clivalue_t valueTable
[] = {
327 { "emf_avoidance", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.emf_avoidance
, 0, 1 },
328 { "rc_smoothing", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rcSmoothing
, 0, 1 },
330 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.midrc
, 1200, 1700 },
331 { "min_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.mincheck
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
332 { "max_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.maxcheck
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
333 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_channel
, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
},
334 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_scale
, RSSI_SCALE_MIN
, RSSI_SCALE_MAX
},
335 { "rssi_ppm_invert", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_ppm_invert
, 0, 1 },
336 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
, &masterConfig
.inputFilteringMode
, 0, 1 },
338 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.minthrottle
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
339 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.maxthrottle
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
340 { "min_command", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.mincommand
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
341 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.servoCenterPulse
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
343 { "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
344 { "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,
345 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.neutral3d
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
346 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_throttle
, PWM_RANGE_ZERO
, PWM_RANGE_MAX
},
348 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motor_pwm_rate
, 50, 32000 },
349 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servo_pwm_rate
, 50, 498 },
351 { "retarded_arm", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.retarded_arm
, 0, 1 },
352 { "disarm_kill_switch", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.disarm_kill_switch
, 0, 1 },
353 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.auto_disarm_delay
, 0, 60 },
354 { "small_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.small_angle
, 0, 180 },
356 { "fixedwing_althold_dir", VAR_INT8
| MASTER_VALUE
, &masterConfig
.airplaneConfig
.fixedwing_althold_dir
, -1, 1 },
358 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.serialConfig
.reboot_character
, 48, 126 },
361 { "gps_provider", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gpsConfig
.provider
, 0, GPS_PROVIDER_MAX
},
362 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gpsConfig
.sbasMode
, 0, SBAS_MODE_MAX
},
363 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gpsConfig
.autoConfig
, GPS_AUTOCONFIG_OFF
, GPS_AUTOCONFIG_ON
},
364 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gpsConfig
.autoBaud
, GPS_AUTOBAUD_OFF
, GPS_AUTOBAUD_ON
},
366 { "gps_pos_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOS
], 0, 200 },
367 { "gps_pos_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOS
], 0, 200 },
368 { "gps_pos_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOS
], 0, 200 },
369 { "gps_posr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOSR
], 0, 200 },
370 { "gps_posr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOSR
], 0, 200 },
371 { "gps_posr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOSR
], 0, 200 },
372 { "gps_nav_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDNAVR
], 0, 200 },
373 { "gps_nav_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDNAVR
], 0, 200 },
374 { "gps_nav_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDNAVR
], 0, 200 },
375 { "gps_wp_radius", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].gpsProfile
.gps_wp_radius
, 0, 2000 },
376 { "nav_controls_heading", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].gpsProfile
.nav_controls_heading
, 0, 1 },
377 { "nav_speed_min", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].gpsProfile
.nav_speed_min
, 10, 2000 },
378 { "nav_speed_max", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].gpsProfile
.nav_speed_max
, 10, 2000 },
379 { "nav_slew_rate", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].gpsProfile
.nav_slew_rate
, 0, 100 },
382 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.serialrx_provider
, 0, SERIALRX_PROVIDER_MAX
},
383 { "spektrum_sat_bind", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.spektrum_sat_bind
, SPEKTRUM_SAT_BIND_DISABLED
, SPEKTRUM_SAT_BIND_MAX
},
385 { "telemetry_switch", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.telemetry_switch
, 0, 1 },
386 { "telemetry_inversion", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.telemetry_inversion
, 0, 1 },
387 { "frsky_default_lattitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLatitude
, -90.0, 90.0 },
388 { "frsky_default_longitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLongitude
, -180.0, 180.0 },
389 { "frsky_coordinates_format", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_coordinate_format
, 0, FRSKY_FORMAT_NMEA
},
390 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_unit
, 0, FRSKY_UNIT_IMPERIALS
},
391 { "frsky_vfas_precision", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_vfas_precision
, FRSKY_VFAS_PRECISION_LOW
, FRSKY_VFAS_PRECISION_HIGH
},
392 { "hott_alarm_sound_interval", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.hottAlarmSoundInterval
, 0, 120 },
394 { "battery_capacity", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.batteryCapacity
, 0, 20000 },
395 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatscale
, VBAT_SCALE_MIN
, VBAT_SCALE_MAX
},
396 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmaxcellvoltage
, 10, 50 },
397 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmincellvoltage
, 10, 50 },
398 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatwarningcellvoltage
, 10, 50 },
399 { "current_meter_scale", VAR_INT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterScale
, -10000, 10000 },
400 { "current_meter_offset", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterOffset
, 0, 3300 },
401 { "multiwii_current_meter_output", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.multiwiiCurrentMeterOutput
, 0, 1 },
402 { "current_meter_type", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterType
, 0, CURRENT_SENSOR_MAX
},
404 { "align_gyro", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.sensorAlignmentConfig
.gyro_align
, 0, 8 },
405 { "align_acc", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.sensorAlignmentConfig
.acc_align
, 0, 8 },
406 { "align_mag", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.sensorAlignmentConfig
.mag_align
, 0, 8 },
408 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.rollDegrees
, -180, 360 },
409 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.pitchDegrees
, -180, 360 },
410 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.yawDegrees
, -180, 360 },
412 { "max_angle_inclination", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.max_angle_inclination
, 100, 900 },
414 { "gyro_lpf", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyro_lpf
, 0, 256 },
415 { "moron_threshold", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyroMovementCalibrationThreshold
, 0, 128 },
416 { "gyro_cmpf_factor", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyro_cmpf_factor
, 100, 1000 },
417 { "gyro_cmpfm_factor", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyro_cmpfm_factor
, 100, 1000 },
419 { "alt_hold_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.alt_hold_deadband
, 1, 250 },
420 { "alt_hold_fast_change", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.alt_hold_fast_change
, 0, 1 },
421 { "deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.deadband
, 0, 32 },
422 { "yaw_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.yaw_deadband
, 0, 100 },
424 { "throttle_correction_value", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].throttle_correction_value
, 0, 150 },
425 { "throttle_correction_angle", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].throttle_correction_angle
, 1, 900 },
427 { "yaw_control_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.yaw_control_direction
, -1, 1 },
429 { "pid_at_min_throttle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.pid_at_min_throttle
, 0, 1 },
430 { "yaw_motor_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_motor_direction
, -1, 1 },
431 { "yaw_jump_prevention_limit", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_jump_prevention_limit
, YAW_JUMP_PREVENTION_LIMIT_LOW
, YAW_JUMP_PREVENTION_LIMIT_HIGH
},
433 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.tri_unarmed_servo
, 0, 1 },
434 { "servo_lowpass_freq", VAR_INT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.servo_lowpass_freq
, 10, 400},
435 { "servo_lowpass_enable", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.servo_lowpass_enable
, 0, 1 },
438 { "default_rate_profile", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].defaultRateProfileIndex
, 0, MAX_CONTROL_RATE_PROFILE_COUNT
- 1 },
439 { "rc_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcRate8
, 0, 250 },
440 { "rc_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcExpo8
, 0, 100 },
441 { "rc_yaw_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcYawExpo8
, 0, 100 },
442 { "thr_mid", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrMid8
, 0, 100 },
443 { "thr_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrExpo8
, 0, 100 },
444 { "roll_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_ROLL
], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
},
445 { "pitch_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_PITCH
], 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
},
446 { "yaw_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_YAW
], 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX
},
447 { "tpa_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].dynThrPID
, 0, CONTROL_RATE_CONFIG_TPA_MAX
},
448 { "tpa_breakpoint", VAR_UINT16
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].tpa_breakpoint
, PWM_RANGE_MIN
, PWM_RANGE_MAX
},
450 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_delay
, 0, 200 },
451 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_off_delay
, 0, 200 },
452 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle
, PWM_RANGE_MIN
, PWM_RANGE_MAX
},
453 { "failsafe_kill_switch", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_kill_switch
, 0, 1 },
454 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
, 0, 300 },
456 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_min_usec
, PWM_PULSE_MIN
, PWM_PULSE_MAX
},
457 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_max_usec
, PWM_PULSE_MIN
, PWM_PULSE_MAX
},
460 { "gimbal_mode", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].gimbalConfig
.mode
, 0, GIMBAL_MODE_MAX
},
463 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.acc_hardware
, 0, ACC_MAX
},
464 { "acc_lpf_factor", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].acc_lpf_factor
, 0, 250 },
465 { "accxy_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].accDeadband
.xy
, 0, 100 },
466 { "accz_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].accDeadband
.z
, 0, 100 },
467 { "accz_lpf_cutoff", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].accz_lpf_cutoff
, 1, 20 },
468 { "acc_unarmedcal", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].acc_unarmedcal
, 0, 1 },
469 { "acc_trim_pitch", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].accelerometerTrims
.values
.pitch
, -300, 300 },
470 { "acc_trim_roll", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].accelerometerTrims
.values
.roll
, -300, 300 },
472 { "baro_tab_size", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_sample_count
, 0, BARO_SAMPLE_COUNT_MAX
},
473 { "baro_noise_lpf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_noise_lpf
, 0, 1 },
474 { "baro_cf_vel", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_cf_vel
, 0, 1 },
475 { "baro_cf_alt", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].barometerConfig
.baro_cf_alt
, 0, 1 },
476 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.baro_hardware
, 0, BARO_MAX
},
478 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.mag_hardware
, 0, MAG_MAX
},
479 { "mag_declination", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].mag_declination
, -18000, 18000 },
481 { "pid_controller", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.pidController
, 0, 5 },
483 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PITCH
], 0, 200 },
484 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PITCH
], 0, 200 },
485 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PITCH
], 0, 200 },
486 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[ROLL
], 0, 200 },
487 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[ROLL
], 0, 200 },
488 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[ROLL
], 0, 200 },
489 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[YAW
], 0, 200 },
490 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[YAW
], 0, 200 },
491 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[YAW
], 0, 200 },
493 { "p_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[PITCH
], 0, 100 },
494 { "i_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[PITCH
], 0, 100 },
495 { "d_pitchf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[PITCH
], 0, 100 },
496 { "p_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[ROLL
], 0, 100 },
497 { "i_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[ROLL
], 0, 100 },
498 { "d_rollf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[ROLL
], 0, 100 },
499 { "p_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P_f
[YAW
], 0, 100 },
500 { "i_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I_f
[YAW
], 0, 100 },
501 { "d_yawf", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D_f
[YAW
], 0, 100 },
503 { "level_horizon", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.H_level
, 0, 10 },
504 { "level_angle", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.A_level
, 0, 10 },
505 { "sensitivity_horizon", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.H_sensitivity
, 0, 250 },
507 { "p_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDALT
], 0, 200 },
508 { "i_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDALT
], 0, 200 },
509 { "d_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDALT
], 0, 200 },
511 { "p_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDLEVEL
], 0, 200 },
512 { "i_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDLEVEL
], 0, 200 },
513 { "d_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDLEVEL
], 0, 200 },
515 { "p_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDVEL
], 0, 200 },
516 { "i_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDVEL
], 0, 200 },
517 { "d_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDVEL
], 0, 200 },
519 { "yaw_p_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_p_limit
, YAW_P_LIMIT_MIN
, YAW_P_LIMIT_MAX
},
520 { "dterm_cut_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_cut_hz
, 0, 200 },
523 { "blackbox_rate_num", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_num
, 1, 32 },
524 { "blackbox_rate_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_denom
, 1, 32 },
525 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_device
, 0, 1 },
528 { "magzero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[X
], -32768, 32767 },
529 { "magzero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Y
], -32768, 32767 },
530 { "magzero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Z
], -32768, 32767 },
533 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
541 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
);
542 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
);
543 static void cliPrint(const char *str
);
544 static void cliWrite(uint8_t ch
);
546 static void cliPrompt(void)
551 static void cliShowParseError(void)
553 cliPrint("Parse error\r\n");
556 static void cliShowArgumentRangeError(char *name
, int min
, int max
)
558 printf("%s must be between %d and %d\r\n", name
, min
, max
);
561 static char *processChannelRangeArgs(char *ptr
, channelRange_t
*range
, uint8_t *validArgumentCount
)
565 for (int argIndex
= 0; argIndex
< 2; argIndex
++) {
566 ptr
= strchr(ptr
, ' ');
569 val
= CHANNEL_VALUE_TO_STEP(val
);
570 if (val
>= MIN_MODE_RANGE_STEP
&& val
<= MAX_MODE_RANGE_STEP
) {
572 range
->startStep
= val
;
574 range
->endStep
= val
;
576 (*validArgumentCount
)++;
584 // Check if a string's length is zero
585 static bool isEmpty(const char *string
)
587 return *string
== '\0';
590 static void cliRxFail(char *cmdline
)
595 if (isEmpty(cmdline
)) {
596 // print out rxConfig failsafe settings
597 for (channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
598 cliRxFail(itoa(channel
, buf
, 10));
602 channel
= atoi(ptr
++);
603 if ((channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
)) {
605 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[channel
];
608 rxFailsafeChannelType_e type
= (channel
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_TYPE_FLIGHT
: RX_FAILSAFE_TYPE_AUX
;
609 rxFailsafeChannelMode_e mode
= channelFailsafeConfiguration
->mode
;
610 bool requireValue
= channelFailsafeConfiguration
->mode
== RX_FAILSAFE_MODE_SET
;
612 ptr
= strchr(ptr
, ' ');
614 char *p
= strchr(rxFailsafeModeCharacters
, *(++ptr
));
616 uint8_t requestedMode
= p
- rxFailsafeModeCharacters
;
617 mode
= rxFailsafeModesTable
[type
][requestedMode
];
619 mode
= RX_FAILSAFE_MODE_INVALID
;
621 if (mode
== RX_FAILSAFE_MODE_INVALID
) {
626 requireValue
= mode
== RX_FAILSAFE_MODE_SET
;
628 ptr
= strchr(ptr
, ' ');
635 value
= CHANNEL_VALUE_TO_RXFAIL_STEP(value
);
636 if (value
> MAX_RXFAIL_RANGE_STEP
) {
637 cliPrint("Value out of range\r\n");
641 channelFailsafeConfiguration
->step
= value
;
642 } else if (requireValue
) {
646 channelFailsafeConfiguration
->mode
= mode
;
650 char modeCharacter
= rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
];
652 // triple use of printf below
653 // 1. acknowledge interpretation on command,
654 // 2. query current setting on single item,
655 // 3. recursive use for full list.
658 printf("rxfail %u %c %d\r\n",
661 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration
->step
)
664 printf("rxfail %u %c\r\n",
670 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
- 1);
675 static void cliAux(char *cmdline
)
680 if (isEmpty(cmdline
)) {
681 // print out aux channel settings
682 for (i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
683 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
684 printf("aux %u %u %u %u %u\r\n",
687 mac
->auxChannelIndex
,
688 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
689 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
)
695 if (i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
) {
696 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
697 uint8_t validArgumentCount
= 0;
698 ptr
= strchr(ptr
, ' ');
701 if (val
>= 0 && val
< CHECKBOX_ITEM_COUNT
) {
703 validArgumentCount
++;
706 ptr
= strchr(ptr
, ' ');
709 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
710 mac
->auxChannelIndex
= val
;
711 validArgumentCount
++;
714 ptr
= processChannelRangeArgs(ptr
, &mac
->range
, &validArgumentCount
);
716 if (validArgumentCount
!= 4) {
717 memset(mac
, 0, sizeof(modeActivationCondition_t
));
720 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT
- 1);
725 static void cliSerial(char *cmdline
)
730 if (isEmpty(cmdline
)) {
731 for (i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
732 if (!serialIsPortAvailable(masterConfig
.serialConfig
.portConfigs
[i
].identifier
)) {
735 printf("serial %d %d %ld %ld %ld %ld\r\n" ,
736 masterConfig
.serialConfig
.portConfigs
[i
].identifier
,
737 masterConfig
.serialConfig
.portConfigs
[i
].functionMask
,
738 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].msp_baudrateIndex
],
739 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].gps_baudrateIndex
],
740 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].telemetry_baudrateIndex
],
741 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].blackbox_baudrateIndex
]
747 serialPortConfig_t portConfig
;
748 memset(&portConfig
, 0 , sizeof(portConfig
));
750 serialPortConfig_t
*currentConfig
;
752 uint8_t validArgumentCount
= 0;
757 currentConfig
= serialFindPortConfiguration(val
);
759 portConfig
.identifier
= val
;
760 validArgumentCount
++;
763 ptr
= strchr(ptr
, ' ');
766 portConfig
.functionMask
= val
& 0xFFFF;
767 validArgumentCount
++;
770 for (i
= 0; i
< 4; i
++) {
771 ptr
= strchr(ptr
, ' ');
778 uint8_t baudRateIndex
= lookupBaudRateIndex(val
);
779 if (baudRates
[baudRateIndex
] != (uint32_t) val
) {
785 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
788 portConfig
.msp_baudrateIndex
= baudRateIndex
;
791 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
794 portConfig
.gps_baudrateIndex
= baudRateIndex
;
797 if (baudRateIndex
!= BAUD_AUTO
&& baudRateIndex
> BAUD_115200
) {
800 portConfig
.telemetry_baudrateIndex
= baudRateIndex
;
803 if (baudRateIndex
< BAUD_19200
|| baudRateIndex
> BAUD_250000
) {
806 portConfig
.blackbox_baudrateIndex
= baudRateIndex
;
810 validArgumentCount
++;
813 if (validArgumentCount
< 6) {
818 memcpy(currentConfig
, &portConfig
, sizeof(portConfig
));
822 static void cliAdjustmentRange(char *cmdline
)
827 if (isEmpty(cmdline
)) {
828 // print out adjustment ranges channel settings
829 for (i
= 0; i
< MAX_ADJUSTMENT_RANGE_COUNT
; i
++) {
830 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
831 printf("adjrange %u %u %u %u %u %u %u\r\n",
835 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
836 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
837 ar
->adjustmentFunction
,
838 ar
->auxSwitchChannelIndex
844 if (i
< MAX_ADJUSTMENT_RANGE_COUNT
) {
845 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
846 uint8_t validArgumentCount
= 0;
848 ptr
= strchr(ptr
, ' ');
851 if (val
>= 0 && val
< MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
) {
852 ar
->adjustmentIndex
= val
;
853 validArgumentCount
++;
856 ptr
= strchr(ptr
, ' ');
859 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
860 ar
->auxChannelIndex
= val
;
861 validArgumentCount
++;
865 ptr
= processChannelRangeArgs(ptr
, &ar
->range
, &validArgumentCount
);
867 ptr
= strchr(ptr
, ' ');
870 if (val
>= 0 && val
< ADJUSTMENT_FUNCTION_COUNT
) {
871 ar
->adjustmentFunction
= val
;
872 validArgumentCount
++;
875 ptr
= strchr(ptr
, ' ');
878 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
879 ar
->auxSwitchChannelIndex
= val
;
880 validArgumentCount
++;
884 if (validArgumentCount
!= 6) {
885 memset(ar
, 0, sizeof(adjustmentRange_t
));
889 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT
- 1);
894 static void cliMotorMix(char *cmdline
)
896 #ifdef USE_QUAD_MIXER_ONLY
905 if (isEmpty(cmdline
)) {
906 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
907 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
908 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
912 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].throttle
, buf
));
913 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].roll
, buf
));
914 printf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].pitch
, buf
));
915 printf("%s\r\n", ftoa(masterConfig
.customMotorMixer
[i
].yaw
, buf
));
918 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
919 // erase custom mixer
920 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
921 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
922 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
923 ptr
= strchr(cmdline
, ' ');
927 if (mixerNames
[i
] == NULL
) {
928 cliPrint("Invalid name\r\n");
931 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
932 mixerLoadMix(i
, masterConfig
.customMotorMixer
);
933 printf("Loaded %s\r\n", mixerNames
[i
]);
941 i
= atoi(ptr
); // get motor number
942 if (i
< MAX_SUPPORTED_MOTORS
) {
943 ptr
= strchr(ptr
, ' ');
945 masterConfig
.customMotorMixer
[i
].throttle
= fastA2F(++ptr
);
948 ptr
= strchr(ptr
, ' ');
950 masterConfig
.customMotorMixer
[i
].roll
= fastA2F(++ptr
);
953 ptr
= strchr(ptr
, ' ');
955 masterConfig
.customMotorMixer
[i
].pitch
= fastA2F(++ptr
);
958 ptr
= strchr(ptr
, ' ');
960 masterConfig
.customMotorMixer
[i
].yaw
= fastA2F(++ptr
);
969 cliShowArgumentRangeError("index", 1, MAX_SUPPORTED_MOTORS
);
975 static void cliRxRange(char *cmdline
)
977 int i
, validArgumentCount
= 0;
980 if (isEmpty(cmdline
)) {
981 for (i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
982 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
983 printf("rxrange %u %u %u\r\n", i
, channelRangeConfiguration
->min
, channelRangeConfiguration
->max
);
985 } else if (strcasecmp(cmdline
, "reset") == 0) {
986 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
990 if (i
>= 0 && i
< NON_AUX_CHANNEL_COUNT
) {
991 int rangeMin
, rangeMax
;
993 ptr
= strchr(ptr
, ' ');
995 rangeMin
= atoi(++ptr
);
996 validArgumentCount
++;
999 ptr
= strchr(ptr
, ' ');
1001 rangeMax
= atoi(++ptr
);
1002 validArgumentCount
++;
1005 if (validArgumentCount
!= 2) {
1006 cliShowParseError();
1007 } else if (rangeMin
< PWM_PULSE_MIN
|| rangeMin
> PWM_PULSE_MAX
|| rangeMax
< PWM_PULSE_MIN
|| rangeMax
> PWM_PULSE_MAX
) {
1008 cliShowParseError();
1010 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1011 channelRangeConfiguration
->min
= rangeMin
;
1012 channelRangeConfiguration
->max
= rangeMax
;
1015 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT
- 1);
1021 static void cliLed(char *cmdline
)
1025 char ledConfigBuffer
[20];
1027 if (isEmpty(cmdline
)) {
1028 for (i
= 0; i
< MAX_LED_STRIP_LENGTH
; i
++) {
1029 generateLedConfig(i
, ledConfigBuffer
, sizeof(ledConfigBuffer
));
1030 printf("led %u %s\r\n", i
, ledConfigBuffer
);
1035 if (i
< MAX_LED_STRIP_LENGTH
) {
1036 ptr
= strchr(cmdline
, ' ');
1037 if (!parseLedStripConfig(i
, ++ptr
)) {
1038 cliShowParseError();
1041 cliShowArgumentRangeError("index", 0, MAX_LED_STRIP_LENGTH
- 1);
1046 static void cliColor(char *cmdline
)
1051 if (isEmpty(cmdline
)) {
1052 for (i
= 0; i
< CONFIGURABLE_COLOR_COUNT
; i
++) {
1053 printf("color %u %d,%u,%u\r\n",
1055 masterConfig
.colors
[i
].h
,
1056 masterConfig
.colors
[i
].s
,
1057 masterConfig
.colors
[i
].v
1063 if (i
< CONFIGURABLE_COLOR_COUNT
) {
1064 ptr
= strchr(cmdline
, ' ');
1065 if (!parseColor(i
, ++ptr
)) {
1066 cliShowParseError();
1069 cliShowArgumentRangeError("index", 0, CONFIGURABLE_COLOR_COUNT
- 1);
1076 static void cliServo(char *cmdline
)
1078 enum { SERVO_ARGUMENT_COUNT
= 8 };
1079 int16_t arguments
[SERVO_ARGUMENT_COUNT
];
1081 servoParam_t
*servo
;
1086 if (isEmpty(cmdline
)) {
1087 // print out servo settings
1088 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1089 servo
= ¤tProfile
->servoConf
[i
];
1091 printf("servo %u %d %d %d %d %d %d %d\r\n",
1099 servo
->forwardFromChannel
1103 int validArgumentCount
= 0;
1107 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1109 // If command line doesn't fit the format, don't modify the config
1111 if (*ptr
== '-' || (*ptr
>= '0' && *ptr
<= '9')) {
1112 if (validArgumentCount
>= SERVO_ARGUMENT_COUNT
) {
1113 cliShowParseError();
1117 arguments
[validArgumentCount
++] = atoi(ptr
);
1121 } while (*ptr
>= '0' && *ptr
<= '9');
1122 } else if (*ptr
== ' ') {
1125 cliShowParseError();
1130 enum {INDEX
= 0, MIN
, MAX
, MIDDLE
, ANGLE_AT_MIN
, ANGLE_AT_MAX
, RATE
, FORWARD
};
1132 i
= arguments
[INDEX
];
1134 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1135 if (validArgumentCount
!= SERVO_ARGUMENT_COUNT
|| i
< 0 || i
>= MAX_SUPPORTED_SERVOS
) {
1136 cliShowParseError();
1140 servo
= ¤tProfile
->servoConf
[i
];
1143 arguments
[MIN
] < PWM_PULSE_MIN
|| arguments
[MIN
] > PWM_PULSE_MAX
||
1144 arguments
[MAX
] < PWM_PULSE_MIN
|| arguments
[MAX
] > PWM_PULSE_MAX
||
1145 arguments
[MIDDLE
] < arguments
[MIN
] || arguments
[MIDDLE
] > arguments
[MAX
] ||
1146 arguments
[MIN
] > arguments
[MAX
] || arguments
[MAX
] < arguments
[MIN
] ||
1147 arguments
[RATE
] < -100 || arguments
[RATE
] > 100 ||
1148 arguments
[FORWARD
] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
||
1149 arguments
[ANGLE_AT_MIN
] < 0 || arguments
[ANGLE_AT_MIN
] > 180 ||
1150 arguments
[ANGLE_AT_MAX
] < 0 || arguments
[ANGLE_AT_MAX
] > 180
1152 cliShowParseError();
1156 servo
->min
= arguments
[1];
1157 servo
->max
= arguments
[2];
1158 servo
->middle
= arguments
[3];
1159 servo
->angleAtMin
= arguments
[4];
1160 servo
->angleAtMax
= arguments
[5];
1161 servo
->rate
= arguments
[6];
1162 servo
->forwardFromChannel
= arguments
[7];
1168 static void cliServoMix(char *cmdline
)
1173 int args
[8], check
= 0;
1174 len
= strlen(cmdline
);
1178 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1180 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1181 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1184 printf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1186 masterConfig
.customServoMixer
[i
].targetChannel
,
1187 masterConfig
.customServoMixer
[i
].inputSource
,
1188 masterConfig
.customServoMixer
[i
].rate
,
1189 masterConfig
.customServoMixer
[i
].speed
,
1190 masterConfig
.customServoMixer
[i
].min
,
1191 masterConfig
.customServoMixer
[i
].max
,
1192 masterConfig
.customServoMixer
[i
].box
1197 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1198 // erase custom mixer
1199 memset(masterConfig
.customServoMixer
, 0, sizeof(masterConfig
.customServoMixer
));
1200 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1201 currentProfile
->servoConf
[i
].reversedSources
= 0;
1203 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1204 ptr
= strchr(cmdline
, ' ');
1206 len
= strlen(++ptr
);
1207 for (i
= 0; ; i
++) {
1208 if (mixerNames
[i
] == NULL
) {
1209 printf("Invalid name\r\n");
1212 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1213 servoMixerLoadMix(i
, masterConfig
.customServoMixer
);
1214 printf("Loaded %s\r\n", mixerNames
[i
]);
1220 } else if (strncasecmp(cmdline
, "reverse", 7) == 0) {
1221 enum {SERVO
= 0, INPUT
, REVERSE
, ARGS_COUNT
};
1222 int servoIndex
, inputSource
;
1223 ptr
= strchr(cmdline
, ' ');
1228 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1229 printf("\ti%d", inputSource
);
1232 for (servoIndex
= 0; servoIndex
< MAX_SUPPORTED_SERVOS
; servoIndex
++) {
1233 printf("%d", servoIndex
);
1234 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1235 printf("\t%s ", (currentProfile
->servoConf
[servoIndex
].reversedSources
& (1 << inputSource
)) ? "r" : "n");
1241 ptr
= strtok(ptr
, " ");
1242 while (ptr
!= NULL
&& check
< ARGS_COUNT
- 1) {
1243 args
[check
++] = atoi(ptr
);
1244 ptr
= strtok(NULL
, " ");
1247 if (ptr
== NULL
|| check
!= ARGS_COUNT
- 1) {
1248 cliShowParseError();
1252 if (args
[SERVO
] >= 0 && args
[SERVO
] < MAX_SUPPORTED_SERVOS
1253 && args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
1254 && (*ptr
== 'r' || *ptr
== 'n')) {
1256 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
|= 1 << args
[INPUT
];
1258 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
&= ~(1 << args
[INPUT
]);
1260 cliShowParseError();
1262 cliServoMix("reverse");
1264 enum {RULE
= 0, TARGET
, INPUT
, RATE
, SPEED
, MIN
, MAX
, BOX
, ARGS_COUNT
};
1265 ptr
= strtok(cmdline
, " ");
1266 while (ptr
!= NULL
&& check
< ARGS_COUNT
) {
1267 args
[check
++] = atoi(ptr
);
1268 ptr
= strtok(NULL
, " ");
1271 if (ptr
!= NULL
|| check
!= ARGS_COUNT
) {
1272 cliShowParseError();
1277 if (i
>= 0 && i
< MAX_SERVO_RULES
&&
1278 args
[TARGET
] >= 0 && args
[TARGET
] < MAX_SUPPORTED_SERVOS
&&
1279 args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
&&
1280 args
[RATE
] >= -100 && args
[RATE
] <= 100 &&
1281 args
[SPEED
] >= 0 && args
[SPEED
] <= MAX_SERVO_SPEED
&&
1282 args
[MIN
] >= 0 && args
[MIN
] <= 100 &&
1283 args
[MAX
] >= 0 && args
[MAX
] <= 100 && args
[MIN
] < args
[MAX
] &&
1284 args
[BOX
] >= 0 && args
[BOX
] <= MAX_SERVO_BOXES
) {
1285 masterConfig
.customServoMixer
[i
].targetChannel
= args
[TARGET
];
1286 masterConfig
.customServoMixer
[i
].inputSource
= args
[INPUT
];
1287 masterConfig
.customServoMixer
[i
].rate
= args
[RATE
];
1288 masterConfig
.customServoMixer
[i
].speed
= args
[SPEED
];
1289 masterConfig
.customServoMixer
[i
].min
= args
[MIN
];
1290 masterConfig
.customServoMixer
[i
].max
= args
[MAX
];
1291 masterConfig
.customServoMixer
[i
].box
= args
[BOX
];
1294 cliShowParseError();
1303 static void cliFlashInfo(char *cmdline
)
1305 const flashGeometry_t
*layout
= flashfsGetGeometry();
1309 printf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1310 layout
->sectors
, layout
->sectorSize
, layout
->pagesPerSector
, layout
->pageSize
, layout
->totalSize
, flashfsGetOffset());
1313 static void cliFlashErase(char *cmdline
)
1317 printf("Erasing...\r\n");
1318 flashfsEraseCompletely();
1320 while (!flashfsIsReady()) {
1324 printf("Done.\r\n");
1327 #ifdef USE_FLASH_TOOLS
1329 static void cliFlashWrite(char *cmdline
)
1331 uint32_t address
= atoi(cmdline
);
1332 char *text
= strchr(cmdline
, ' ');
1335 cliShowParseError();
1337 flashfsSeekAbs(address
);
1338 flashfsWrite((uint8_t*)text
, strlen(text
), true);
1341 printf("Wrote %u bytes at %u.\r\n", strlen(text
), address
);
1345 static void cliFlashRead(char *cmdline
)
1347 uint32_t address
= atoi(cmdline
);
1353 char *nextArg
= strchr(cmdline
, ' ');
1356 cliShowParseError();
1358 length
= atoi(nextArg
);
1360 printf("Reading %u bytes at %u:\r\n", length
, address
);
1362 while (length
> 0) {
1365 bytesRead
= flashfsReadAbs(address
, buffer
, length
< sizeof(buffer
) ? length
: sizeof(buffer
));
1367 for (i
= 0; i
< bytesRead
; i
++) {
1368 cliWrite(buffer
[i
]);
1371 length
-= bytesRead
;
1372 address
+= bytesRead
;
1374 if (bytesRead
== 0) {
1375 //Assume we reached the end of the volume or something fatal happened
1386 static void dumpValues(uint16_t mask
)
1389 const clivalue_t
*value
;
1390 for (i
= 0; i
< VALUE_COUNT
; i
++) {
1391 value
= &valueTable
[i
];
1393 if ((value
->type
& mask
) == 0) {
1397 printf("set %s = ", valueTable
[i
].name
);
1398 cliPrintVar(value
, 0);
1404 DUMP_MASTER
= (1 << 0),
1405 DUMP_PROFILE
= (1 << 1),
1406 DUMP_CONTROL_RATE_PROFILE
= (1 << 2)
1409 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
1412 static const char* const sectionBreak
= "\r\n";
1414 #define printSectionBreak() printf((char *)sectionBreak)
1416 static void cliDump(char *cmdline
)
1422 #ifndef USE_QUAD_MIXER_ONLY
1423 float thr
, roll
, pitch
, yaw
;
1426 uint8_t dumpMask
= DUMP_ALL
;
1427 if (strcasecmp(cmdline
, "master") == 0) {
1428 dumpMask
= DUMP_MASTER
; // only
1430 if (strcasecmp(cmdline
, "profile") == 0) {
1431 dumpMask
= DUMP_PROFILE
; // only
1433 if (strcasecmp(cmdline
, "rates") == 0) {
1434 dumpMask
= DUMP_CONTROL_RATE_PROFILE
; // only
1437 if (dumpMask
& DUMP_MASTER
) {
1439 cliPrint("\r\n# version\r\n");
1442 cliPrint("\r\n# dump master\r\n");
1443 cliPrint("\r\n# mixer\r\n");
1445 #ifndef USE_QUAD_MIXER_ONLY
1446 printf("mixer %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
1448 printf("mmix reset\r\n");
1450 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1451 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1453 thr
= masterConfig
.customMotorMixer
[i
].throttle
;
1454 roll
= masterConfig
.customMotorMixer
[i
].roll
;
1455 pitch
= masterConfig
.customMotorMixer
[i
].pitch
;
1456 yaw
= masterConfig
.customMotorMixer
[i
].yaw
;
1457 printf("mmix %d", i
);
1460 printf("%s", ftoa(thr
, buf
));
1463 printf("%s", ftoa(roll
, buf
));
1466 printf("%s", ftoa(pitch
, buf
));
1469 printf("%s\r\n", ftoa(yaw
, buf
));
1472 // print custom servo mixer if exists
1473 printf("smix reset\r\n");
1475 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1477 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1480 printf("smix %d %d %d %d %d %d %d %d\r\n",
1482 masterConfig
.customServoMixer
[i
].targetChannel
,
1483 masterConfig
.customServoMixer
[i
].inputSource
,
1484 masterConfig
.customServoMixer
[i
].rate
,
1485 masterConfig
.customServoMixer
[i
].speed
,
1486 masterConfig
.customServoMixer
[i
].min
,
1487 masterConfig
.customServoMixer
[i
].max
,
1488 masterConfig
.customServoMixer
[i
].box
1494 cliPrint("\r\n\r\n# feature\r\n");
1496 mask
= featureMask();
1497 for (i
= 0; ; i
++) { // disable all feature first
1498 if (featureNames
[i
] == NULL
)
1500 printf("feature -%s\r\n", featureNames
[i
]);
1502 for (i
= 0; ; i
++) { // reenable what we want.
1503 if (featureNames
[i
] == NULL
)
1505 if (mask
& (1 << i
))
1506 printf("feature %s\r\n", featureNames
[i
]);
1509 cliPrint("\r\n\r\n# map\r\n");
1511 for (i
= 0; i
< 8; i
++)
1512 buf
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
1514 printf("map %s\r\n", buf
);
1516 cliPrint("\r\n\r\n# serial\r\n");
1520 cliPrint("\r\n\r\n# led\r\n");
1523 cliPrint("\r\n\r\n# color\r\n");
1526 printSectionBreak();
1527 dumpValues(MASTER_VALUE
);
1529 cliPrint("\r\n# rxfail\r\n");
1533 if (dumpMask
& DUMP_PROFILE
) {
1534 cliPrint("\r\n# dump profile\r\n");
1536 cliPrint("\r\n# profile\r\n");
1539 cliPrint("\r\n# aux\r\n");
1543 cliPrint("\r\n# adjrange\r\n");
1545 cliAdjustmentRange("");
1547 printf("\r\n# rxrange\r\n");
1552 cliPrint("\r\n# servo\r\n");
1556 // print servo directions
1557 unsigned int channel
;
1559 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1560 for (channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
1561 if (servoDirection(i
, channel
) < 0) {
1562 printf("smix reverse %d %d r\r\n", i
, channel
);
1568 printSectionBreak();
1570 dumpValues(PROFILE_VALUE
);
1573 if (dumpMask
& DUMP_CONTROL_RATE_PROFILE
) {
1574 cliPrint("\r\n# dump rates\r\n");
1576 cliPrint("\r\n# rateprofile\r\n");
1579 printSectionBreak();
1581 dumpValues(CONTROL_RATE_VALUE
);
1585 void cliEnter(serialPort_t
*serialPort
)
1588 cliPort
= serialPort
;
1589 setPrintfSerialPort(cliPort
);
1590 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
1592 ENABLE_ARMING_FLAG(PREVENT_ARMING
);
1595 static void cliExit(char *cmdline
)
1599 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
1603 // incase a motor was left running during motortest, clear it here
1604 mixerResetDisarmedMotors();
1610 static void cliFeature(char *cmdline
)
1616 len
= strlen(cmdline
);
1617 mask
= featureMask();
1620 cliPrint("Enabled: ");
1621 for (i
= 0; ; i
++) {
1622 if (featureNames
[i
] == NULL
)
1624 if (mask
& (1 << i
))
1625 printf("%s ", featureNames
[i
]);
1628 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
1629 cliPrint("Available: ");
1630 for (i
= 0; ; i
++) {
1631 if (featureNames
[i
] == NULL
)
1633 printf("%s ", featureNames
[i
]);
1638 bool remove
= false;
1639 if (cmdline
[0] == '-') {
1642 cmdline
++; // skip over -
1646 for (i
= 0; ; i
++) {
1647 if (featureNames
[i
] == NULL
) {
1648 cliPrint("Invalid name\r\n");
1652 if (strncasecmp(cmdline
, featureNames
[i
], len
) == 0) {
1656 if (mask
& FEATURE_GPS
) {
1657 cliPrint("unavailable\r\n");
1662 if (mask
& FEATURE_SONAR
) {
1663 cliPrint("unavailable\r\n");
1669 cliPrint("Disabled");
1672 cliPrint("Enabled");
1674 printf(" %s\r\n", featureNames
[i
]);
1682 static void cliGpsPassthrough(char *cmdline
)
1686 gpsEnablePassthrough(cliPort
);
1690 static void cliHelp(char *cmdline
)
1696 for (i
= 0; i
< CMD_COUNT
; i
++) {
1697 cliPrint(cmdTable
[i
].name
);
1698 if (cmdTable
[i
].description
) {
1699 printf(" - %s", cmdTable
[i
].description
);
1701 if (cmdTable
[i
].args
) {
1702 printf("\r\n\t%s", cmdTable
[i
].args
);
1708 static void cliMap(char *cmdline
)
1714 len
= strlen(cmdline
);
1718 for (i
= 0; i
< 8; i
++)
1719 cmdline
[i
] = toupper((unsigned char)cmdline
[i
]);
1720 for (i
= 0; i
< 8; i
++) {
1721 if (strchr(rcChannelLetters
, cmdline
[i
]) && !strchr(cmdline
+ i
+ 1, cmdline
[i
]))
1723 cliShowParseError();
1726 parseRcChannels(cmdline
, &masterConfig
.rxConfig
);
1729 for (i
= 0; i
< 8; i
++)
1730 out
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
1732 printf("%s\r\n", out
);
1735 #ifndef USE_QUAD_MIXER_ONLY
1736 static void cliMixer(char *cmdline
)
1741 len
= strlen(cmdline
);
1744 printf("Mixer: %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
1746 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
1747 cliPrint("Available mixers: ");
1748 for (i
= 0; ; i
++) {
1749 if (mixerNames
[i
] == NULL
)
1751 printf("%s ", mixerNames
[i
]);
1757 for (i
= 0; ; i
++) {
1758 if (mixerNames
[i
] == NULL
) {
1759 cliPrint("Invalid name\r\n");
1762 if (strncasecmp(cmdline
, mixerNames
[i
], len
) == 0) {
1763 masterConfig
.mixerMode
= i
+ 1;
1772 static void cliMotor(char *cmdline
)
1774 int motor_index
= 0;
1775 int motor_value
= 0;
1780 if (isEmpty(cmdline
)) {
1781 cliShowParseError();
1785 pch
= strtok_r(cmdline
, " ", &saveptr
);
1786 while (pch
!= NULL
) {
1789 motor_index
= atoi(pch
);
1792 motor_value
= atoi(pch
);
1796 pch
= strtok_r(NULL
, " ", &saveptr
);
1799 if (motor_index
< 0 || motor_index
>= MAX_SUPPORTED_MOTORS
) {
1800 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
);
1805 if (motor_value
< PWM_RANGE_MIN
|| motor_value
> PWM_RANGE_MAX
) {
1806 cliShowArgumentRangeError("value", 1000, 2000);
1809 motor_disarmed
[motor_index
] = motor_value
;
1813 printf("motor %d: %d\r\n", motor_index
, motor_disarmed
[motor_index
]);
1816 static void cliPlaySound(char *cmdline
)
1818 #if FLASH_SIZE <= 64
1823 static int lastSoundIdx
= -1;
1825 if (isEmpty(cmdline
)) {
1826 i
= lastSoundIdx
+ 1; //next sound index
1827 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
1828 while (true) { //no name for index; try next one
1829 if (++i
>= beeperTableEntryCount())
1830 i
= 0; //if end then wrap around to first entry
1831 if ((name
=beeperNameForTableIndex(i
)) != NULL
)
1832 break; //if name OK then play sound below
1833 if (i
== lastSoundIdx
+ 1) { //prevent infinite loop
1834 printf("Error playing sound\r\n");
1839 } else { //index value was given
1841 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
1842 printf("No sound for index %d\r\n", i
);
1848 printf("Playing sound %d: %s\r\n", i
, name
);
1849 beeper(beeperModeForTableIndex(i
));
1853 static void cliProfile(char *cmdline
)
1857 if (isEmpty(cmdline
)) {
1858 printf("profile %d\r\n", getCurrentProfile());
1862 if (i
>= 0 && i
< MAX_PROFILE_COUNT
) {
1863 masterConfig
.current_profile_index
= i
;
1871 static void cliRateProfile(char *cmdline
)
1875 if (isEmpty(cmdline
)) {
1876 printf("rateprofile %d\r\n", getCurrentControlRateProfile());
1880 if (i
>= 0 && i
< MAX_CONTROL_RATE_PROFILE_COUNT
) {
1881 changeControlRateProfile(i
);
1887 static void cliReboot(void) {
1888 cliPrint("\r\nRebooting");
1889 waitForSerialPortToFinishTransmitting(cliPort
);
1891 handleOneshotFeatureChangeOnRestart();
1895 static void cliSave(char *cmdline
)
1900 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
1905 static void cliDefaults(char *cmdline
)
1909 cliPrint("Resetting to defaults");
1914 static void cliPrint(const char *str
)
1917 serialWrite(cliPort
, *(str
++));
1920 static void cliWrite(uint8_t ch
)
1922 serialWrite(cliPort
, ch
);
1925 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
)
1930 void *ptr
= var
->ptr
;
1931 if (var
->type
& PROFILE_VALUE
) {
1932 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
1934 if (var
->type
& CONTROL_RATE_VALUE
) {
1935 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
1938 switch (var
->type
& VALUE_TYPE_MASK
) {
1940 value
= *(uint8_t *)ptr
;
1944 value
= *(int8_t *)ptr
;
1948 value
= *(uint16_t *)ptr
;
1952 value
= *(int16_t *)ptr
;
1956 value
= *(uint32_t *)ptr
;
1960 printf("%s", ftoa(*(float *)ptr
, buf
));
1962 printf(" %s", ftoa((float)var
->min
, buf
));
1963 printf(" %s", ftoa((float)var
->max
, buf
));
1965 return; // return from case for float only
1967 printf("%d", value
);
1969 printf(" %d %d", var
->min
, var
->max
);
1972 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
)
1974 void *ptr
= var
->ptr
;
1975 if (var
->type
& PROFILE_VALUE
) {
1976 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
1978 if (var
->type
& CONTROL_RATE_VALUE
) {
1979 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
1982 switch (var
->type
& VALUE_TYPE_MASK
) {
1985 *(int8_t *)ptr
= value
.int_value
;
1990 *(int16_t *)ptr
= value
.int_value
;
1994 *(uint32_t *)ptr
= value
.int_value
;
1998 *(float *)ptr
= (float)value
.float_value
;
2003 static void cliSet(char *cmdline
)
2007 const clivalue_t
*val
;
2012 len
= strlen(cmdline
);
2014 if (len
== 0 || (len
== 1 && cmdline
[0] == '*')) {
2015 cliPrint("Current settings: \r\n");
2016 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2017 val
= &valueTable
[i
];
2018 printf("%s = ", valueTable
[i
].name
);
2019 cliPrintVar(val
, len
); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2022 } else if ((eqptr
= strstr(cmdline
, "=")) != NULL
) {
2023 // has equal, set var
2024 char *lastNonSpaceCharacter
= eqptr
;
2025 while (*(lastNonSpaceCharacter
- 1) == ' ') {
2026 lastNonSpaceCharacter
--;
2028 uint8_t variableNameLength
= lastNonSpaceCharacter
- cmdline
;
2032 value
= atoi(eqptr
);
2033 valuef
= fastA2F(eqptr
);
2034 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2035 val
= &valueTable
[i
];
2036 // ensure exact match when setting to prevent setting variables with shorter names
2037 if (strncasecmp(cmdline
, valueTable
[i
].name
, strlen(valueTable
[i
].name
)) == 0 && variableNameLength
== strlen(valueTable
[i
].name
)) {
2038 if (valuef
>= valueTable
[i
].min
&& valuef
<= valueTable
[i
].max
) { // here we compare the float value since... it should work, RIGHT?
2039 int_float_value_t tmp
;
2040 if (valueTable
[i
].type
& VAR_FLOAT
)
2041 tmp
.float_value
= valuef
;
2043 tmp
.int_value
= value
;
2044 cliSetVar(val
, tmp
);
2045 printf("%s set to ", valueTable
[i
].name
);
2046 cliPrintVar(val
, 0);
2048 cliPrint("Value assignment out of range\r\n");
2053 cliPrint("Invalid name\r\n");
2055 // no equals, check for matching variables.
2060 static void cliGet(char *cmdline
)
2063 const clivalue_t
*val
;
2064 int matchedCommands
= 0;
2066 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2067 if (strstr(valueTable
[i
].name
, cmdline
)) {
2068 val
= &valueTable
[i
];
2069 printf("%s = ", valueTable
[i
].name
);
2070 cliPrintVar(val
, 0);
2078 if (matchedCommands
) {
2082 cliPrint("Invalid name\r\n");
2085 static void cliStatus(char *cmdline
)
2089 printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s)\r\n",
2090 millis() / 1000, vbat
, batteryCellCount
, getBatteryStateString());
2093 printf("CPU Clock=%dMHz", (SystemCoreClock
/ 1000000));
2098 uint32_t detectedSensorsMask
= sensorsMask();
2100 for (i
= 0; ; i
++) {
2102 if (sensorTypeNames
[i
] == NULL
)
2106 if ((detectedSensorsMask
& mask
) && (mask
& SENSOR_NAMES_MASK
)) {
2107 const char *sensorHardware
;
2108 uint8_t sensorHardwareIndex
= detectedSensors
[i
];
2109 sensorHardware
= sensorHardwareNames
[i
][sensorHardwareIndex
];
2111 printf(", %s=%s", sensorTypeNames
[i
], sensorHardware
);
2113 if (mask
== SENSOR_ACC
&& acc
.revisionCode
) {
2114 printf(".%c", acc
.revisionCode
);
2122 uint16_t i2cErrorCounter
= i2cGetErrorCounter();
2124 uint16_t i2cErrorCounter
= 0;
2127 printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime
, i2cErrorCounter
, sizeof(master_t
));
2130 #ifdef USE_SERIAL_1WIRE
2131 static void cliUSB1Wire(char *cmdline
)
2135 if (isEmpty(cmdline
)) {
2136 cliPrint("Please specify a ouput channel. e.g. `1wire 2` to connect to motor 2\r\n");
2140 if (i
>= 0 && i
<= ESC_COUNT
) {
2141 printf("Switching to BlHeli mode on motor port %d\r\n", i
);
2144 printf("Invalid motor port, valid range: 1 to %d\r\n", ESC_COUNT
);
2147 // motor 1 => index 0
2148 usb1WirePassthrough(i
-1);
2152 static void cliVersion(char *cmdline
)
2156 printf("# BetaFlight v2/%s %s %s / %s (%s)",
2165 void cliProcess(void)
2171 while (serialTotalBytesWaiting(cliPort
)) {
2172 uint8_t c
= serialRead(cliPort
);
2173 if (c
== '\t' || c
== '?') {
2174 // do tab completion
2175 const clicmd_t
*cmd
, *pstart
= NULL
, *pend
= NULL
;
2176 uint32_t i
= bufferIndex
;
2177 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2178 if (bufferIndex
&& (strncasecmp(cliBuffer
, cmd
->name
, bufferIndex
) != 0))
2184 if (pstart
) { /* Buffer matches one or more commands */
2185 for (; ; bufferIndex
++) {
2186 if (pstart
->name
[bufferIndex
] != pend
->name
[bufferIndex
])
2188 if (!pstart
->name
[bufferIndex
] && bufferIndex
< sizeof(cliBuffer
) - 2) {
2189 /* Unambiguous -- append a space */
2190 cliBuffer
[bufferIndex
++] = ' ';
2191 cliBuffer
[bufferIndex
] = '\0';
2194 cliBuffer
[bufferIndex
] = pstart
->name
[bufferIndex
];
2197 if (!bufferIndex
|| pstart
!= pend
) {
2198 /* Print list of ambiguous matches */
2199 cliPrint("\r\033[K");
2200 for (cmd
= pstart
; cmd
<= pend
; cmd
++) {
2201 cliPrint(cmd
->name
);
2205 i
= 0; /* Redraw prompt */
2207 for (; i
< bufferIndex
; i
++)
2208 cliWrite(cliBuffer
[i
]);
2209 } else if (!bufferIndex
&& c
== 4) { // CTRL-D
2212 } else if (c
== 12) { // NewPage / CTRL-L
2214 cliPrint("\033[2J\033[1;1H");
2216 } else if (bufferIndex
&& (c
== '\n' || c
== '\r')) {
2220 // Strip comment starting with # from line
2221 char *p
= cliBuffer
;
2224 bufferIndex
= (uint32_t)(p
- cliBuffer
);
2227 // Strip trailing whitespace
2228 while (bufferIndex
> 0 && cliBuffer
[bufferIndex
- 1] == ' ') {
2232 // Process non-empty lines
2233 if (bufferIndex
> 0) {
2234 cliBuffer
[bufferIndex
] = 0; // null terminate
2236 const clicmd_t
*cmd
;
2237 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2238 if(!strncasecmp(cliBuffer
, cmd
->name
, strlen(cmd
->name
)) // command names match
2239 && !isalnum((unsigned)cliBuffer
[strlen(cmd
->name
)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2242 if(cmd
< cmdTable
+ CMD_COUNT
)
2243 cmd
->func(cliBuffer
+ strlen(cmd
->name
) + 1);
2245 cliPrint("Unknown command, try 'help'");
2249 memset(cliBuffer
, 0, sizeof(cliBuffer
));
2251 // 'exit' will reset this flag, so we don't need to print prompt again
2256 } else if (c
== 127) {
2259 cliBuffer
[--bufferIndex
] = 0;
2260 cliPrint("\010 \010");
2262 } else if (bufferIndex
< sizeof(cliBuffer
) && c
>= 32 && c
<= 126) {
2263 if (!bufferIndex
&& c
== ' ')
2264 continue; // Ignore leading spaces
2265 cliBuffer
[bufferIndex
++] = c
;
2271 void cliInit(serialConfig_t
*serialConfig
)
2273 UNUSED(serialConfig
);