Relocate some structures and code to the right places.
[betaflight.git] / src / main / io / serial_cli.c
blobbb950a69b06add76a2f3e00a25e9df84582a469f
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"
56 #include "rx/rx.h"
57 #include "rx/spektrum.h"
59 #include "sensors/battery.h"
60 #include "sensors/boardalignment.h"
61 #include "sensors/sensors.h"
62 #include "sensors/acceleration.h"
63 #include "sensors/gyro.h"
64 #include "sensors/compass.h"
65 #include "sensors/barometer.h"
67 #include "flight/flight.h"
68 #include "flight/imu.h"
69 #include "flight/mixer.h"
70 #include "flight/navigation.h"
71 #include "flight/failsafe.h"
73 #include "telemetry/telemetry.h"
75 #include "config/runtime_config.h"
76 #include "config/config.h"
77 #include "config/config_profile.h"
78 #include "config/config_master.h"
80 #include "common/printf.h"
82 #include "serial_cli.h"
84 extern uint16_t cycleTime; // FIXME dependency on mw.c
86 static serialPort_t *cliPort;
88 static void cliAux(char *cmdline);
89 static void cliAdjustmentRange(char *cmdline);
90 static void cliCMix(char *cmdline);
91 static void cliDefaults(char *cmdline);
92 static void cliDump(char *cmdLine);
93 static void cliExit(char *cmdline);
94 static void cliFeature(char *cmdline);
95 static void cliMotor(char *cmdline);
96 static void cliProfile(char *cmdline);
97 static void cliRateProfile(char *cmdline);
98 static void cliReboot(void);
99 static void cliSave(char *cmdline);
100 static void cliSet(char *cmdline);
101 static void cliGet(char *cmdline);
102 static void cliStatus(char *cmdline);
103 static void cliVersion(char *cmdline);
105 #ifdef GPS
106 static void cliGpsPassthrough(char *cmdline);
107 #endif
109 static void cliHelp(char *cmdline);
110 static void cliMap(char *cmdline);
112 #ifdef LED_STRIP
113 static void cliLed(char *cmdline);
114 static void cliColor(char *cmdline);
115 #endif
117 #ifndef USE_QUAD_MIXER_ONLY
118 static void cliMixer(char *cmdline);
119 #endif
121 // signal that we're in cli mode
122 uint8_t cliMode = 0;
124 // buffer
125 static char cliBuffer[48];
126 static uint32_t bufferIndex = 0;
128 #ifndef USE_QUAD_MIXER_ONLY
129 // sync this with mixerMode_e
130 static const char * const mixerNames[] = {
131 "TRI", "QUADP", "QUADX", "BI",
132 "GIMBAL", "Y6", "HEX6",
133 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
134 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
135 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
136 "ATAIL4", "CUSTOM", NULL
138 #endif
140 // sync this with features_e
141 static const char * const featureNames[] = {
142 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
143 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
144 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
145 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
146 "BLACKBOX", NULL
149 // sync this with sensors_e
150 static const char * const sensorNames[] = {
151 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
154 static const char * const accNames[] = {
155 "", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE", "None", NULL
158 typedef struct {
159 const char *name;
160 const char *param;
161 void (*func)(char *cmdline);
162 } clicmd_t;
164 // should be sorted a..z for bsearch()
165 const clicmd_t cmdTable[] = {
166 { "adjrange", "show/set adjustment ranges settings", cliAdjustmentRange },
167 { "aux", "show/set aux settings", cliAux },
168 { "cmix", "design custom mixer", cliCMix },
169 #ifdef LED_STRIP
170 { "color", "configure colors", cliColor },
171 #endif
172 { "defaults", "reset to defaults and reboot", cliDefaults },
173 { "dump", "dump configuration", cliDump },
174 { "exit", "", cliExit },
175 { "feature", "list or -val or val", cliFeature },
176 { "get", "get variable value", cliGet },
177 #ifdef GPS
178 { "gpspassthrough", "passthrough gps to serial", cliGpsPassthrough },
179 #endif
180 { "help", "", cliHelp },
181 #ifdef LED_STRIP
182 { "led", "configure leds", cliLed },
183 #endif
184 { "map", "mapping of rc channel order", cliMap },
185 #ifndef USE_QUAD_MIXER_ONLY
186 { "mixer", "mixer name or list", cliMixer },
187 #endif
188 { "motor", "get/set motor output value", cliMotor },
189 { "profile", "index (0 to 2)", cliProfile },
190 { "rateprofile", "index (0 to 2)", cliRateProfile },
191 { "save", "save and reboot", cliSave },
192 { "set", "name=value or blank or * for list", cliSet },
193 { "status", "show system status", cliStatus },
194 { "version", "", cliVersion },
196 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
198 typedef enum {
199 VAR_UINT8 = (1 << 0),
200 VAR_INT8 = (1 << 1),
201 VAR_UINT16 = (1 << 2),
202 VAR_INT16 = (1 << 3),
203 VAR_UINT32 = (1 << 4),
204 VAR_FLOAT = (1 << 5),
206 MASTER_VALUE = (1 << 6),
207 PROFILE_VALUE = (1 << 7),
208 CONTROL_RATE_VALUE = (1 << 8)
209 } cliValueFlag_e;
211 #define VALUE_TYPE_MASK (VAR_UINT8 | VAR_INT8 | VAR_UINT16 | VAR_INT16 | VAR_UINT32 | VAR_FLOAT)
212 #define SECTION_MASK (MASTER_VALUE | PROFILE_VALUE | CONTROL_RATE_VALUE)
214 typedef struct {
215 const char *name;
216 const uint16_t type; // cliValueFlag_e - specify one of each from VALUE_TYPE_MASK and SECTION_MASK
217 void *ptr;
218 const int32_t min;
219 const int32_t max;
220 } clivalue_t;
222 const clivalue_t valueTable[] = {
223 { "looptime", VAR_UINT16 | MASTER_VALUE, &masterConfig.looptime, 0, 9000 },
224 { "emf_avoidance", VAR_UINT8 | MASTER_VALUE, &masterConfig.emf_avoidance, 0, 1 },
226 { "mid_rc", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.midrc, 1200, 1700 },
227 { "min_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.mincheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
228 { "max_check", VAR_UINT16 | MASTER_VALUE, &masterConfig.rxConfig.maxcheck, PWM_RANGE_ZERO, PWM_RANGE_MAX },
229 { "rssi_channel", VAR_INT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_channel, 0, MAX_SUPPORTED_RC_CHANNEL_COUNT },
230 { "rssi_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.rssi_scale, RSSI_SCALE_MIN, RSSI_SCALE_MAX },
231 { "input_filtering_mode", VAR_INT8 | MASTER_VALUE, &masterConfig.inputFilteringMode, 0, 1 },
233 { "min_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.minthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
234 { "max_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.maxthrottle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
235 { "min_command", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.mincommand, PWM_RANGE_ZERO, PWM_RANGE_MAX },
236 { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &masterConfig.escAndServoConfig.servoCenterPulse, PWM_RANGE_ZERO, PWM_RANGE_MAX },
238 { "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
239 { "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,
240 { "3d_neutral", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.neutral3d, PWM_RANGE_ZERO, PWM_RANGE_MAX },
241 { "3d_deadband_throttle", VAR_UINT16 | MASTER_VALUE, &masterConfig.flight3DConfig.deadband3d_throttle, PWM_RANGE_ZERO, PWM_RANGE_MAX },
243 { "motor_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.motor_pwm_rate, 50, 32000 },
244 { "servo_pwm_rate", VAR_UINT16 | MASTER_VALUE, &masterConfig.servo_pwm_rate, 50, 498 },
246 { "retarded_arm", VAR_UINT8 | MASTER_VALUE, &masterConfig.retarded_arm, 0, 1 },
247 { "disarm_kill_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.disarm_kill_switch, 0, 1 },
248 { "auto_disarm_delay", VAR_UINT8 | MASTER_VALUE, &masterConfig.auto_disarm_delay, 0, 60 },
249 { "small_angle", VAR_UINT8 | MASTER_VALUE, &masterConfig.small_angle, 0, 180 },
251 { "flaps_speed", VAR_UINT8 | MASTER_VALUE, &masterConfig.airplaneConfig.flaps_speed, 0, 100 },
253 { "fixedwing_althold_dir", VAR_INT8 | MASTER_VALUE, &masterConfig.airplaneConfig.fixedwing_althold_dir, -1, 1 },
255 { "serial_port_1_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[0], 0, SERIAL_PORT_SCENARIO_MAX },
256 { "serial_port_2_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[1], 0, SERIAL_PORT_SCENARIO_MAX },
257 #if (SERIAL_PORT_COUNT > 2)
258 { "serial_port_3_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[2], 0, SERIAL_PORT_SCENARIO_MAX },
259 #if (SERIAL_PORT_COUNT > 3)
260 { "serial_port_4_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[3], 0, SERIAL_PORT_SCENARIO_MAX },
261 #if (SERIAL_PORT_COUNT > 4)
262 { "serial_port_5_scenario", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.serial_port_scenario[4], 0, SERIAL_PORT_SCENARIO_MAX },
263 #endif
264 #endif
265 #endif
267 { "reboot_character", VAR_UINT8 | MASTER_VALUE, &masterConfig.serialConfig.reboot_character, 48, 126 },
268 { "msp_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.msp_baudrate, 1200, 115200 },
269 { "cli_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.cli_baudrate, 1200, 115200 },
271 #ifdef GPS
272 { "gps_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_baudrate, 0, 115200 },
273 { "gps_passthrough_baudrate", VAR_UINT32 | MASTER_VALUE, &masterConfig.serialConfig.gps_passthrough_baudrate, 1200, 115200 },
275 { "gps_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.provider, 0, GPS_PROVIDER_MAX },
276 { "gps_sbas_mode", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.sbasMode, 0, SBAS_MODE_MAX },
277 { "gps_auto_config", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoConfig, GPS_AUTOCONFIG_OFF, GPS_AUTOCONFIG_ON },
278 { "gps_auto_baud", VAR_UINT8 | MASTER_VALUE, &masterConfig.gpsConfig.autoBaud, GPS_AUTOBAUD_OFF, GPS_AUTOBAUD_ON },
281 { "gps_pos_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOS], 0, 200 },
282 { "gps_pos_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOS], 0, 200 },
283 { "gps_pos_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOS], 0, 200 },
284 { "gps_posr_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDPOSR], 0, 200 },
285 { "gps_posr_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDPOSR], 0, 200 },
286 { "gps_posr_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDPOSR], 0, 200 },
287 { "gps_nav_p", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDNAVR], 0, 200 },
288 { "gps_nav_i", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDNAVR], 0, 200 },
289 { "gps_nav_d", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDNAVR], 0, 200 },
290 { "gps_wp_radius", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.gps_wp_radius, 0, 2000 },
291 { "nav_controls_heading", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_controls_heading, 0, 1 },
292 { "nav_speed_min", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_min, 10, 2000 },
293 { "nav_speed_max", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_speed_max, 10, 2000 },
294 { "nav_slew_rate", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gpsProfile.nav_slew_rate, 0, 100 },
295 #endif
297 { "serialrx_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.serialrx_provider, 0, SERIALRX_PROVIDER_MAX },
298 { "spektrum_sat_bind", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.spektrum_sat_bind, SPEKTRUM_SAT_BIND_DISABLED, SPEKTRUM_SAT_BIND_MAX},
300 { "telemetry_provider", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_provider, 0, TELEMETRY_PROVIDER_MAX },
301 { "telemetry_switch", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_switch, 0, 1 },
302 { "telemetry_inversion", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.telemetry_inversion, 0, 1 },
303 { "frsky_default_lattitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLatitude, -90.0, 90.0 },
304 { "frsky_default_longitude", VAR_FLOAT | MASTER_VALUE, &masterConfig.telemetryConfig.gpsNoFixLongitude, -180.0, 180.0 },
305 { "frsky_coordinates_format", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_coordinate_format, 0, FRSKY_FORMAT_NMEA },
306 { "frsky_unit", VAR_UINT8 | MASTER_VALUE, &masterConfig.telemetryConfig.frsky_unit, 0, FRSKY_UNIT_IMPERIALS },
308 { "battery_capacity", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.batteryCapacity, 0, 20000 },
309 { "vbat_scale", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatscale, VBAT_SCALE_MIN, VBAT_SCALE_MAX },
310 { "vbat_max_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50 },
311 { "vbat_min_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatmincellvoltage, 10, 50 },
312 { "vbat_warning_cell_voltage", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.vbatwarningcellvoltage, 10, 50 },
313 { "current_meter_scale", VAR_INT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterScale, -10000, 10000 },
314 { "current_meter_offset", VAR_UINT16 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterOffset, 0, 3300 },
315 { "multiwii_current_meter_output", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.multiwiiCurrentMeterOutput, 0, 1 },
316 { "current_meter_type", VAR_UINT8 | MASTER_VALUE, &masterConfig.batteryConfig.currentMeterType, 0, CURRENT_SENSOR_MAX },
318 { "align_gyro", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.gyro_align, 0, 8 },
319 { "align_acc", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.acc_align, 0, 8 },
320 { "align_mag", VAR_UINT8 | MASTER_VALUE, &masterConfig.sensorAlignmentConfig.mag_align, 0, 8 },
322 { "align_board_roll", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.rollDegrees, -180, 360 },
323 { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.pitchDegrees, -180, 360 },
324 { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &masterConfig.boardAlignment.yawDegrees, -180, 360 },
326 { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, 100, 900 },
328 { "gyro_lpf", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_lpf, 0, 256 },
329 { "moron_threshold", VAR_UINT8 | MASTER_VALUE, &masterConfig.gyroConfig.gyroMovementCalibrationThreshold, 0, 128 },
330 { "gyro_cmpf_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpf_factor, 100, 1000 },
331 { "gyro_cmpfm_factor", VAR_UINT16 | MASTER_VALUE, &masterConfig.gyro_cmpfm_factor, 100, 1000 },
333 { "alt_hold_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_deadband, 1, 250 },
334 { "alt_hold_fast_change", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.alt_hold_fast_change, 0, 1 },
335 { "deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.deadband, 0, 32 },
336 { "yaw_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].rcControlsConfig.yaw_deadband, 0, 100 },
338 { "throttle_correction_value", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_value, 0, 150 },
339 { "throttle_correction_angle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].throttle_correction_angle, 1, 900 },
341 { "yaw_control_direction", VAR_INT8 | MASTER_VALUE, &masterConfig.yaw_control_direction, -1, 1 },
342 { "yaw_direction", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.yaw_direction, -1, 1 },
343 { "tri_unarmed_servo", VAR_INT8 | PROFILE_VALUE, &masterConfig.profile[0].mixerConfig.tri_unarmed_servo, 0, 1 },
345 { "default_rate_profile", VAR_UINT8 | PROFILE_VALUE , &masterConfig.profile[0].defaultRateProfileIndex, 0, MAX_CONTROL_RATE_PROFILE_COUNT - 1 },
346 { "rc_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcRate8, 0, 250 },
347 { "rc_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rcExpo8, 0, 100 },
348 { "thr_mid", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrMid8, 0, 100 },
349 { "thr_expo", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].thrExpo8, 0, 100 },
350 { "roll_pitch_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].rollPitchRate, 0, 100 },
351 { "yaw_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].yawRate, 0, 100 },
352 { "tpa_rate", VAR_UINT8 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].dynThrPID, 0, 100},
353 { "tpa_breakpoint", VAR_UINT16 | CONTROL_RATE_VALUE, &masterConfig.controlRateProfiles[0].tpa_breakpoint, PWM_RANGE_MIN, PWM_RANGE_MAX},
355 { "failsafe_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_delay, 0, 200 },
356 { "failsafe_off_delay", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_off_delay, 0, 200 },
357 { "failsafe_throttle", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_throttle, PWM_RANGE_MIN, PWM_RANGE_MAX },
358 { "failsafe_min_usec", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_min_usec, 100, PWM_RANGE_MAX },
359 { "failsafe_max_usec", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].failsafeConfig.failsafe_max_usec, 100, PWM_RANGE_MAX + (PWM_RANGE_MAX - PWM_RANGE_MIN) },
361 { "gimbal_flags", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].gimbalConfig.gimbal_flags, 0, 255},
363 { "acc_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.acc_hardware, 0, ACC_NONE },
364 { "acc_lpf_factor", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].acc_lpf_factor, 0, 250 },
365 { "accxy_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.xy, 0, 100 },
366 { "accz_deadband", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].accDeadband.z, 0, 100 },
367 { "accz_lpf_cutoff", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].accz_lpf_cutoff, 1, 20 },
368 { "acc_unarmedcal", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].acc_unarmedcal, 0, 1 },
369 { "acc_trim_pitch", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.pitch, -300, 300 },
370 { "acc_trim_roll", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].accelerometerTrims.values.roll, -300, 300 },
372 { "baro_tab_size", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_sample_count, 0, BARO_SAMPLE_COUNT_MAX },
373 { "baro_noise_lpf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_noise_lpf, 0, 1 },
374 { "baro_cf_vel", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_vel, 0, 1 },
375 { "baro_cf_alt", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].barometerConfig.baro_cf_alt, 0, 1 },
377 { "mag_hardware", VAR_UINT8 | MASTER_VALUE, &masterConfig.mag_hardware, 0, MAG_NONE },
378 { "mag_declination", VAR_INT16 | PROFILE_VALUE, &masterConfig.profile[0].mag_declination, -18000, 18000 },
380 { "pid_controller", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidController, 0, 5 },
382 { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], 0, 200 },
383 { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], 0, 200 },
384 { "d_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PITCH], 0, 200 },
385 { "p_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[ROLL], 0, 200 },
386 { "i_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[ROLL], 0, 200 },
387 { "d_roll", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[ROLL], 0, 200 },
388 { "p_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[YAW], 0, 200 },
389 { "i_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[YAW], 0, 200 },
390 { "d_yaw", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[YAW], 0, 200 },
392 { "p_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[PITCH], 0, 100 },
393 { "i_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[PITCH], 0, 100 },
394 { "d_pitchf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[PITCH], 0, 100 },
395 { "p_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[ROLL], 0, 100 },
396 { "i_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[ROLL], 0, 100 },
397 { "d_rollf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[ROLL], 0, 100 },
398 { "p_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P_f[YAW], 0, 100 },
399 { "i_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I_f[YAW], 0, 100 },
400 { "d_yawf", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D_f[YAW], 0, 100 },
402 { "level_horizon", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_level, 0, 10 },
403 { "level_angle", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.A_level, 0, 10 },
404 { "sensitivity_horizon", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.H_sensitivity, 0, 250 },
406 { "p_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDALT], 0, 200 },
407 { "i_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDALT], 0, 200 },
408 { "d_alt", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDALT], 0, 200 },
410 { "p_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDLEVEL], 0, 200 },
411 { "i_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDLEVEL], 0, 200 },
412 { "d_level", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDLEVEL], 0, 200 },
414 { "p_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PIDVEL], 0, 200 },
415 { "i_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PIDVEL], 0, 200 },
416 { "d_vel", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.D8[PIDVEL], 0, 200 },
418 #ifdef BLACKBOX
419 { "blackbox_rate_num", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_num, 1, 32 },
420 { "blackbox_rate_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.blackbox_rate_denom, 1, 32 },
421 #endif
424 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
427 typedef union {
428 int32_t int_value;
429 float float_value;
430 } int_float_value_t;
432 static void cliSetVar(const clivalue_t *var, const int_float_value_t value);
433 static void cliPrintVar(const clivalue_t *var, uint32_t full);
434 static void cliPrint(const char *str);
435 static void cliWrite(uint8_t ch);
436 static void cliPrompt(void)
438 cliPrint("\r\n# ");
441 static int cliCompare(const void *a, const void *b)
443 const clicmd_t *ca = a, *cb = b;
444 return strncasecmp(ca->name, cb->name, strlen(cb->name));
447 static char *processChannelRangeArgs(char *ptr, channelRange_t *range, uint8_t *validArgumentCount)
449 int val;
450 ptr = strchr(ptr, ' ');
451 if (ptr) {
452 val = atoi(++ptr);
453 val = CHANNEL_VALUE_TO_STEP(val);
454 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
455 range->startStep = val;
456 (*validArgumentCount)++;
459 ptr = strchr(ptr, ' ');
460 if (ptr) {
461 val = atoi(++ptr);
462 val = CHANNEL_VALUE_TO_STEP(val);
463 if (val >= MIN_MODE_RANGE_STEP && val <= MAX_MODE_RANGE_STEP) {
464 range->endStep = val;
465 (*validArgumentCount)++;
468 return ptr;
471 static void cliAux(char *cmdline)
473 int i, val = 0;
474 uint8_t len;
475 char *ptr;
477 len = strlen(cmdline);
478 if (len == 0) {
479 // print out aux channel settings
480 for (i = 0; i < MAX_MODE_ACTIVATION_CONDITION_COUNT; i++) {
481 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
482 printf("aux %u %u %u %u %u\r\n",
484 mac->modeId,
485 mac->auxChannelIndex,
486 MODE_STEP_TO_CHANNEL_VALUE(mac->range.startStep),
487 MODE_STEP_TO_CHANNEL_VALUE(mac->range.endStep)
490 } else {
491 ptr = cmdline;
492 i = atoi(ptr++);
493 if (i < MAX_MODE_ACTIVATION_CONDITION_COUNT) {
494 modeActivationCondition_t *mac = &currentProfile->modeActivationConditions[i];
495 uint8_t validArgumentCount = 0;
496 ptr = strchr(ptr, ' ');
497 if (ptr) {
498 val = atoi(++ptr);
499 if (val >= 0 && val < CHECKBOX_ITEM_COUNT) {
500 mac->modeId = val;
501 validArgumentCount++;
504 ptr = strchr(ptr, ' ');
505 if (ptr) {
506 val = atoi(++ptr);
507 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
508 mac->auxChannelIndex = val;
509 validArgumentCount++;
512 ptr = processChannelRangeArgs(ptr, &mac->range, &validArgumentCount);
514 if (validArgumentCount != 4) {
515 memset(mac, 0, sizeof(modeActivationCondition_t));
517 } else {
518 printf("index: must be < %u\r\n", MAX_MODE_ACTIVATION_CONDITION_COUNT);
524 static void cliAdjustmentRange(char *cmdline)
526 int i, val = 0;
527 uint8_t len;
528 char *ptr;
530 len = strlen(cmdline);
531 if (len == 0) {
532 // print out adjustment ranges channel settings
533 for (i = 0; i < MAX_ADJUSTMENT_RANGE_COUNT; i++) {
534 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
535 printf("adjrange %u %u %u %u %u %u %u\r\n",
537 ar->adjustmentIndex,
538 ar->auxChannelIndex,
539 MODE_STEP_TO_CHANNEL_VALUE(ar->range.startStep),
540 MODE_STEP_TO_CHANNEL_VALUE(ar->range.endStep),
541 ar->adjustmentFunction,
542 ar->auxSwitchChannelIndex
545 } else {
546 ptr = cmdline;
547 i = atoi(ptr++);
548 if (i < MAX_ADJUSTMENT_RANGE_COUNT) {
549 adjustmentRange_t *ar = &currentProfile->adjustmentRanges[i];
550 uint8_t validArgumentCount = 0;
551 ptr = strchr(ptr, ' ');
552 if (ptr) {
553 val = atoi(++ptr);
554 if (val >= 0 && val < MAX_SIMULTANEOUS_ADJUSTMENT_COUNT) {
555 ar->adjustmentIndex = val;
556 validArgumentCount++;
559 ptr = strchr(ptr, ' ');
560 if (ptr) {
561 val = atoi(++ptr);
562 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
563 ar->auxChannelIndex = val;
564 validArgumentCount++;
567 ptr = processChannelRangeArgs(ptr, &ar->range, &validArgumentCount);
568 ptr = strchr(ptr, ' ');
569 if (ptr) {
570 val = atoi(++ptr);
571 if (val >= 0 && val < ADJUSTMENT_FUNCTION_COUNT) {
572 ar->adjustmentFunction = val;
573 validArgumentCount++;
576 ptr = strchr(ptr, ' ');
577 if (ptr) {
578 val = atoi(++ptr);
579 if (val >= 0 && val < MAX_AUX_CHANNEL_COUNT) {
580 ar->auxSwitchChannelIndex = val;
581 validArgumentCount++;
585 if (validArgumentCount != 6) {
586 memset(ar, 0, sizeof(adjustmentRange_t));
588 } else {
589 printf("index: must be < %u\r\n", MAX_ADJUSTMENT_RANGE_COUNT);
594 static void cliCMix(char *cmdline)
596 #ifdef USE_QUAD_MIXER_ONLY
597 UNUSED(cmdline);
598 #else
599 int i, check = 0;
600 int num_motors = 0;
601 uint8_t len;
602 char buf[16];
603 float mixsum[3];
604 char *ptr;
606 len = strlen(cmdline);
608 if (len == 0) {
609 cliPrint("Custom mixer: \r\nMotor\tThr\tRoll\tPitch\tYaw\r\n");
610 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
611 if (masterConfig.customMixer[i].throttle == 0.0f)
612 break;
613 num_motors++;
614 printf("#%d:\t", i + 1);
615 printf("%s\t", ftoa(masterConfig.customMixer[i].throttle, buf));
616 printf("%s\t", ftoa(masterConfig.customMixer[i].roll, buf));
617 printf("%s\t", ftoa(masterConfig.customMixer[i].pitch, buf));
618 printf("%s\r\n", ftoa(masterConfig.customMixer[i].yaw, buf));
620 mixsum[0] = mixsum[1] = mixsum[2] = 0.0f;
621 for (i = 0; i < num_motors; i++) {
622 mixsum[0] += masterConfig.customMixer[i].roll;
623 mixsum[1] += masterConfig.customMixer[i].pitch;
624 mixsum[2] += masterConfig.customMixer[i].yaw;
626 cliPrint("Sanity check:\t");
627 for (i = 0; i < 3; i++)
628 cliPrint(fabsf(mixsum[i]) > 0.01f ? "NG\t" : "OK\t");
629 cliPrint("\r\n");
630 return;
631 } else if (strncasecmp(cmdline, "reset", 5) == 0) {
632 // erase custom mixer
633 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++)
634 masterConfig.customMixer[i].throttle = 0.0f;
635 } else if (strncasecmp(cmdline, "load", 4) == 0) {
636 ptr = strchr(cmdline, ' ');
637 if (ptr) {
638 len = strlen(++ptr);
639 for (i = 0; ; i++) {
640 if (mixerNames[i] == NULL) {
641 cliPrint("Invalid mixer type\r\n");
642 break;
644 if (strncasecmp(ptr, mixerNames[i], len) == 0) {
645 mixerLoadMix(i, masterConfig.customMixer);
646 printf("Loaded %s mix\r\n", mixerNames[i]);
647 cliCMix("");
648 break;
652 } else {
653 ptr = cmdline;
654 i = atoi(ptr); // get motor number
655 if (--i < MAX_SUPPORTED_MOTORS) {
656 ptr = strchr(ptr, ' ');
657 if (ptr) {
658 masterConfig.customMixer[i].throttle = fastA2F(++ptr);
659 check++;
661 ptr = strchr(ptr, ' ');
662 if (ptr) {
663 masterConfig.customMixer[i].roll = fastA2F(++ptr);
664 check++;
666 ptr = strchr(ptr, ' ');
667 if (ptr) {
668 masterConfig.customMixer[i].pitch = fastA2F(++ptr);
669 check++;
671 ptr = strchr(ptr, ' ');
672 if (ptr) {
673 masterConfig.customMixer[i].yaw = fastA2F(++ptr);
674 check++;
676 if (check != 4) {
677 cliPrint("Wrong number of arguments, needs idx thr roll pitch yaw\r\n");
678 } else {
679 cliCMix("");
681 } else {
682 printf("Motor number must be between 1 and %d\r\n", MAX_SUPPORTED_MOTORS);
685 #endif
688 #ifdef LED_STRIP
689 static void cliLed(char *cmdline)
691 int i;
692 uint8_t len;
693 char *ptr;
694 char ledConfigBuffer[20];
696 len = strlen(cmdline);
697 if (len == 0) {
698 for (i = 0; i < MAX_LED_STRIP_LENGTH; i++) {
699 generateLedConfig(i, ledConfigBuffer, sizeof(ledConfigBuffer));
700 printf("led %u %s\r\n", i, ledConfigBuffer);
702 } else {
703 ptr = cmdline;
704 i = atoi(ptr);
705 if (i < MAX_LED_STRIP_LENGTH) {
706 ptr = strchr(cmdline, ' ');
707 if (!parseLedStripConfig(i, ++ptr)) {
708 printf("Parse error\r\n", MAX_LED_STRIP_LENGTH);
710 } else {
711 printf("Invalid led index: must be < %u\r\n", MAX_LED_STRIP_LENGTH);
716 static void cliColor(char *cmdline)
718 int i;
719 uint8_t len;
720 char *ptr;
722 len = strlen(cmdline);
723 if (len == 0) {
724 for (i = 0; i < CONFIGURABLE_COLOR_COUNT; i++) {
725 printf("color %u %d,%u,%u\r\n", i, masterConfig.colors[i].h, masterConfig.colors[i].s, masterConfig.colors[i].v);
727 } else {
728 ptr = cmdline;
729 i = atoi(ptr);
730 if (i < CONFIGURABLE_COLOR_COUNT) {
731 ptr = strchr(cmdline, ' ');
732 if (!parseColor(i, ++ptr)) {
733 printf("Parse error\r\n", CONFIGURABLE_COLOR_COUNT);
735 } else {
736 printf("Invalid color index: must be < %u\r\n", CONFIGURABLE_COLOR_COUNT);
740 #endif
742 static void dumpValues(uint16_t mask)
744 uint32_t i;
745 const clivalue_t *value;
746 for (i = 0; i < VALUE_COUNT; i++) {
747 value = &valueTable[i];
749 if ((value->type & mask) == 0) {
750 continue;
753 printf("set %s = ", valueTable[i].name);
754 cliPrintVar(value, 0);
755 cliPrint("\r\n");
759 typedef enum {
760 DUMP_MASTER = (1 << 0),
761 DUMP_PROFILE = (1 << 1),
762 DUMP_CONTROL_RATE_PROFILE = (1 << 2)
763 } dumpFlags_e;
765 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
768 static const char* const sectionBreak = "\r\n";
770 #define printSectionBreak() printf((char *)sectionBreak)
772 static void cliDump(char *cmdline)
774 unsigned int i;
775 char buf[16];
776 uint32_t mask;
778 #ifndef USE_QUAD_MIXER_ONLY
779 float thr, roll, pitch, yaw;
780 #endif
782 uint8_t dumpMask = DUMP_ALL;
783 if (strcasecmp(cmdline, "master") == 0) {
784 dumpMask = DUMP_MASTER; // only
786 if (strcasecmp(cmdline, "profile") == 0) {
787 dumpMask = DUMP_PROFILE; // only
789 if (strcasecmp(cmdline, "rates") == 0) {
790 dumpMask = DUMP_CONTROL_RATE_PROFILE; // only
793 if (dumpMask & DUMP_MASTER) {
795 printf("\r\n# version\r\n");
796 cliVersion(NULL);
798 printf("\r\n# dump master\r\n");
799 printf("\r\n# mixer\r\n");
801 #ifndef USE_QUAD_MIXER_ONLY
802 printf("mixer %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
804 if (masterConfig.customMixer[0].throttle != 0.0f) {
805 for (i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
806 if (masterConfig.customMixer[i].throttle == 0.0f)
807 break;
808 thr = masterConfig.customMixer[i].throttle;
809 roll = masterConfig.customMixer[i].roll;
810 pitch = masterConfig.customMixer[i].pitch;
811 yaw = masterConfig.customMixer[i].yaw;
812 printf("cmix %d", i + 1);
813 if (thr < 0)
814 printf(" ");
815 printf("%s", ftoa(thr, buf));
816 if (roll < 0)
817 printf(" ");
818 printf("%s", ftoa(roll, buf));
819 if (pitch < 0)
820 printf(" ");
821 printf("%s", ftoa(pitch, buf));
822 if (yaw < 0)
823 printf(" ");
824 printf("%s\r\n", ftoa(yaw, buf));
826 printf("cmix %d 0 0 0 0\r\n", i + 1);
828 #endif
830 printf("\r\n\r\n# feature\r\n");
832 mask = featureMask();
833 for (i = 0; ; i++) { // disable all feature first
834 if (featureNames[i] == NULL)
835 break;
836 printf("feature -%s\r\n", featureNames[i]);
838 for (i = 0; ; i++) { // reenable what we want.
839 if (featureNames[i] == NULL)
840 break;
841 if (mask & (1 << i))
842 printf("feature %s\r\n", featureNames[i]);
845 printf("\r\n\r\n# map\r\n");
847 for (i = 0; i < 8; i++)
848 buf[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
849 buf[i] = '\0';
850 printf("map %s\r\n", buf);
852 #ifdef LED_STRIP
853 printf("\r\n\r\n# led\r\n");
854 cliLed("");
856 printf("\r\n\r\n# color\r\n");
857 cliColor("");
858 #endif
859 printSectionBreak();
860 dumpValues(MASTER_VALUE);
863 if (dumpMask & DUMP_PROFILE) {
864 printf("\r\n# dump profile\r\n");
866 printf("\r\n# profile\r\n");
867 cliProfile("");
869 printf("\r\n# aux\r\n");
871 cliAux("");
873 printf("\r\n# adjrange\r\n");
875 cliAdjustmentRange("");
877 printSectionBreak();
879 dumpValues(PROFILE_VALUE);
882 if (dumpMask & DUMP_CONTROL_RATE_PROFILE) {
883 printf("\r\n# dump rates\r\n");
885 printf("\r\n# rateprofile\r\n");
886 cliRateProfile("");
888 printSectionBreak();
890 dumpValues(CONTROL_RATE_VALUE);
894 static void cliEnter(void)
896 cliMode = 1;
897 beginSerialPortFunction(cliPort, FUNCTION_CLI);
898 setPrintfSerialPort(cliPort);
899 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
900 cliPrompt();
903 static void cliExit(char *cmdline)
905 UNUSED(cmdline);
906 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
907 *cliBuffer = '\0';
908 bufferIndex = 0;
909 cliMode = 0;
910 // incase a motor was left running during motortest, clear it here
911 mixerResetMotors();
912 cliReboot();
915 static void cliFeature(char *cmdline)
917 uint32_t i;
918 uint32_t len;
919 uint32_t mask;
921 len = strlen(cmdline);
922 mask = featureMask();
924 if (len == 0) {
925 cliPrint("Enabled features: ");
926 for (i = 0; ; i++) {
927 if (featureNames[i] == NULL)
928 break;
929 if (mask & (1 << i))
930 printf("%s ", featureNames[i]);
932 cliPrint("\r\n");
933 } else if (strncasecmp(cmdline, "list", len) == 0) {
934 cliPrint("Available features: ");
935 for (i = 0; ; i++) {
936 if (featureNames[i] == NULL)
937 break;
938 printf("%s ", featureNames[i]);
940 cliPrint("\r\n");
941 return;
942 } else {
943 bool remove = false;
944 if (cmdline[0] == '-') {
945 // remove feature
946 remove = true;
947 cmdline++; // skip over -
948 len--;
951 for (i = 0; ; i++) {
952 if (featureNames[i] == NULL) {
953 cliPrint("Invalid feature name\r\n");
954 break;
957 if (strncasecmp(cmdline, featureNames[i], len) == 0) {
959 mask = 1 << i;
960 #ifndef GPS
961 if (mask & FEATURE_GPS) {
962 cliPrint("GPS unavailable\r\n");
963 break;
965 #endif
966 #ifndef SONAR
967 if (mask & FEATURE_SONAR) {
968 cliPrint("SONAR unavailable\r\n");
969 break;
971 #endif
972 if (remove) {
973 featureClear(mask);
974 cliPrint("Disabled ");
975 } else {
976 featureSet(mask);
977 cliPrint("Enabled ");
979 printf("%s\r\n", featureNames[i]);
980 break;
986 #ifdef GPS
987 static void cliGpsPassthrough(char *cmdline)
989 UNUSED(cmdline);
991 gpsEnablePassthroughResult_e result = gpsEnablePassthrough();
993 switch (result) {
994 case GPS_PASSTHROUGH_NO_SERIAL_PORT:
995 cliPrint("Error: Enable and plug in GPS first\r\n");
996 break;
998 default:
999 break;
1002 #endif
1004 static void cliHelp(char *cmdline)
1006 uint32_t i = 0;
1008 UNUSED(cmdline);
1010 cliPrint("Available commands:\r\n");
1011 for (i = 0; i < CMD_COUNT; i++)
1012 printf("%s\t%s\r\n", cmdTable[i].name, cmdTable[i].param);
1015 static void cliMap(char *cmdline)
1017 uint32_t len;
1018 uint32_t i;
1019 char out[9];
1021 len = strlen(cmdline);
1023 if (len == 8) {
1024 // uppercase it
1025 for (i = 0; i < 8; i++)
1026 cmdline[i] = toupper((unsigned char)cmdline[i]);
1027 for (i = 0; i < 8; i++) {
1028 if (strchr(rcChannelLetters, cmdline[i]) && !strchr(cmdline + i + 1, cmdline[i]))
1029 continue;
1030 cliPrint("Must be any order of AETR1234\r\n");
1031 return;
1033 parseRcChannels(cmdline, &masterConfig.rxConfig);
1035 cliPrint("Current assignment: ");
1036 for (i = 0; i < 8; i++)
1037 out[masterConfig.rxConfig.rcmap[i]] = rcChannelLetters[i];
1038 out[i] = '\0';
1039 printf("%s\r\n", out);
1042 #ifndef USE_QUAD_MIXER_ONLY
1043 static void cliMixer(char *cmdline)
1045 int i;
1046 int len;
1048 len = strlen(cmdline);
1050 if (len == 0) {
1051 printf("Current mixer: %s\r\n", mixerNames[masterConfig.mixerMode - 1]);
1052 return;
1053 } else if (strncasecmp(cmdline, "list", len) == 0) {
1054 cliPrint("Available mixers: ");
1055 for (i = 0; ; i++) {
1056 if (mixerNames[i] == NULL)
1057 break;
1058 printf("%s ", mixerNames[i]);
1060 cliPrint("\r\n");
1061 return;
1064 for (i = 0; ; i++) {
1065 if (mixerNames[i] == NULL) {
1066 cliPrint("Invalid mixer type\r\n");
1067 break;
1069 if (strncasecmp(cmdline, mixerNames[i], len) == 0) {
1070 masterConfig.mixerMode = i + 1;
1071 printf("Mixer set to %s\r\n", mixerNames[i]);
1072 break;
1076 #endif
1078 static void cliMotor(char *cmdline)
1080 int motor_index = 0;
1081 int motor_value = 0;
1082 int len, index = 0;
1083 char *pch = NULL;
1085 len = strlen(cmdline);
1086 if (len == 0) {
1087 printf("Usage:\r\nmotor index [value] - show [or set] motor value\r\n");
1088 return;
1091 pch = strtok(cmdline, " ");
1092 while (pch != NULL) {
1093 switch (index) {
1094 case 0:
1095 motor_index = atoi(pch);
1096 break;
1097 case 1:
1098 motor_value = atoi(pch);
1099 break;
1101 index++;
1102 pch = strtok(NULL, " ");
1105 if (motor_index < 0 || motor_index >= MAX_SUPPORTED_MOTORS) {
1106 printf("No such motor, use a number [0, %d]\r\n", MAX_SUPPORTED_MOTORS);
1107 return;
1110 if (index < 2) {
1111 printf("Motor %d is set at %d\r\n", motor_index, motor_disarmed[motor_index]);
1112 return;
1115 if (motor_value < PWM_RANGE_MIN || motor_value > PWM_RANGE_MAX) {
1116 printf("Invalid motor value, 1000..2000\r\n");
1117 return;
1120 printf("Setting motor %d to %d\r\n", motor_index, motor_value);
1121 motor_disarmed[motor_index] = motor_value;
1124 static void cliProfile(char *cmdline)
1126 uint8_t len;
1127 int i;
1129 len = strlen(cmdline);
1130 if (len == 0) {
1131 printf("profile %d\r\n", getCurrentProfile());
1132 return;
1133 } else {
1134 i = atoi(cmdline);
1135 if (i >= 0 && i < MAX_PROFILE_COUNT) {
1136 masterConfig.current_profile_index = i;
1137 writeEEPROM();
1138 readEEPROM();
1139 cliProfile("");
1144 static void cliRateProfile(char *cmdline)
1146 uint8_t len;
1147 int i;
1149 len = strlen(cmdline);
1150 if (len == 0) {
1151 printf("rateprofile %d\r\n", getCurrentControlRateProfile());
1152 return;
1153 } else {
1154 i = atoi(cmdline);
1155 if (i >= 0 && i < MAX_CONTROL_RATE_PROFILE_COUNT) {
1156 changeControlRateProfile(i);
1157 cliRateProfile("");
1162 static void cliReboot(void) {
1163 cliPrint("\r\nRebooting");
1164 waitForSerialPortToFinishTransmitting(cliPort);
1165 systemReset();
1168 static void cliSave(char *cmdline)
1170 UNUSED(cmdline);
1172 cliPrint("Saving");
1173 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
1174 writeEEPROM();
1175 cliReboot();
1178 static void cliDefaults(char *cmdline)
1180 UNUSED(cmdline);
1182 cliPrint("Resetting to defaults");
1183 resetEEPROM();
1184 cliReboot();
1187 static void cliPrint(const char *str)
1189 while (*str)
1190 serialWrite(cliPort, *(str++));
1193 static void cliWrite(uint8_t ch)
1195 serialWrite(cliPort, ch);
1198 static void cliPrintVar(const clivalue_t *var, uint32_t full)
1200 int32_t value = 0;
1201 char buf[8];
1203 void *ptr = var->ptr;
1204 if (var->type & PROFILE_VALUE) {
1205 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
1207 if (var->type & CONTROL_RATE_VALUE) {
1208 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
1211 switch (var->type & VALUE_TYPE_MASK) {
1212 case VAR_UINT8:
1213 value = *(uint8_t *)ptr;
1214 break;
1216 case VAR_INT8:
1217 value = *(int8_t *)ptr;
1218 break;
1220 case VAR_UINT16:
1221 value = *(uint16_t *)ptr;
1222 break;
1224 case VAR_INT16:
1225 value = *(int16_t *)ptr;
1226 break;
1228 case VAR_UINT32:
1229 value = *(uint32_t *)ptr;
1230 break;
1232 case VAR_FLOAT:
1233 printf("%s", ftoa(*(float *)ptr, buf));
1234 if (full) {
1235 printf(" %s", ftoa((float)var->min, buf));
1236 printf(" %s", ftoa((float)var->max, buf));
1238 return; // return from case for float only
1240 printf("%d", value);
1241 if (full)
1242 printf(" %d %d", var->min, var->max);
1245 static void cliSetVar(const clivalue_t *var, const int_float_value_t value)
1247 void *ptr = var->ptr;
1248 if (var->type & PROFILE_VALUE) {
1249 ptr = ((uint8_t *)ptr) + (sizeof(profile_t) * masterConfig.current_profile_index);
1251 if (var->type & CONTROL_RATE_VALUE) {
1252 ptr = ((uint8_t *)ptr) + (sizeof(controlRateConfig_t) * getCurrentControlRateProfile());
1255 switch (var->type & VALUE_TYPE_MASK) {
1256 case VAR_UINT8:
1257 case VAR_INT8:
1258 *(char *)ptr = (char)value.int_value;
1259 break;
1261 case VAR_UINT16:
1262 case VAR_INT16:
1263 *(short *)ptr = (short)value.int_value;
1264 break;
1266 case VAR_UINT32:
1267 *(int *)ptr = (int)value.int_value;
1268 break;
1270 case VAR_FLOAT:
1271 *(float *)ptr = (float)value.float_value;
1272 break;
1276 static void cliSet(char *cmdline)
1278 uint32_t i;
1279 uint32_t len;
1280 const clivalue_t *val;
1281 char *eqptr = NULL;
1282 int32_t value = 0;
1283 float valuef = 0;
1285 len = strlen(cmdline);
1287 if (len == 0 || (len == 1 && cmdline[0] == '*')) {
1288 cliPrint("Current settings: \r\n");
1289 for (i = 0; i < VALUE_COUNT; i++) {
1290 val = &valueTable[i];
1291 printf("%s = ", valueTable[i].name);
1292 cliPrintVar(val, len); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
1293 cliPrint("\r\n");
1295 } else if ((eqptr = strstr(cmdline, "=")) != NULL) {
1296 // has equal, set var
1297 char *lastNonSpaceCharacter = eqptr;
1298 while (*(lastNonSpaceCharacter - 1) == ' ') {
1299 lastNonSpaceCharacter--;
1301 uint8_t variableNameLength = lastNonSpaceCharacter - cmdline;
1303 eqptr++;
1304 len--;
1305 value = atoi(eqptr);
1306 valuef = fastA2F(eqptr);
1307 for (i = 0; i < VALUE_COUNT; i++) {
1308 val = &valueTable[i];
1309 // ensure exact match when setting to prevent setting variables with shorter names
1310 if (strncasecmp(cmdline, valueTable[i].name, strlen(valueTable[i].name)) == 0 && variableNameLength == strlen(valueTable[i].name)) {
1311 if (valuef >= valueTable[i].min && valuef <= valueTable[i].max) { // here we compare the float value since... it should work, RIGHT?
1312 int_float_value_t tmp;
1313 if (valueTable[i].type & VAR_FLOAT)
1314 tmp.float_value = valuef;
1315 else
1316 tmp.int_value = value;
1317 cliSetVar(val, tmp);
1318 printf("%s set to ", valueTable[i].name);
1319 cliPrintVar(val, 0);
1320 } else {
1321 cliPrint("Value assignment out of range\r\n");
1323 return;
1326 cliPrint("Unknown variable name\r\n");
1327 } else {
1328 // no equals, check for matching variables.
1329 cliGet(cmdline);
1333 static void cliGet(char *cmdline)
1335 uint32_t i;
1336 const clivalue_t *val;
1337 int matchedCommands = 0;
1339 for (i = 0; i < VALUE_COUNT; i++) {
1340 if (strstr(valueTable[i].name, cmdline)) {
1341 val = &valueTable[i];
1342 printf("%s = ", valueTable[i].name);
1343 cliPrintVar(val, 0);
1344 printf("\r\n");
1346 matchedCommands++;
1351 if (matchedCommands) {
1352 return;
1355 cliPrint("Unknown variable name\r\n");
1358 static void cliStatus(char *cmdline)
1360 uint8_t i;
1361 uint32_t mask;
1363 UNUSED(cmdline);
1365 printf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery)\r\n",
1366 millis() / 1000, vbat, batteryCellCount);
1367 mask = sensorsMask();
1369 printf("CPU %dMHz, detected sensors: ", (SystemCoreClock / 1000000));
1370 for (i = 0; ; i++) {
1371 if (sensorNames[i] == NULL)
1372 break;
1373 if (mask & (1 << i))
1374 printf("%s ", sensorNames[i]);
1376 if (sensors(SENSOR_ACC)) {
1377 printf("ACCHW: %s", accNames[accHardware]);
1378 if (acc.revisionCode)
1379 printf(".%c", acc.revisionCode);
1381 cliPrint("\r\n");
1383 #ifdef USE_I2C
1384 uint16_t i2cErrorCounter = i2cGetErrorCounter();
1385 #else
1386 uint16_t i2cErrorCounter = 0;
1387 #endif
1389 printf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime, i2cErrorCounter, sizeof(master_t));
1392 static void cliVersion(char *cmdline)
1394 UNUSED(cmdline);
1396 printf("Cleanflight/%s %s / %s (%s)", targetName, buildDate, buildTime, shortGitRevision);
1399 void cliProcess(void)
1401 if (!cliMode) {
1402 cliEnter();
1405 while (serialTotalBytesWaiting(cliPort)) {
1406 uint8_t c = serialRead(cliPort);
1407 if (c == '\t' || c == '?') {
1408 // do tab completion
1409 const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
1410 uint32_t i = bufferIndex;
1411 for (cmd = cmdTable; cmd < cmdTable + CMD_COUNT; cmd++) {
1412 if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
1413 continue;
1414 if (!pstart)
1415 pstart = cmd;
1416 pend = cmd;
1418 if (pstart) { /* Buffer matches one or more commands */
1419 for (; ; bufferIndex++) {
1420 if (pstart->name[bufferIndex] != pend->name[bufferIndex])
1421 break;
1422 if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
1423 /* Unambiguous -- append a space */
1424 cliBuffer[bufferIndex++] = ' ';
1425 cliBuffer[bufferIndex] = '\0';
1426 break;
1428 cliBuffer[bufferIndex] = pstart->name[bufferIndex];
1431 if (!bufferIndex || pstart != pend) {
1432 /* Print list of ambiguous matches */
1433 cliPrint("\r\033[K");
1434 for (cmd = pstart; cmd <= pend; cmd++) {
1435 cliPrint(cmd->name);
1436 cliWrite('\t');
1438 cliPrompt();
1439 i = 0; /* Redraw prompt */
1441 for (; i < bufferIndex; i++)
1442 cliWrite(cliBuffer[i]);
1443 } else if (!bufferIndex && c == 4) {
1444 cliExit(cliBuffer);
1445 return;
1446 } else if (c == 12) {
1447 // clear screen
1448 cliPrint("\033[2J\033[1;1H");
1449 cliPrompt();
1450 } else if (bufferIndex && (c == '\n' || c == '\r')) {
1451 // enter pressed
1452 clicmd_t *cmd = NULL;
1453 clicmd_t target;
1454 cliPrint("\r\n");
1455 cliBuffer[bufferIndex] = 0; // null terminate
1457 if (cliBuffer[0] != '#') {
1458 target.name = cliBuffer;
1459 target.param = NULL;
1461 cmd = bsearch(&target, cmdTable, CMD_COUNT, sizeof cmdTable[0], cliCompare);
1462 if (cmd)
1463 cmd->func(cliBuffer + strlen(cmd->name) + 1);
1464 else
1465 cliPrint("Unknown command, try 'help'");
1468 memset(cliBuffer, 0, sizeof(cliBuffer));
1469 bufferIndex = 0;
1471 // 'exit' will reset this flag, so we don't need to print prompt again
1472 if (!cliMode)
1473 return;
1475 cliPrompt();
1476 } else if (c == 127) {
1477 // backspace
1478 if (bufferIndex) {
1479 cliBuffer[--bufferIndex] = 0;
1480 cliPrint("\010 \010");
1482 } else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
1483 if (!bufferIndex && c == 32)
1484 continue;
1485 cliBuffer[bufferIndex++] = c;
1486 cliWrite(c);
1491 void cliInit(serialConfig_t *serialConfig)
1493 cliPort = findOpenSerialPort(FUNCTION_CLI);
1494 if (!cliPort) {
1495 cliPort = openSerialPort(FUNCTION_CLI, NULL, serialConfig->cli_baudrate, MODE_RXTX, SERIAL_NOT_INVERTED);