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/>.
28 #include "build/version.h"
29 #include "build/build_config.h"
30 #include "build/assert.h"
32 #include "scheduler/scheduler.h"
34 #include "common/axis.h"
35 #include "common/maths.h"
36 #include "common/color.h"
37 #include "common/typeconversion.h"
39 #include "drivers/system.h"
41 #include "drivers/sensor.h"
42 #include "drivers/accgyro.h"
43 #include "drivers/compass.h"
45 #include "drivers/serial.h"
46 #include "drivers/bus_i2c.h"
47 #include "drivers/gpio.h"
48 #include "drivers/io.h"
49 #include "drivers/io_impl.h"
50 #include "drivers/timer.h"
51 #include "drivers/pwm_rx.h"
52 #include "drivers/sdcard.h"
54 #include "drivers/buf_writer.h"
56 #include "io/escservo.h"
58 #include "io/gimbal.h"
59 #include "fc/rc_controls.h"
61 #include "io/serial.h"
62 #include "io/ledstrip.h"
63 #include "io/flashfs.h"
64 #include "io/beeper.h"
65 #include "io/asyncfatfs/asyncfatfs.h"
68 #include "rx/spektrum.h"
70 #include "sensors/battery.h"
71 #include "sensors/boardalignment.h"
72 #include "sensors/sensors.h"
73 #include "sensors/acceleration.h"
74 #include "sensors/gyro.h"
75 #include "sensors/compass.h"
76 #include "sensors/barometer.h"
78 #include "flight/pid.h"
79 #include "flight/imu.h"
80 #include "flight/mixer.h"
81 #include "flight/navigation_rewrite.h"
82 #include "flight/failsafe.h"
84 #include "telemetry/telemetry.h"
85 #include "telemetry/frsky.h"
87 #include "fc/runtime_config.h"
89 #include "config/config.h"
90 #include "config/config_profile.h"
91 #include "config/config_master.h"
93 #include "common/printf.h"
95 #include "serial_cli.h"
97 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
98 // signal that we're in cli mode
103 extern uint16_t cycleTime
; // FIXME dependency on mw.c
104 extern uint8_t detectedSensors
[SENSOR_INDEX_COUNT
];
106 void gpsEnablePassthrough(serialPort_t
*gpsPassthroughPort
);
108 static serialPort_t
*cliPort
;
109 static bufWriter_t
*cliWriter
;
110 static uint8_t cliWriteBuffer
[sizeof(*cliWriter
) + 16];
112 #if defined(USE_ASSERT)
113 static void cliAssert(char *cmdline
);
116 static void cliAux(char *cmdline
);
117 static void cliRxFail(char *cmdline
);
118 static void cliAdjustmentRange(char *cmdline
);
119 static void cliMotorMix(char *cmdline
);
120 static void cliDefaults(char *cmdline
);
121 static void cliDump(char *cmdLine
);
122 static void cliExit(char *cmdline
);
123 static void cliFeature(char *cmdline
);
124 static void cliMotor(char *cmdline
);
125 static void cliPlaySound(char *cmdline
);
126 static void cliProfile(char *cmdline
);
127 static void cliRateProfile(char *cmdline
);
128 static void cliReboot(void);
129 static void cliSave(char *cmdline
);
130 static void cliSerial(char *cmdline
);
133 static void cliServo(char *cmdline
);
134 static void cliServoMix(char *cmdline
);
137 static void cliSet(char *cmdline
);
138 static void cliGet(char *cmdline
);
139 static void cliStatus(char *cmdline
);
140 #ifndef SKIP_TASK_STATISTICS
141 static void cliTasks(char *cmdline
);
143 static void cliVersion(char *cmdline
);
144 static void cliRxRange(char *cmdline
);
145 static void cliPFlags(char *cmdline
);
147 #ifndef SKIP_TASK_STATISTICS
148 static void cliResource(char *cmdline
);
151 static void cliGpsPassthrough(char *cmdline
);
154 static void cliHelp(char *cmdline
);
155 static void cliMap(char *cmdline
);
158 static void cliLed(char *cmdline
);
159 static void cliColor(char *cmdline
);
160 static void cliModeColor(char *cmdline
);
163 #ifndef USE_QUAD_MIXER_ONLY
164 static void cliMixer(char *cmdline
);
168 static void cliFlashInfo(char *cmdline
);
169 static void cliFlashErase(char *cmdline
);
170 #ifdef USE_FLASH_TOOLS
171 static void cliFlashWrite(char *cmdline
);
172 static void cliFlashRead(char *cmdline
);
177 static void cliSdInfo(char *cmdline
);
181 static void cliBeeper(char *cmdline
);
185 static char cliBuffer
[48];
186 static uint32_t bufferIndex
= 0;
188 #ifndef USE_QUAD_MIXER_ONLY
189 // sync this with mixerMode_e
190 static const char * const mixerNames
[] = {
191 "TRI", "QUADP", "QUADX", "BI",
192 "GIMBAL", "Y6", "HEX6",
193 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
194 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
195 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
196 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", NULL
200 // sync this with features_e
201 static const char * const featureNames
[] = {
202 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
203 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
204 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
205 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "ONESHOT125",
206 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
207 "SUPEREXPO", "VTX", "RX_NRF24", "SOFTSPI", NULL
210 // sync this with rxFailsafeChannelMode_e
211 static const char rxFailsafeModeCharacters
[] = "ahs";
213 static const rxFailsafeChannelMode_e rxFailsafeModesTable
[RX_FAILSAFE_TYPE_COUNT
][RX_FAILSAFE_MODE_COUNT
] = {
214 { RX_FAILSAFE_MODE_AUTO
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_INVALID
},
215 { RX_FAILSAFE_MODE_INVALID
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
}
218 #if (FLASH_SIZE > 64)
219 // sync this with sensors_e
220 static const char * const sensorTypeNames
[] = {
221 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
224 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG | SENSOR_SONAR)
225 // sync with gyroSensor_e
226 static const char * const gyroNames
[] = { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "FAKE"};
227 // sync with accelerationSensor_e
228 static const char * const accNames
[] = { "None", "", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "FAKE"};
229 // sync with baroSensor_e
230 static const char * const baroNames
[] = { "", "None", "BMP085", "MS5611", "BMP280", "FAKE"};
231 // sync with magSensor_e
232 static const char * const magNames
[] = { "None", "", "HMC5883", "AK8975", "MAG_GPS", "MAG_MAG3110", "MAG_AK8963", "FAKE"};
233 // sycn with rangefinderType_e
234 static const char * const rangefinderNames
[] = { "None", "HCSR04", "SRF10"};
236 static const char * const *sensorHardwareNames
[] = {gyroNames
, accNames
, baroNames
, magNames
, rangefinderNames
};
242 #ifndef SKIP_CLI_COMMAND_HELP
243 const char *description
;
246 void (*func
)(char *cmdline
);
249 #ifndef SKIP_CLI_COMMAND_HELP
250 #define CLI_COMMAND_DEF(name, description, args, method) \
258 #define CLI_COMMAND_DEF(name, description, args, method) \
265 // should be sorted a..z for bsearch()
266 const clicmd_t cmdTable
[] = {
267 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL
, cliAdjustmentRange
),
268 #if defined(USE_ASSERT)
269 CLI_COMMAND_DEF("assert", "", NULL
, cliAssert
),
271 CLI_COMMAND_DEF("aux", "configure modes", NULL
, cliAux
),
273 CLI_COMMAND_DEF("color", "configure colors", NULL
, cliColor
),
274 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL
, cliModeColor
),
276 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL
, cliDefaults
),
277 CLI_COMMAND_DEF("dump", "dump configuration", "[master|profile]", cliDump
),
278 CLI_COMMAND_DEF("exit", NULL
, NULL
, cliExit
),
279 CLI_COMMAND_DEF("feature", "configure features",
281 "\t<+|->[name]", cliFeature
),
283 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL
, cliFlashErase
),
284 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL
, cliFlashInfo
),
285 #ifdef USE_FLASH_TOOLS
286 CLI_COMMAND_DEF("flash_read", NULL
, "<length> <address>", cliFlashRead
),
287 CLI_COMMAND_DEF("flash_write", NULL
, "<address> <message>", cliFlashWrite
),
290 CLI_COMMAND_DEF("get", "get variable value",
293 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL
, cliGpsPassthrough
),
295 CLI_COMMAND_DEF("help", NULL
, NULL
, cliHelp
),
297 CLI_COMMAND_DEF("led", "configure leds", NULL
, cliLed
),
299 CLI_COMMAND_DEF("map", "configure rc channel order",
301 #ifndef USE_QUAD_MIXER_ONLY
302 CLI_COMMAND_DEF("mixer", "configure mixer",
304 "\t<name>", cliMixer
),
306 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL
, cliMotorMix
),
307 CLI_COMMAND_DEF("motor", "get/set motor",
308 "<index> [<value>]", cliMotor
),
309 CLI_COMMAND_DEF("play_sound", NULL
,
310 "[<index>]\r\n", cliPlaySound
),
311 CLI_COMMAND_DEF("profile", "change profile",
312 "[<index>]", cliProfile
),
313 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile
),
314 #ifndef SKIP_TASK_STATISTICS
315 CLI_COMMAND_DEF("resource", "view currently used resources", NULL
, cliResource
),
317 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL
, cliRxRange
),
318 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL
, cliRxFail
),
319 CLI_COMMAND_DEF("save", "save and reboot", NULL
, cliSave
),
320 CLI_COMMAND_DEF("serial", "configure serial ports", NULL
, cliSerial
),
322 CLI_COMMAND_DEF("servo", "configure servos", NULL
, cliServo
),
324 CLI_COMMAND_DEF("set", "change setting",
325 "[<name>=<value>]", cliSet
),
326 CLI_COMMAND_DEF("pflags", "get persistent flags", NULL
, cliPFlags
),
328 CLI_COMMAND_DEF("smix", "servo mixer",
329 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
332 "\treverse <servo> <source> r|n", cliServoMix
),
335 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL
, cliSdInfo
),
337 CLI_COMMAND_DEF("status", "show status", NULL
, cliStatus
),
338 #ifndef SKIP_TASK_STATISTICS
339 CLI_COMMAND_DEF("tasks", "show task stats", NULL
, cliTasks
),
341 CLI_COMMAND_DEF("version", "show version", NULL
, cliVersion
),
343 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
344 "\t<+|->[name]", cliBeeper
),
347 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
349 static const char * const lookupTableOffOn
[] = {
353 static const char * const lookupTableUnit
[] = {
357 static const char * const lookupTableAlignment
[] = {
370 static const char * const lookupTableGPSProvider
[] = {
371 "NMEA", "UBLOX", "I2C-NAV", "NAZA"
374 static const char * const lookupTableGPSSBASMode
[] = {
375 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN", "NONE"
378 static const char * const lookupTableGpsModel
[] = {
379 "PEDESTRIAN", "AIR_1G", "AIR_4G"
383 static const char * const lookupTableCurrentSensor
[] = {
384 "NONE", "ADC", "VIRTUAL"
388 static const char * const lookupTableGimbalMode
[] = {
394 static const char * const lookupTableBlackboxDevice
[] = {
395 "SERIAL", "SPIFLASH", "SDCARD"
399 static const char * const lookupTablePidController
[] = {
400 "UNUSED", "MWREWRITE", "LUX"
404 static const char * const lookupTableSerialRX
[] = {
417 // sync with nrf24_protocol_t
418 static const char * const lookupTableNRF24RX
[] = {
430 static const char * const lookupTableGyroLpf
[] = {
439 static const char * const lookupTableFailsafeProcedure
[] = {
440 "SET-THR", "DROP", "RTH"
444 static const char * const lookupTableNavControlMode
[] = {
448 static const char * const lookupTableNavRthAltMode
[] = {
449 "CURRENT", "EXTRA", "FIXED", "MAX", "AT_LEAST"
453 static const char * const lookupTableAuxOperator
[] = {
457 typedef struct lookupTableEntry_s
{
458 const char * const *values
;
459 const uint8_t valueCount
;
460 } lookupTableEntry_t
;
472 TABLE_BLACKBOX_DEVICE
,
474 TABLE_CURRENT_SENSOR
,
478 TABLE_PID_CONTROLLER
,
486 TABLE_FAILSAFE_PROCEDURE
,
488 TABLE_NAV_USER_CTL_MODE
,
489 TABLE_NAV_RTH_ALT_MODE
,
492 } lookupTableIndex_e
;
494 static const lookupTableEntry_t lookupTables
[] = {
495 { lookupTableOffOn
, sizeof(lookupTableOffOn
) / sizeof(char *) },
496 { lookupTableUnit
, sizeof(lookupTableUnit
) / sizeof(char *) },
497 { lookupTableAlignment
, sizeof(lookupTableAlignment
) / sizeof(char *) },
499 { lookupTableGPSProvider
, sizeof(lookupTableGPSProvider
) / sizeof(char *) },
500 { lookupTableGPSSBASMode
, sizeof(lookupTableGPSSBASMode
) / sizeof(char *) },
501 { lookupTableGpsModel
, sizeof(lookupTableGpsModel
) / sizeof(char *) },
504 { lookupTableBlackboxDevice
, sizeof(lookupTableBlackboxDevice
) / sizeof(char *) },
506 { lookupTableCurrentSensor
, sizeof(lookupTableCurrentSensor
) / sizeof(char *) },
508 { lookupTableGimbalMode
, sizeof(lookupTableGimbalMode
) / sizeof(char *) },
510 { lookupTablePidController
, sizeof(lookupTablePidController
) / sizeof(char *) },
512 { lookupTableSerialRX
, sizeof(lookupTableSerialRX
) / sizeof(char *) },
515 { lookupTableNRF24RX
, sizeof(lookupTableNRF24RX
) / sizeof(char *) },
517 { lookupTableGyroLpf
, sizeof(lookupTableGyroLpf
) / sizeof(char *) },
518 { lookupTableFailsafeProcedure
, sizeof(lookupTableFailsafeProcedure
) / sizeof(char *) },
520 { lookupTableNavControlMode
, sizeof(lookupTableNavControlMode
) / sizeof(char *) },
521 { lookupTableNavRthAltMode
, sizeof(lookupTableNavRthAltMode
) / sizeof(char *) },
523 { lookupTableAuxOperator
, sizeof(lookupTableAuxOperator
) / sizeof(char *) },
526 #define VALUE_TYPE_OFFSET 0
527 #define VALUE_SECTION_OFFSET 4
528 #define VALUE_MODE_OFFSET 6
532 VAR_UINT8
= (0 << VALUE_TYPE_OFFSET
),
533 VAR_INT8
= (1 << VALUE_TYPE_OFFSET
),
534 VAR_UINT16
= (2 << VALUE_TYPE_OFFSET
),
535 VAR_INT16
= (3 << VALUE_TYPE_OFFSET
),
536 VAR_UINT32
= (4 << VALUE_TYPE_OFFSET
),
537 VAR_FLOAT
= (5 << VALUE_TYPE_OFFSET
),
540 MASTER_VALUE
= (0 << VALUE_SECTION_OFFSET
),
541 PROFILE_VALUE
= (1 << VALUE_SECTION_OFFSET
),
542 CONTROL_RATE_VALUE
= (2 << VALUE_SECTION_OFFSET
),
545 MODE_DIRECT
= (0 << VALUE_MODE_OFFSET
),
546 MODE_LOOKUP
= (1 << VALUE_MODE_OFFSET
)
549 #define VALUE_TYPE_MASK (0x0F)
550 #define VALUE_SECTION_MASK (0x30)
551 #define VALUE_MODE_MASK (0xC0)
553 typedef struct cliMinMaxConfig_s
{
558 typedef struct cliLookupTableConfig_s
{
559 const lookupTableIndex_e tableIndex
;
560 } cliLookupTableConfig_t
;
563 cliLookupTableConfig_t lookup
;
564 cliMinMaxConfig_t minmax
;
569 const uint8_t type
; // see cliValueFlag_e
571 const cliValueConfig_t config
;
572 const persistent_flags_e pflags_to_set
;
575 const clivalue_t valueTable
[] = {
576 { "looptime", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.looptime
, .config
.minmax
= {0, 9000}, 0 },
577 { "i2c_overclock", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.i2c_overclock
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
578 { "gyro_sync", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyroSync
, .config
.lookup
= { TABLE_OFF_ON
} },
579 { "gyro_sync_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroSyncDenominator
, .config
.minmax
= { 1, 32 } },
581 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.midrc
, .config
.minmax
= { 1200, 1700 }, 0 },
582 { "min_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.mincheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
583 { "max_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.maxcheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
584 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_channel
, .config
.minmax
= { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
}, 0 },
585 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_scale
, .config
.minmax
= { RSSI_SCALE_MIN
, RSSI_SCALE_MAX
}, 0 },
586 { "rssi_ppm_invert", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rssi_ppm_invert
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
587 { "rc_smoothing", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rcSmoothing
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
588 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.inputFilteringMode
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
590 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.minthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
591 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.maxthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
592 { "min_command", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.mincommand
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
594 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.escAndServoConfig
.servoCenterPulse
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
597 { "3d_deadband_low", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_low
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 }, // FIXME upper limit should match code in the mixer, 1500 currently
598 { "3d_deadband_high", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_high
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 }, // FIXME lower limit should match code in the mixer, 1500 currently,
599 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.neutral3d
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
600 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_throttle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
}, 0 },
602 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motor_pwm_rate
, .config
.minmax
= { 50, 32000 }, 0 },
604 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servo_pwm_rate
, .config
.minmax
= { 50, 498 }, 0 },
607 { "disarm_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.disarm_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
608 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.auto_disarm_delay
, .config
.minmax
= { 0, 60 }, 0 },
609 { "small_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.small_angle
, .config
.minmax
= { 0, 180 }, 0 },
611 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.serialConfig
.reboot_character
, .config
.minmax
= { 48, 126 }, 0 },
614 { "gps_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.provider
, .config
.lookup
= { TABLE_GPS_PROVIDER
}, 0 },
615 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.sbasMode
, .config
.lookup
= { TABLE_GPS_SBAS_MODE
}, 0 },
616 { "gps_dyn_model", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.dynModel
, .config
.lookup
= { TABLE_GPS_DYN_MODEL
}, 0 },
617 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoConfig
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
618 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoBaud
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
622 { "nav_alt_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
623 { "nav_alt_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
624 { "nav_alt_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDALT
], .config
.minmax
= { 0, 255 }, 0 },
626 { "nav_vel_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
627 { "nav_vel_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
628 { "nav_vel_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDVEL
], .config
.minmax
= { 0, 255 }, 0 },
630 { "nav_pos_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
631 { "nav_pos_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
632 { "nav_pos_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOS
], .config
.minmax
= { 0, 255 }, 0 },
633 { "nav_posr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
634 { "nav_posr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
635 { "nav_posr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOSR
], .config
.minmax
= { 0, 255 }, 0 },
636 { "nav_navr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
637 { "nav_navr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
638 { "nav_navr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDNAVR
], .config
.minmax
= { 0, 255 }, 0 },
640 #if defined(NAV_AUTO_MAG_DECLINATION)
641 { "inav_auto_mag_decl", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.automatic_mag_declination
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
644 { "inav_accz_unarmedcal", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.accz_unarmed_cal
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
645 { "inav_use_gps_velned", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.inav
.use_gps_velned
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
646 { "inav_gps_delay", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.gps_delay_ms
, .config
.minmax
= { 0, 500 }, 0 },
647 { "inav_gps_min_sats", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.gps_min_sats
, .config
.minmax
= { 5, 10}, 0 },
649 { "inav_w_z_baro_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_baro_p
, .config
.minmax
= { 0, 10 }, 0 },
650 { "inav_w_z_gps_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_gps_p
, .config
.minmax
= { 0, 10 }, 0 },
651 { "inav_w_z_gps_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_gps_v
, .config
.minmax
= { 0, 10 }, 0 },
652 { "inav_w_xy_gps_p", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_gps_p
, .config
.minmax
= { 0, 10 }, 0 },
653 { "inav_w_xy_gps_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_gps_v
, .config
.minmax
= { 0, 10 }, 0 },
654 { "inav_w_z_res_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_z_res_v
, .config
.minmax
= { 0, 10 }, 0 },
655 { "inav_w_xy_res_v", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_xy_res_v
, .config
.minmax
= { 0, 10 }, 0 },
656 { "inav_w_acc_bias", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.w_acc_bias
, .config
.minmax
= { 0, 1 }, 0 },
658 { "inav_max_eph_epv", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.max_eph_epv
, .config
.minmax
= { 0, 9999 }, 0 },
659 { "inav_baro_epv", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.navConfig
.inav
.baro_epv
, .config
.minmax
= { 0, 9999 }, 0 },
661 { "nav_disarm_on_landing", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.disarm_on_landing
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
662 { "nav_use_midthr_for_althold", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.use_thr_mid_for_althold
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
663 { "nav_extra_arming_safety", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.extra_arming_safety
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
664 { "nav_user_control_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.user_control_mode
, .config
.lookup
= { TABLE_NAV_USER_CTL_MODE
}, 0 },
665 { "nav_position_timeout", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.pos_failure_timeout
, .config
.minmax
= { 0, 10 }, 0 },
666 { "nav_wp_radius", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.waypoint_radius
, .config
.minmax
= { 10, 10000 }, 0 },
667 { "nav_max_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_speed
, .config
.minmax
= { 10, 2000 }, 0 },
668 { "nav_max_climb_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_climb_rate
, .config
.minmax
= { 10, 2000 }, 0 },
669 { "nav_manual_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_manual_speed
, .config
.minmax
= { 10, 2000 }, 0 },
670 { "nav_manual_climb_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.max_manual_climb_rate
, .config
.minmax
= { 10, 2000 }, 0 },
671 { "nav_landing_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.land_descent_rate
, .config
.minmax
= { 100, 2000 }, 0 },
672 { "nav_land_slowdown_minalt", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.land_slowdown_minalt
, .config
.minmax
= { 50, 1000 }, 0 },
673 { "nav_land_slowdown_maxalt", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.land_slowdown_maxalt
, .config
.minmax
= { 500, 4000 }, 0 },
674 { "nav_emerg_landing_speed", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.emerg_descent_rate
, .config
.minmax
= { 100, 2000 }, 0 },
675 { "nav_min_rth_distance", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.min_rth_distance
, .config
.minmax
= { 0, 5000 }, 0 },
676 { "nav_rth_tail_first", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.rth_tail_first
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
677 { "nav_rth_alt_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.navConfig
.flags
.rth_alt_control_style
, .config
.lookup
= { TABLE_NAV_RTH_ALT_MODE
}, 0 },
678 { "nav_rth_altitude", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.rth_altitude
, .config
.minmax
= { 100, 65000 }, 0 },
680 { "nav_mc_bank_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_max_bank_angle
, .config
.minmax
= { 15, 45 }, 0 },
681 { "nav_mc_hover_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_hover_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
682 { "nav_mc_auto_disarm_delay", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.mc_auto_disarm_delay
, .config
.minmax
= { 100, 10000 }, 0 },
684 { "nav_fw_cruise_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_cruise_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
685 { "nav_fw_min_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_min_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
686 { "nav_fw_max_thr", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_throttle
, .config
.minmax
= { 1000, 2000 }, 0 },
687 { "nav_fw_bank_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_bank_angle
, .config
.minmax
= { 5, 45 }, 0 },
688 { "nav_fw_climb_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_climb_angle
, .config
.minmax
= { 5, 45 }, 0 },
689 { "nav_fw_dive_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_max_dive_angle
, .config
.minmax
= { 5, 45 }, 0 },
690 { "nav_fw_pitch2thr", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_pitch_to_throttle
, .config
.minmax
= { 0, 100 }, 0 },
691 { "nav_fw_roll2pitch", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_roll_to_pitch
, .config
.minmax
= { 0, 200 }, 0 },
692 { "nav_fw_loiter_radius", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.navConfig
.fw_loiter_radius
, .config
.minmax
= { 0, 10000 }, 0 },
696 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.serialrx_provider
, .config
.lookup
= { TABLE_SERIAL_RX
}, 0 },
699 { "nrf24rx_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.nrf24rx_protocol
, .config
.lookup
= { TABLE_NRF24_RX
}, 0 },
700 { "nrf24rx_id", VAR_UINT32
| MASTER_VALUE
, &masterConfig
.rxConfig
.nrf24rx_id
, .config
.minmax
= { 0, 0 }, 0 },
701 { "nrf24rx_channel_count", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.nrf24rx_channel_count
, .config
.minmax
= { 0, 8 }, 0 },
704 { "spektrum_sat_bind", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.spektrum_sat_bind
, .config
.minmax
= { SPEKTRUM_SAT_BIND_DISABLED
, SPEKTRUM_SAT_BIND_MAX
}, 0 },
707 { "telemetry_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
708 { "telemetry_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_inversion
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
709 { "frsky_default_lattitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLatitude
, .config
.minmax
= { -90.0, 90.0 }, 0 },
710 { "frsky_default_longitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLongitude
, .config
.minmax
= { -180.0, 180.0 }, 0 },
711 { "frsky_coordinates_format", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_coordinate_format
, .config
.minmax
= { 0, FRSKY_FORMAT_NMEA
}, 0 },
712 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.frsky_unit
, .config
.lookup
= { TABLE_UNIT
}, 0 },
713 { "frsky_vfas_precision", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_vfas_precision
, .config
.minmax
= { FRSKY_VFAS_PRECISION_LOW
, FRSKY_VFAS_PRECISION_HIGH
}, 0 },
714 { "hott_alarm_sound_interval", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.hottAlarmSoundInterval
, .config
.minmax
= { 0, 120 }, 0 },
717 { "battery_capacity", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.batteryCapacity
, .config
.minmax
= { 0, 20000 }, 0 },
718 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatscale
, .config
.minmax
= { VBAT_SCALE_MIN
, VBAT_SCALE_MAX
}, 0 },
719 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmaxcellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
720 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmincellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
721 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatwarningcellvoltage
, .config
.minmax
= { 10, 50 }, 0 },
722 { "current_meter_scale", VAR_INT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterScale
, .config
.minmax
= { -10000, 10000 }, 0 },
723 { "current_meter_offset", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterOffset
, .config
.minmax
= { 0, 3300 }, 0 },
724 { "multiwii_current_meter_output", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.multiwiiCurrentMeterOutput
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
725 { "current_meter_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.currentMeterType
, .config
.lookup
= { TABLE_CURRENT_SENSOR
}, 0 },
727 { "align_gyro", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.gyro_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
728 { "align_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.acc_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
729 { "align_mag", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.mag_align
, .config
.lookup
= { TABLE_ALIGNMENT
}, 0 },
731 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.rollDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
732 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.pitchDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
733 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.yawDeciDegrees
, .config
.minmax
= { -1800, 3600 }, 0 },
735 { "gyro_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyro_lpf
, .config
.lookup
= { TABLE_GYRO_LPF
} },
736 { "moron_threshold", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyroMovementCalibrationThreshold
, .config
.minmax
= { 0, 128 }, 0 },
738 { "imu_dcm_kp", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_kp_acc
, .config
.minmax
= { 0, 65535 }, 0 },
739 { "imu_dcm_ki", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_ki_acc
, .config
.minmax
= { 0, 65535 }, 0 },
740 { "imu_dcm_kp_mag", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_kp_mag
, .config
.minmax
= { 0, 65535 }, 0 },
741 { "imu_dcm_ki_mag", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.dcm_ki_mag
, .config
.minmax
= { 0, 65535 }, 0 },
743 { "deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.deadband
, .config
.minmax
= { 0, 32 }, 0 },
744 { "yaw_deadband", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.yaw_deadband
, .config
.minmax
= { 0, 100 }, 0 },
745 { "pos_hold_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.pos_hold_deadband
, .config
.minmax
= { 10, 250 }, 0 },
746 { "alt_hold_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.profile
[0].rcControlsConfig
.alt_hold_deadband
, .config
.minmax
= { 10, 250 }, 0 },
748 { "throttle_tilt_comp_str", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].throttle_tilt_compensation_strength
, .config
.minmax
= { 0, 100 }, 0 },
750 { "yaw_motor_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_motor_direction
, .config
.minmax
= { -1, 1 }, 0 },
751 { "yaw_jump_prevention_limit", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_jump_prevention_limit
, .config
.minmax
= { YAW_JUMP_PREVENTION_LIMIT_LOW
, YAW_JUMP_PREVENTION_LIMIT_HIGH
}, 0 },
754 { "flaperon_throw_offset", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].flaperon_throw_offset
, .config
.minmax
= { FLAPERON_THROW_MIN
, FLAPERON_THROW_MAX
}, 0 },
755 { "flaperon_throw_inverted", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].flaperon_throw_inverted
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
756 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.mixerConfig
.tri_unarmed_servo
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
757 { "servo_lowpass_freq", VAR_INT16
| MASTER_VALUE
, &masterConfig
.mixerConfig
.servo_lowpass_freq
, .config
.minmax
= { 10, 400}, 0 },
758 { "servo_lowpass_enable", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.mixerConfig
.servo_lowpass_enable
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
761 { "mode_range_logic_operator", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].modeActivationOperator
, .config
.lookup
= { TABLE_AUX_OPERATOR
}, 0 },
762 { "default_rate_profile", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].defaultRateProfileIndex
, .config
.minmax
= { 0, MAX_CONTROL_RATE_PROFILE_COUNT
- 1 }, 0 },
763 { "rc_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcExpo8
, .config
.minmax
= { 0, 100 }, 0 },
764 { "rc_yaw_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rcYawExpo8
, .config
.minmax
= { 0, 100 }, 0 },
765 { "thr_mid", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrMid8
, .config
.minmax
= { 0, 100 }, 0 },
766 { "thr_expo", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].thrExpo8
, .config
.minmax
= { 0, 100 }, 0 },
769 New rates are in dps/10. That means, Rate of 20 means 200dps of rotation speed on given axis.
770 Rate 180 (1800dps) is max. value gyro can measure reliably
772 { "roll_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_ROLL
], .config
.minmax
= { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN
, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
}, 0 },
773 { "pitch_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_PITCH
], .config
.minmax
= { CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MIN
, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
}, 0 },
774 { "yaw_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].rates
[FD_YAW
], .config
.minmax
= { CONTROL_RATE_CONFIG_YAW_RATE_MIN
, CONTROL_RATE_CONFIG_YAW_RATE_MAX
}, 0 },
776 { "tpa_rate", VAR_UINT8
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].dynThrPID
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_TPA_MAX
}, 0 },
777 { "tpa_breakpoint", VAR_UINT16
| CONTROL_RATE_VALUE
, &masterConfig
.controlRateProfiles
[0].tpa_breakpoint
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
}, 0 },
779 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_delay
, .config
.minmax
= { 0, 200 }, 0 },
780 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_off_delay
, .config
.minmax
= { 0, 200 }, 0 },
781 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
}, 0 },
782 { "failsafe_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
783 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
, .config
.minmax
= { 0, 300 }, 0 },
784 { "failsafe_procedure", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_procedure
, .config
.lookup
= { TABLE_FAILSAFE_PROCEDURE
}, 0 },
786 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_min_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, 0 },
787 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_max_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
}, 0 },
790 { "gimbal_mode", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].gimbalConfig
.mode
, .config
.lookup
= { TABLE_GIMBAL_MODE
}, 0 },
793 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.acc_hardware
, .config
.minmax
= { 0, ACC_MAX
}, 0 },
796 { "baro_use_median_filter", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.barometerConfig
.use_median_filtering
, .config
.lookup
= { TABLE_OFF_ON
}, 0 },
797 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.baro_hardware
, .config
.minmax
= { 0, BARO_MAX
}, 0 },
801 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.mag_hardware
, .config
.minmax
= { 0, MAG_MAX
}, 0 },
802 { "mag_declination", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].mag_declination
, .config
.minmax
= { -18000, 18000 }, 0 },
803 { "mag_hold_rate_limit", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.mag_hold_rate_limit
, .config
.minmax
= { MAG_HOLD_RATE_LIMIT_MIN
, MAG_HOLD_RATE_LIMIT_MAX
}, 0 },
806 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
807 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
808 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PITCH
], .config
.minmax
= { 0, 200 }, 0 },
809 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
810 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
811 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[ROLL
], .config
.minmax
= { 0, 200 }, 0 },
812 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
813 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
814 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[YAW
], .config
.minmax
= { 0, 200 }, 0 },
816 { "p_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDLEVEL
], .config
.minmax
= { 0, 255 }, 0 },
817 { "i_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDLEVEL
], .config
.minmax
= { 0, 100 }, 0 },
818 { "d_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDLEVEL
], .config
.minmax
= { 0, 100 }, 0 },
820 { "max_angle_inclination_rll", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.max_angle_inclination
[FD_ROLL
], .config
.minmax
= { 100, 900 }, 0 },
821 { "max_angle_inclination_pit", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.max_angle_inclination
[FD_PITCH
], .config
.minmax
= { 100, 900 }, 0 },
823 { "gyro_soft_lpf_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gyro_soft_lpf_hz
, .config
.minmax
= {0, 200 } },
824 { "acc_soft_lpf_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.acc_soft_lpf_hz
, .config
.minmax
= {0, 200 } },
825 { "dterm_lpf_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_lpf_hz
, .config
.minmax
= {0, 200 } },
826 { "yaw_lpf_hz", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_lpf_hz
, .config
.minmax
= {0, 200 } },
828 { "yaw_p_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_p_limit
, .config
.minmax
= { YAW_P_LIMIT_MIN
, YAW_P_LIMIT_MAX
}, 0 },
830 { "iterm_ignore_threshold", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.rollPitchItermIgnoreRate
, .config
.minmax
= {15, 1000 } },
831 { "yaw_iterm_ignore_threshold", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yawItermIgnoreRate
, .config
.minmax
= {15, 1000 } },
833 { "rate_accel_limit_roll_pitch",VAR_UINT32
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.axisAccelerationLimitRollPitch
, .config
.minmax
= {0, 500000 } },
834 { "rate_accel_limit_yaw", VAR_UINT32
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.axisAccelerationLimitYaw
, .config
.minmax
= {0, 500000 } },
837 { "blackbox_rate_num", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_num
, .config
.minmax
= { 1, 32 }, 0 },
838 { "blackbox_rate_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackbox_rate_denom
, .config
.minmax
= { 1, 32 }, 0 },
839 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.blackbox_device
, .config
.lookup
= { TABLE_BLACKBOX_DEVICE
}, 0 },
843 { "magzero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[X
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
844 { "magzero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Y
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
845 { "magzero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.magZero
.raw
[Z
], .config
.minmax
= { -32768, 32767 }, FLAG_MAG_CALIBRATION_DONE
},
848 { "acczero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[X
], .config
.minmax
= { -32768, 32767 }, 0 },
849 { "acczero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[Y
], .config
.minmax
= { -32768, 32767 }, 0 },
850 { "acczero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accZero
.raw
[Z
], .config
.minmax
= { -32768, 32767 }, 0 },
852 { "ledstrip_visual_beeper", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.ledstrip_visual_beeper
, .config
.lookup
= { TABLE_OFF_ON
} },
855 { "accgain_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[X
], .config
.minmax
= { 1, 8192 }, 0 },
856 { "accgain_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[Y
], .config
.minmax
= { 1, 8192 }, 0 },
857 { "accgain_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accGain
.raw
[Z
], .config
.minmax
= { 1, 8192 }, 0 },
860 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
868 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
);
869 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
);
870 static void cliPrintVarRange(const clivalue_t
*var
);
871 static void cliPrint(const char *str
);
872 static void cliPrintf(const char *fmt
, ...);
873 static void cliWrite(uint8_t ch
);
875 static void cliPrompt(void)
878 bufWriterFlush(cliWriter
);
881 static void cliShowParseError(void)
883 cliPrint("Parse error\r\n");
886 static void cliShowArgumentRangeError(char *name
, int min
, int max
)
888 cliPrintf("%s must be between %d and %d\r\n", name
, min
, max
);
891 static char *processChannelRangeArgs(char *ptr
, channelRange_t
*range
, uint8_t *validArgumentCount
)
895 for (int argIndex
= 0; argIndex
< 2; argIndex
++) {
896 ptr
= strchr(ptr
, ' ');
899 val
= CHANNEL_VALUE_TO_STEP(val
);
900 if (val
>= MIN_MODE_RANGE_STEP
&& val
<= MAX_MODE_RANGE_STEP
) {
902 range
->startStep
= val
;
904 range
->endStep
= val
;
906 (*validArgumentCount
)++;
914 // Check if a string's length is zero
915 static bool isEmpty(const char *string
)
917 return *string
== '\0';
920 static void cliRxFail(char *cmdline
)
925 if (isEmpty(cmdline
)) {
926 // print out rxConfig failsafe settings
927 for (channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
928 cliRxFail(itoa(channel
, buf
, 10));
932 channel
= atoi(ptr
++);
933 if ((channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
)) {
935 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[channel
];
938 rxFailsafeChannelType_e type
= (channel
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_TYPE_FLIGHT
: RX_FAILSAFE_TYPE_AUX
;
939 rxFailsafeChannelMode_e mode
= channelFailsafeConfiguration
->mode
;
940 bool requireValue
= channelFailsafeConfiguration
->mode
== RX_FAILSAFE_MODE_SET
;
942 ptr
= strchr(ptr
, ' ');
944 char *p
= strchr(rxFailsafeModeCharacters
, *(++ptr
));
946 uint8_t requestedMode
= p
- rxFailsafeModeCharacters
;
947 mode
= rxFailsafeModesTable
[type
][requestedMode
];
949 mode
= RX_FAILSAFE_MODE_INVALID
;
951 if (mode
== RX_FAILSAFE_MODE_INVALID
) {
956 requireValue
= mode
== RX_FAILSAFE_MODE_SET
;
958 ptr
= strchr(ptr
, ' ');
965 value
= CHANNEL_VALUE_TO_RXFAIL_STEP(value
);
966 if (value
> MAX_RXFAIL_RANGE_STEP
) {
967 cliPrint("Value out of range\r\n");
971 channelFailsafeConfiguration
->step
= value
;
972 } else if (requireValue
) {
976 channelFailsafeConfiguration
->mode
= mode
;
980 char modeCharacter
= rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
];
982 // triple use of cliPrintf below
983 // 1. acknowledge interpretation on command,
984 // 2. query current setting on single item,
985 // 3. recursive use for full list.
988 cliPrintf("rxfail %u %c %d\r\n",
991 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration
->step
)
994 cliPrintf("rxfail %u %c\r\n",
1000 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
- 1);
1005 #if defined(USE_ASSERT)
1006 static void cliAssert(char *cmdline
)
1010 if (assertFailureLine
) {
1011 if (assertFailureFile
) {
1012 cliPrintf("Assertion failed at line %d, file %s\r\n", assertFailureLine
, assertFailureFile
);
1015 cliPrintf("Assertion failed at line %d\r\n", assertFailureLine
);
1019 cliPrintf("No assert() failed\r\n");
1024 static void cliAux(char *cmdline
)
1029 if (isEmpty(cmdline
)) {
1030 // print out aux channel settings
1031 for (i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
1032 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
1033 cliPrintf("aux %u %u %u %u %u\r\n",
1036 mac
->auxChannelIndex
,
1037 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
1038 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
)
1044 if (i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
) {
1045 modeActivationCondition_t
*mac
= ¤tProfile
->modeActivationConditions
[i
];
1046 uint8_t validArgumentCount
= 0;
1047 ptr
= strchr(ptr
, ' ');
1050 if (val
>= 0 && val
< CHECKBOX_ITEM_COUNT
) {
1052 validArgumentCount
++;
1055 ptr
= strchr(ptr
, ' ');
1058 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1059 mac
->auxChannelIndex
= val
;
1060 validArgumentCount
++;
1063 ptr
= processChannelRangeArgs(ptr
, &mac
->range
, &validArgumentCount
);
1065 if (validArgumentCount
!= 4) {
1066 memset(mac
, 0, sizeof(modeActivationCondition_t
));
1069 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT
- 1);
1074 static void cliSerial(char *cmdline
)
1079 if (isEmpty(cmdline
)) {
1080 for (i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
1081 if (!serialIsPortAvailable(masterConfig
.serialConfig
.portConfigs
[i
].identifier
)) {
1084 cliPrintf("serial %d %d %ld %ld %ld %ld\r\n" ,
1085 masterConfig
.serialConfig
.portConfigs
[i
].identifier
,
1086 masterConfig
.serialConfig
.portConfigs
[i
].functionMask
,
1087 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].msp_baudrateIndex
],
1088 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].gps_baudrateIndex
],
1089 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].telemetry_baudrateIndex
],
1090 baudRates
[masterConfig
.serialConfig
.portConfigs
[i
].blackbox_baudrateIndex
]
1096 serialPortConfig_t portConfig
;
1097 memset(&portConfig
, 0 , sizeof(portConfig
));
1099 serialPortConfig_t
*currentConfig
;
1101 uint8_t validArgumentCount
= 0;
1106 currentConfig
= serialFindPortConfiguration(val
);
1107 if (currentConfig
) {
1108 portConfig
.identifier
= val
;
1109 validArgumentCount
++;
1112 ptr
= strchr(ptr
, ' ');
1115 portConfig
.functionMask
= val
& 0xFFFF;
1116 validArgumentCount
++;
1119 for (i
= 0; i
< 4; i
++) {
1120 ptr
= strchr(ptr
, ' ');
1127 uint8_t baudRateIndex
= lookupBaudRateIndex(val
);
1128 if (baudRates
[baudRateIndex
] != (uint32_t) val
) {
1134 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1137 portConfig
.msp_baudrateIndex
= baudRateIndex
;
1140 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1143 portConfig
.gps_baudrateIndex
= baudRateIndex
;
1146 if (baudRateIndex
!= BAUD_AUTO
&& baudRateIndex
> BAUD_115200
) {
1149 portConfig
.telemetry_baudrateIndex
= baudRateIndex
;
1152 if (baudRateIndex
< BAUD_19200
|| baudRateIndex
> BAUD_250000
) {
1155 portConfig
.blackbox_baudrateIndex
= baudRateIndex
;
1159 validArgumentCount
++;
1162 if (validArgumentCount
< 6) {
1163 cliShowParseError();
1167 memcpy(currentConfig
, &portConfig
, sizeof(portConfig
));
1171 static void cliAdjustmentRange(char *cmdline
)
1176 if (isEmpty(cmdline
)) {
1177 // print out adjustment ranges channel settings
1178 for (i
= 0; i
< MAX_ADJUSTMENT_RANGE_COUNT
; i
++) {
1179 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
1180 cliPrintf("adjrange %u %u %u %u %u %u %u\r\n",
1182 ar
->adjustmentIndex
,
1183 ar
->auxChannelIndex
,
1184 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
1185 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
1186 ar
->adjustmentFunction
,
1187 ar
->auxSwitchChannelIndex
1193 if (i
< MAX_ADJUSTMENT_RANGE_COUNT
) {
1194 adjustmentRange_t
*ar
= ¤tProfile
->adjustmentRanges
[i
];
1195 uint8_t validArgumentCount
= 0;
1197 ptr
= strchr(ptr
, ' ');
1200 if (val
>= 0 && val
< MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
) {
1201 ar
->adjustmentIndex
= val
;
1202 validArgumentCount
++;
1205 ptr
= strchr(ptr
, ' ');
1208 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1209 ar
->auxChannelIndex
= val
;
1210 validArgumentCount
++;
1214 ptr
= processChannelRangeArgs(ptr
, &ar
->range
, &validArgumentCount
);
1216 ptr
= strchr(ptr
, ' ');
1219 if (val
>= 0 && val
< ADJUSTMENT_FUNCTION_COUNT
) {
1220 ar
->adjustmentFunction
= val
;
1221 validArgumentCount
++;
1224 ptr
= strchr(ptr
, ' ');
1227 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1228 ar
->auxSwitchChannelIndex
= val
;
1229 validArgumentCount
++;
1233 if (validArgumentCount
!= 6) {
1234 memset(ar
, 0, sizeof(adjustmentRange_t
));
1235 cliShowParseError();
1238 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT
- 1);
1243 static void cliMotorMix(char *cmdline
)
1245 #ifdef USE_QUAD_MIXER_ONLY
1251 char ftoaBuffer
[FTOA_BUFFER_SIZE
];
1254 if (isEmpty(cmdline
)) {
1255 cliPrint("Motor\tThr\tRoll\tPitch\tYaw\r\n");
1256 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1257 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1260 cliPrintf("#%d:\t", i
);
1261 cliPrintf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].throttle
, ftoaBuffer
));
1262 cliPrintf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].roll
, ftoaBuffer
));
1263 cliPrintf("%s\t", ftoa(masterConfig
.customMotorMixer
[i
].pitch
, ftoaBuffer
));
1264 cliPrintf("%s\r\n", ftoa(masterConfig
.customMotorMixer
[i
].yaw
, ftoaBuffer
));
1267 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1268 // erase custom mixer
1269 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
1270 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
1271 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1272 ptr
= strchr(cmdline
, ' ');
1274 len
= strlen(++ptr
);
1275 for (i
= 0; ; i
++) {
1276 if (mixerNames
[i
] == NULL
) {
1277 cliPrint("Invalid name\r\n");
1280 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1281 mixerLoadMix(i
, masterConfig
.customMotorMixer
);
1282 cliPrintf("Loaded %s\r\n", mixerNames
[i
]);
1290 i
= atoi(ptr
); // get motor number
1291 if (i
< MAX_SUPPORTED_MOTORS
) {
1292 ptr
= strchr(ptr
, ' ');
1294 masterConfig
.customMotorMixer
[i
].throttle
= fastA2F(++ptr
);
1297 ptr
= strchr(ptr
, ' ');
1299 masterConfig
.customMotorMixer
[i
].roll
= fastA2F(++ptr
);
1302 ptr
= strchr(ptr
, ' ');
1304 masterConfig
.customMotorMixer
[i
].pitch
= fastA2F(++ptr
);
1307 ptr
= strchr(ptr
, ' ');
1309 masterConfig
.customMotorMixer
[i
].yaw
= fastA2F(++ptr
);
1313 cliShowParseError();
1318 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
1324 static void cliRxRange(char *cmdline
)
1326 int i
, validArgumentCount
= 0;
1329 if (isEmpty(cmdline
)) {
1330 for (i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
1331 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1332 cliPrintf("rxrange %u %u %u\r\n", i
, channelRangeConfiguration
->min
, channelRangeConfiguration
->max
);
1334 } else if (strcasecmp(cmdline
, "reset") == 0) {
1335 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
1339 if (i
>= 0 && i
< NON_AUX_CHANNEL_COUNT
) {
1340 int rangeMin
, rangeMax
;
1342 ptr
= strchr(ptr
, ' ');
1344 rangeMin
= atoi(++ptr
);
1345 validArgumentCount
++;
1348 ptr
= strchr(ptr
, ' ');
1350 rangeMax
= atoi(++ptr
);
1351 validArgumentCount
++;
1354 if (validArgumentCount
!= 2) {
1355 cliShowParseError();
1356 } else if (rangeMin
< PWM_PULSE_MIN
|| rangeMin
> PWM_PULSE_MAX
|| rangeMax
< PWM_PULSE_MIN
|| rangeMax
> PWM_PULSE_MAX
) {
1357 cliShowParseError();
1359 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1360 channelRangeConfiguration
->min
= rangeMin
;
1361 channelRangeConfiguration
->max
= rangeMax
;
1364 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT
- 1);
1370 static void cliLed(char *cmdline
)
1374 char ledConfigBuffer
[20];
1376 if (isEmpty(cmdline
)) {
1377 for (i
= 0; i
< LED_MAX_STRIP_LENGTH
; i
++) {
1378 generateLedConfig(&masterConfig
.ledConfigs
[i
], ledConfigBuffer
, sizeof(ledConfigBuffer
));
1379 cliPrintf("led %u %s\r\n", i
, ledConfigBuffer
);
1384 if (i
< LED_MAX_STRIP_LENGTH
) {
1385 ptr
= strchr(cmdline
, ' ');
1386 if (!parseLedStripConfig(i
, ++ptr
)) {
1387 cliShowParseError();
1390 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH
- 1);
1395 static void cliColor(char *cmdline
)
1400 if (isEmpty(cmdline
)) {
1401 for (i
= 0; i
< LED_CONFIGURABLE_COLOR_COUNT
; i
++) {
1402 cliPrintf("color %u %d,%u,%u\r\n",
1404 masterConfig
.colors
[i
].h
,
1405 masterConfig
.colors
[i
].s
,
1406 masterConfig
.colors
[i
].v
1412 if (i
< LED_CONFIGURABLE_COLOR_COUNT
) {
1413 ptr
= strchr(cmdline
, ' ');
1414 if (!parseColor(i
, ++ptr
)) {
1415 cliShowParseError();
1418 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT
- 1);
1423 static void cliModeColor(char *cmdline
)
1425 if (isEmpty(cmdline
)) {
1426 for (int i
= 0; i
< LED_MODE_COUNT
; i
++) {
1427 for (int j
= 0; j
< LED_DIRECTION_COUNT
; j
++) {
1428 int colorIndex
= modeColors
[i
].color
[j
];
1429 cliPrintf("mode_color %u %u %u\r\n", i
, j
, colorIndex
);
1433 for (int j
= 0; j
< LED_SPECIAL_COLOR_COUNT
; j
++) {
1434 int colorIndex
= specialColors
.color
[j
];
1435 cliPrintf("mode_color %u %u %u\r\n", LED_SPECIAL
, j
, colorIndex
);
1438 enum {MODE
= 0, FUNCTION
, COLOR
, ARGS_COUNT
};
1439 int args
[ARGS_COUNT
];
1441 char* ptr
= strtok(cmdline
, " ");
1442 while (ptr
&& argNo
< ARGS_COUNT
) {
1443 args
[argNo
++] = atoi(ptr
);
1444 ptr
= strtok(NULL
, " ");
1447 if (ptr
!= NULL
|| argNo
!= ARGS_COUNT
) {
1448 cliShowParseError();
1452 int modeIdx
= args
[MODE
];
1453 int funIdx
= args
[FUNCTION
];
1454 int color
= args
[COLOR
];
1455 if(!setModeColor(modeIdx
, funIdx
, color
)) {
1456 cliShowParseError();
1459 // values are validated
1460 cliPrintf("mode_color %u %u %u\r\n", modeIdx
, funIdx
, color
);
1466 static void cliServo(char *cmdline
)
1468 enum { SERVO_ARGUMENT_COUNT
= 8 };
1469 int16_t arguments
[SERVO_ARGUMENT_COUNT
];
1471 servoParam_t
*servo
;
1476 if (isEmpty(cmdline
)) {
1477 // print out servo settings
1478 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1479 servo
= ¤tProfile
->servoConf
[i
];
1481 cliPrintf("servo %u %d %d %d %d %d %d %d\r\n",
1489 servo
->forwardFromChannel
1493 int validArgumentCount
= 0;
1497 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1499 // If command line doesn't fit the format, don't modify the config
1501 if (*ptr
== '-' || (*ptr
>= '0' && *ptr
<= '9')) {
1502 if (validArgumentCount
>= SERVO_ARGUMENT_COUNT
) {
1503 cliShowParseError();
1507 arguments
[validArgumentCount
++] = atoi(ptr
);
1511 } while (*ptr
>= '0' && *ptr
<= '9');
1512 } else if (*ptr
== ' ') {
1515 cliShowParseError();
1520 enum {INDEX
= 0, MIN
, MAX
, MIDDLE
, ANGLE_AT_MIN
, ANGLE_AT_MAX
, RATE
, FORWARD
};
1522 i
= arguments
[INDEX
];
1524 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1525 if (validArgumentCount
!= SERVO_ARGUMENT_COUNT
|| i
< 0 || i
>= MAX_SUPPORTED_SERVOS
) {
1526 cliShowParseError();
1530 servo
= ¤tProfile
->servoConf
[i
];
1533 arguments
[MIN
] < PWM_PULSE_MIN
|| arguments
[MIN
] > PWM_PULSE_MAX
||
1534 arguments
[MAX
] < PWM_PULSE_MIN
|| arguments
[MAX
] > PWM_PULSE_MAX
||
1535 arguments
[MIDDLE
] < arguments
[MIN
] || arguments
[MIDDLE
] > arguments
[MAX
] ||
1536 arguments
[MIN
] > arguments
[MAX
] || arguments
[MAX
] < arguments
[MIN
] ||
1537 arguments
[RATE
] < -100 || arguments
[RATE
] > 100 ||
1538 arguments
[FORWARD
] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
||
1539 arguments
[ANGLE_AT_MIN
] < 0 || arguments
[ANGLE_AT_MIN
] > 180 ||
1540 arguments
[ANGLE_AT_MAX
] < 0 || arguments
[ANGLE_AT_MAX
] > 180
1542 cliShowParseError();
1546 servo
->min
= arguments
[1];
1547 servo
->max
= arguments
[2];
1548 servo
->middle
= arguments
[3];
1549 servo
->angleAtMin
= arguments
[4];
1550 servo
->angleAtMax
= arguments
[5];
1551 servo
->rate
= arguments
[6];
1552 servo
->forwardFromChannel
= arguments
[7];
1558 static void cliServoMix(char *cmdline
)
1563 int args
[8], check
= 0;
1564 len
= strlen(cmdline
);
1568 cliPrint("Rule\tServo\tSource\tRate\tSpeed\tMin\tMax\tBox\r\n");
1570 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1571 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1574 cliPrintf("#%d:\t%d\t%d\t%d\t%d\t%d\t%d\t%d\r\n",
1576 masterConfig
.customServoMixer
[i
].targetChannel
,
1577 masterConfig
.customServoMixer
[i
].inputSource
,
1578 masterConfig
.customServoMixer
[i
].rate
,
1579 masterConfig
.customServoMixer
[i
].speed
,
1580 masterConfig
.customServoMixer
[i
].min
,
1581 masterConfig
.customServoMixer
[i
].max
,
1582 masterConfig
.customServoMixer
[i
].box
1587 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1588 // erase custom mixer
1589 memset(masterConfig
.customServoMixer
, 0, sizeof(masterConfig
.customServoMixer
));
1590 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1591 currentProfile
->servoConf
[i
].reversedSources
= 0;
1593 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1594 ptr
= strchr(cmdline
, ' ');
1596 len
= strlen(++ptr
);
1597 for (i
= 0; ; i
++) {
1598 if (mixerNames
[i
] == NULL
) {
1599 cliPrintf("Invalid name\r\n");
1602 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1603 servoMixerLoadMix(i
, masterConfig
.customServoMixer
);
1604 cliPrintf("Loaded %s\r\n", mixerNames
[i
]);
1610 } else if (strncasecmp(cmdline
, "reverse", 7) == 0) {
1611 enum {SERVO
= 0, INPUT
, REVERSE
, ARGS_COUNT
};
1612 int servoIndex
, inputSource
;
1613 ptr
= strchr(cmdline
, ' ');
1618 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1619 cliPrintf("\ti%d", inputSource
);
1622 for (servoIndex
= 0; servoIndex
< MAX_SUPPORTED_SERVOS
; servoIndex
++) {
1623 cliPrintf("%d", servoIndex
);
1624 for (inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
1625 cliPrintf("\t%s ", (currentProfile
->servoConf
[servoIndex
].reversedSources
& (1 << inputSource
)) ? "r" : "n");
1631 ptr
= strtok(ptr
, " ");
1632 while (ptr
!= NULL
&& check
< ARGS_COUNT
- 1) {
1633 args
[check
++] = atoi(ptr
);
1634 ptr
= strtok(NULL
, " ");
1637 if (ptr
== NULL
|| check
!= ARGS_COUNT
- 1) {
1638 cliShowParseError();
1642 if (args
[SERVO
] >= 0 && args
[SERVO
] < MAX_SUPPORTED_SERVOS
1643 && args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
1644 && (*ptr
== 'r' || *ptr
== 'n')) {
1646 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
|= 1 << args
[INPUT
];
1648 currentProfile
->servoConf
[args
[SERVO
]].reversedSources
&= ~(1 << args
[INPUT
]);
1650 cliShowParseError();
1652 cliServoMix("reverse");
1654 enum {RULE
= 0, TARGET
, INPUT
, RATE
, SPEED
, MIN
, MAX
, BOX
, ARGS_COUNT
};
1655 ptr
= strtok(cmdline
, " ");
1656 while (ptr
!= NULL
&& check
< ARGS_COUNT
) {
1657 args
[check
++] = atoi(ptr
);
1658 ptr
= strtok(NULL
, " ");
1661 if (ptr
!= NULL
|| check
!= ARGS_COUNT
) {
1662 cliShowParseError();
1667 if (i
>= 0 && i
< MAX_SERVO_RULES
&&
1668 args
[TARGET
] >= 0 && args
[TARGET
] < MAX_SUPPORTED_SERVOS
&&
1669 args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
&&
1670 args
[RATE
] >= -100 && args
[RATE
] <= 100 &&
1671 args
[SPEED
] >= 0 && args
[SPEED
] <= MAX_SERVO_SPEED
&&
1672 args
[MIN
] >= 0 && args
[MIN
] <= 100 &&
1673 args
[MAX
] >= 0 && args
[MAX
] <= 100 && args
[MIN
] < args
[MAX
] &&
1674 args
[BOX
] >= 0 && args
[BOX
] <= MAX_SERVO_BOXES
) {
1675 masterConfig
.customServoMixer
[i
].targetChannel
= args
[TARGET
];
1676 masterConfig
.customServoMixer
[i
].inputSource
= args
[INPUT
];
1677 masterConfig
.customServoMixer
[i
].rate
= args
[RATE
];
1678 masterConfig
.customServoMixer
[i
].speed
= args
[SPEED
];
1679 masterConfig
.customServoMixer
[i
].min
= args
[MIN
];
1680 masterConfig
.customServoMixer
[i
].max
= args
[MAX
];
1681 masterConfig
.customServoMixer
[i
].box
= args
[BOX
];
1684 cliShowParseError();
1691 static void cliWriteBytes(const uint8_t *buffer
, int count
)
1700 static void cliSdInfo(char *cmdline
)
1704 cliPrint("SD card: ");
1706 if (!sdcard_isInserted()) {
1707 cliPrint("None inserted\r\n");
1711 if (!sdcard_isInitialized()) {
1712 cliPrint("Startup failed\r\n");
1716 const sdcardMetadata_t
*metadata
= sdcard_getMetadata();
1718 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
1719 metadata
->manufacturerID
,
1720 metadata
->numBlocks
/ 2, /* One block is half a kB */
1721 metadata
->productionMonth
,
1722 metadata
->productionYear
,
1723 metadata
->productRevisionMajor
,
1724 metadata
->productRevisionMinor
1727 cliWriteBytes((uint8_t*)metadata
->productName
, sizeof(metadata
->productName
));
1729 cliPrint("'\r\n" "Filesystem: ");
1731 switch (afatfs_getFilesystemState()) {
1732 case AFATFS_FILESYSTEM_STATE_READY
:
1735 case AFATFS_FILESYSTEM_STATE_INITIALIZATION
:
1736 cliPrint("Initializing");
1738 case AFATFS_FILESYSTEM_STATE_UNKNOWN
:
1739 case AFATFS_FILESYSTEM_STATE_FATAL
:
1742 switch (afatfs_getLastError()) {
1743 case AFATFS_ERROR_BAD_MBR
:
1744 cliPrint(" - no FAT MBR partitions");
1746 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER
:
1747 cliPrint(" - bad FAT header");
1749 case AFATFS_ERROR_GENERIC
:
1750 case AFATFS_ERROR_NONE
:
1751 ; // Nothing more detailed to print
1764 static void cliFlashInfo(char *cmdline
)
1766 const flashGeometry_t
*layout
= flashfsGetGeometry();
1770 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
1771 layout
->sectors
, layout
->sectorSize
, layout
->pagesPerSector
, layout
->pageSize
, layout
->totalSize
, flashfsGetOffset());
1774 static void cliFlashErase(char *cmdline
)
1778 cliPrintf("Erasing...\r\n");
1779 flashfsEraseCompletely();
1781 while (!flashfsIsReady()) {
1785 cliPrintf("Done.\r\n");
1788 #ifdef USE_FLASH_TOOLS
1790 static void cliFlashWrite(char *cmdline
)
1792 uint32_t address
= atoi(cmdline
);
1793 char *text
= strchr(cmdline
, ' ');
1796 cliShowParseError();
1798 flashfsSeekAbs(address
);
1799 flashfsWrite((uint8_t*)text
, strlen(text
), true);
1802 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text
), address
);
1806 static void cliFlashRead(char *cmdline
)
1808 uint32_t address
= atoi(cmdline
);
1814 char *nextArg
= strchr(cmdline
, ' ');
1817 cliShowParseError();
1819 length
= atoi(nextArg
);
1821 cliPrintf("Reading %u bytes at %u:\r\n", length
, address
);
1823 while (length
> 0) {
1826 bytesRead
= flashfsReadAbs(address
, buffer
, length
< sizeof(buffer
) ? length
: sizeof(buffer
));
1828 for (i
= 0; i
< bytesRead
; i
++) {
1829 cliWrite(buffer
[i
]);
1832 length
-= bytesRead
;
1833 address
+= bytesRead
;
1835 if (bytesRead
== 0) {
1836 //Assume we reached the end of the volume or something fatal happened
1847 static void dumpValues(uint16_t valueSection
)
1850 const clivalue_t
*value
;
1851 for (i
= 0; i
< VALUE_COUNT
; i
++) {
1852 value
= &valueTable
[i
];
1854 if ((value
->type
& VALUE_SECTION_MASK
) != valueSection
) {
1858 cliPrintf("set %s = ", valueTable
[i
].name
);
1859 cliPrintVar(value
, 0);
1865 DUMP_MASTER
= (1 << 0),
1866 DUMP_PROFILE
= (1 << 1),
1867 DUMP_CONTROL_RATE_PROFILE
= (1 << 2)
1870 #define DUMP_ALL (DUMP_MASTER | DUMP_PROFILE | DUMP_CONTROL_RATE_PROFILE)
1873 static const char* const sectionBreak
= "\r\n";
1875 #define printSectionBreak() cliPrintf((char *)sectionBreak)
1877 static void cliDump(char *cmdline
)
1883 #ifndef USE_QUAD_MIXER_ONLY
1884 float thr
, roll
, pitch
, yaw
;
1887 uint8_t dumpMask
= DUMP_ALL
;
1888 if (strcasecmp(cmdline
, "master") == 0) {
1889 dumpMask
= DUMP_MASTER
; // only
1891 if (strcasecmp(cmdline
, "profile") == 0) {
1892 dumpMask
= DUMP_PROFILE
; // only
1894 if (strcasecmp(cmdline
, "rates") == 0) {
1895 dumpMask
= DUMP_CONTROL_RATE_PROFILE
; // only
1898 if (dumpMask
& DUMP_MASTER
) {
1900 cliPrint("\r\n# version\r\n");
1903 cliPrint("\r\n# pflags\r\n");
1906 cliPrint("\r\n# dump master\r\n");
1907 cliPrint("\r\n# mixer\r\n");
1909 #ifndef USE_QUAD_MIXER_ONLY
1910 cliPrintf("mixer %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
1912 cliPrintf("mmix reset\r\n");
1914 for (i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1915 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1917 thr
= masterConfig
.customMotorMixer
[i
].throttle
;
1918 roll
= masterConfig
.customMotorMixer
[i
].roll
;
1919 pitch
= masterConfig
.customMotorMixer
[i
].pitch
;
1920 yaw
= masterConfig
.customMotorMixer
[i
].yaw
;
1921 cliPrintf("mmix %d", i
);
1924 cliPrintf("%s", ftoa(thr
, buf
));
1927 cliPrintf("%s", ftoa(roll
, buf
));
1930 cliPrintf("%s", ftoa(pitch
, buf
));
1933 cliPrintf("%s\r\n", ftoa(yaw
, buf
));
1936 // print custom servo mixer if exists
1937 cliPrintf("smix reset\r\n");
1939 for (i
= 0; i
< MAX_SERVO_RULES
; i
++) {
1941 if (masterConfig
.customServoMixer
[i
].rate
== 0)
1944 cliPrintf("smix %d %d %d %d %d %d %d %d\r\n",
1946 masterConfig
.customServoMixer
[i
].targetChannel
,
1947 masterConfig
.customServoMixer
[i
].inputSource
,
1948 masterConfig
.customServoMixer
[i
].rate
,
1949 masterConfig
.customServoMixer
[i
].speed
,
1950 masterConfig
.customServoMixer
[i
].min
,
1951 masterConfig
.customServoMixer
[i
].max
,
1952 masterConfig
.customServoMixer
[i
].box
1955 #endif // USE_SERVOS
1956 #endif // USE_QUAD_MIXER_ONLY
1958 cliPrint("\r\n\r\n# feature\r\n");
1960 mask
= featureMask();
1961 for (i
= 0; ; i
++) { // disable all feature first
1962 if (featureNames
[i
] == NULL
)
1964 cliPrintf("feature -%s\r\n", featureNames
[i
]);
1966 for (i
= 0; ; i
++) { // reenable what we want.
1967 if (featureNames
[i
] == NULL
)
1969 if (mask
& (1 << i
))
1970 cliPrintf("feature %s\r\n", featureNames
[i
]);
1975 cliPrint("\r\n\r\n# beeper\r\n");
1977 uint8_t beeperCount
= beeperTableEntryCount();
1978 mask
= getBeeperOffMask();
1979 for (int i
= 0; i
< (beeperCount
-2); i
++) {
1980 if (mask
& (1 << i
))
1981 cliPrintf("beeper -%s\r\n", beeperNameForTableIndex(i
));
1983 cliPrintf("beeper %s\r\n", beeperNameForTableIndex(i
));
1988 cliPrint("\r\n\r\n# map\r\n");
1990 for (i
= 0; i
< 8; i
++)
1991 buf
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
1993 cliPrintf("map %s\r\n", buf
);
1995 cliPrint("\r\n\r\n# serial\r\n");
1999 cliPrint("\r\n\r\n# led\r\n");
2002 cliPrint("\r\n\r\n# color\r\n");
2005 cliPrint("\r\n\r\n# mode_color\r\n");
2008 printSectionBreak();
2009 dumpValues(MASTER_VALUE
);
2011 cliPrint("\r\n# rxfail\r\n");
2015 if (dumpMask
& DUMP_PROFILE
) {
2016 cliPrint("\r\n# dump profile\r\n");
2018 cliPrint("\r\n# profile\r\n");
2021 cliPrint("\r\n# aux\r\n");
2025 cliPrint("\r\n# adjrange\r\n");
2027 cliAdjustmentRange("");
2029 cliPrintf("\r\n# rxrange\r\n");
2034 cliPrint("\r\n# servo\r\n");
2038 // print servo directions
2039 unsigned int channel
;
2041 for (i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2042 for (channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
2043 if (servoDirection(i
, channel
) < 0) {
2044 cliPrintf("smix reverse %d %d r\r\n", i
, channel
);
2050 printSectionBreak();
2052 dumpValues(PROFILE_VALUE
);
2055 if (dumpMask
& DUMP_CONTROL_RATE_PROFILE
) {
2056 cliPrint("\r\n# dump rates\r\n");
2058 cliPrint("\r\n# rateprofile\r\n");
2061 printSectionBreak();
2063 dumpValues(CONTROL_RATE_VALUE
);
2067 void cliEnter(serialPort_t
*serialPort
)
2070 cliPort
= serialPort
;
2071 setPrintfSerialPort(cliPort
);
2072 cliWriter
= bufWriterInit(cliWriteBuffer
, sizeof(cliWriteBuffer
),
2073 (bufWrite_t
)serialWriteBufShim
, serialPort
);
2075 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2077 ENABLE_ARMING_FLAG(PREVENT_ARMING
);
2080 static void cliExit(char *cmdline
)
2084 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2085 bufWriterFlush(cliWriter
);
2090 // incase a motor was left running during motortest, clear it here
2091 mixerResetDisarmedMotors();
2097 static void cliFeature(char *cmdline
)
2103 len
= strlen(cmdline
);
2104 mask
= featureMask();
2107 cliPrint("Enabled: ");
2108 for (i
= 0; ; i
++) {
2109 if (featureNames
[i
] == NULL
)
2111 if (mask
& (1 << i
))
2112 cliPrintf("%s ", featureNames
[i
]);
2115 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
2116 cliPrint("Available: ");
2117 for (i
= 0; ; i
++) {
2118 if (featureNames
[i
] == NULL
)
2120 cliPrintf("%s ", featureNames
[i
]);
2125 bool remove
= false;
2126 if (cmdline
[0] == '-') {
2129 cmdline
++; // skip over -
2133 for (i
= 0; ; i
++) {
2134 if (featureNames
[i
] == NULL
) {
2135 cliPrint("Invalid name\r\n");
2139 if (strncasecmp(cmdline
, featureNames
[i
], len
) == 0) {
2143 if (mask
& FEATURE_GPS
) {
2144 cliPrint("unavailable\r\n");
2149 if (mask
& FEATURE_SONAR
) {
2150 cliPrint("unavailable\r\n");
2156 cliPrint("Disabled");
2159 cliPrint("Enabled");
2161 cliPrintf(" %s\r\n", featureNames
[i
]);
2169 static void cliBeeper(char *cmdline
)
2172 uint32_t len
= strlen(cmdline
);;
2173 uint8_t beeperCount
= beeperTableEntryCount();
2174 uint32_t mask
= getBeeperOffMask();
2177 cliPrintf("Disabled:");
2178 for (int i
= 0; ; i
++) {
2179 if (i
== beeperCount
-2){
2184 if (mask
& (1 << i
))
2185 cliPrintf(" %s", beeperNameForTableIndex(i
));
2188 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
2189 cliPrint("Available:");
2190 for (i
= 0; i
< beeperCount
; i
++)
2191 cliPrintf(" %s", beeperNameForTableIndex(i
));
2195 bool remove
= false;
2196 if (cmdline
[0] == '-') {
2197 remove
= true; // this is for beeper OFF condition
2202 for (i
= 0; ; i
++) {
2203 if (i
== beeperCount
) {
2204 cliPrint("Invalid name\r\n");
2207 if (strncasecmp(cmdline
, beeperNameForTableIndex(i
), len
) == 0) {
2208 if (remove
) { // beeper off
2209 if (i
== BEEPER_ALL
-1)
2210 beeperOffSetAll(beeperCount
-2);
2212 if (i
== BEEPER_PREFERENCE
-1)
2213 setBeeperOffMask(getPreferredBeeperOffMask());
2218 cliPrint("Disabled");
2221 if (i
== BEEPER_ALL
-1)
2222 beeperOffClearAll();
2224 if (i
== BEEPER_PREFERENCE
-1)
2225 setPreferredBeeperOffMask(getBeeperOffMask());
2228 beeperOffClear(mask
);
2230 cliPrint("Enabled");
2232 cliPrintf(" %s\r\n", beeperNameForTableIndex(i
));
2242 static void cliGpsPassthrough(char *cmdline
)
2246 gpsEnablePassthrough(cliPort
);
2250 static void cliHelp(char *cmdline
)
2256 for (i
= 0; i
< CMD_COUNT
; i
++) {
2257 cliPrint(cmdTable
[i
].name
);
2258 #ifndef SKIP_CLI_COMMAND_HELP
2259 if (cmdTable
[i
].description
) {
2260 cliPrintf(" - %s", cmdTable
[i
].description
);
2262 if (cmdTable
[i
].args
) {
2263 cliPrintf("\r\n\t%s", cmdTable
[i
].args
);
2270 static void cliMap(char *cmdline
)
2276 len
= strlen(cmdline
);
2280 for (i
= 0; i
< 8; i
++)
2281 cmdline
[i
] = toupper((unsigned char)cmdline
[i
]);
2282 for (i
= 0; i
< 8; i
++) {
2283 if (strchr(rcChannelLetters
, cmdline
[i
]) && !strchr(cmdline
+ i
+ 1, cmdline
[i
]))
2285 cliShowParseError();
2288 parseRcChannels(cmdline
, &masterConfig
.rxConfig
);
2291 for (i
= 0; i
< 8; i
++)
2292 out
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
2294 cliPrintf("%s\r\n", out
);
2297 #ifndef USE_QUAD_MIXER_ONLY
2298 static void cliMixer(char *cmdline
)
2303 len
= strlen(cmdline
);
2306 cliPrintf("Mixer: %s\r\n", mixerNames
[masterConfig
.mixerMode
- 1]);
2308 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
2309 cliPrint("Available mixers: ");
2310 for (i
= 0; ; i
++) {
2311 if (mixerNames
[i
] == NULL
)
2313 cliPrintf("%s ", mixerNames
[i
]);
2319 for (i
= 0; ; i
++) {
2320 if (mixerNames
[i
] == NULL
) {
2321 cliPrint("Invalid name\r\n");
2324 if (strncasecmp(cmdline
, mixerNames
[i
], len
) == 0) {
2325 masterConfig
.mixerMode
= i
+ 1;
2334 static void cliMotor(char *cmdline
)
2336 int motor_index
= 0;
2337 int motor_value
= 0;
2342 if (isEmpty(cmdline
)) {
2343 cliShowParseError();
2347 pch
= strtok_r(cmdline
, " ", &saveptr
);
2348 while (pch
!= NULL
) {
2351 motor_index
= atoi(pch
);
2354 motor_value
= atoi(pch
);
2358 pch
= strtok_r(NULL
, " ", &saveptr
);
2361 if (motor_index
< 0 || motor_index
>= MAX_SUPPORTED_MOTORS
) {
2362 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
2367 if (motor_value
< PWM_RANGE_MIN
|| motor_value
> PWM_RANGE_MAX
) {
2368 cliShowArgumentRangeError("value", 1000, 2000);
2371 motor_disarmed
[motor_index
] = motor_value
;
2375 cliPrintf("motor %d: %d\r\n", motor_index
, motor_disarmed
[motor_index
]);
2378 static void cliPlaySound(char *cmdline
)
2380 #if FLASH_SIZE <= 64
2385 static int lastSoundIdx
= -1;
2387 if (isEmpty(cmdline
)) {
2388 i
= lastSoundIdx
+ 1; //next sound index
2389 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
2390 while (true) { //no name for index; try next one
2391 if (++i
>= beeperTableEntryCount())
2392 i
= 0; //if end then wrap around to first entry
2393 if ((name
=beeperNameForTableIndex(i
)) != NULL
)
2394 break; //if name OK then play sound below
2395 if (i
== lastSoundIdx
+ 1) { //prevent infinite loop
2396 cliPrintf("Error playing sound\r\n");
2401 } else { //index value was given
2403 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
2404 cliPrintf("No sound for index %d\r\n", i
);
2410 cliPrintf("Playing sound %d: %s\r\n", i
, name
);
2411 beeper(beeperModeForTableIndex(i
));
2415 static void cliProfile(char *cmdline
)
2419 if (isEmpty(cmdline
)) {
2420 cliPrintf("profile %d\r\n", getCurrentProfile());
2424 if (i
>= 0 && i
< MAX_PROFILE_COUNT
) {
2425 masterConfig
.current_profile_index
= i
;
2433 static void cliRateProfile(char *cmdline
)
2437 if (isEmpty(cmdline
)) {
2438 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
2442 if (i
>= 0 && i
< MAX_CONTROL_RATE_PROFILE_COUNT
) {
2443 changeControlRateProfile(i
);
2449 static void cliReboot(void) {
2450 cliPrint("\r\nRebooting");
2451 bufWriterFlush(cliWriter
);
2452 waitForSerialPortToFinishTransmitting(cliPort
);
2454 handleOneshotFeatureChangeOnRestart();
2458 static void cliSave(char *cmdline
)
2463 //copyCurrentProfileToProfileSlot(masterConfig.current_profile_index);
2468 static void cliDefaults(char *cmdline
)
2472 cliPrint("Resetting to defaults");
2477 static void cliPrint(const char *str
)
2480 bufWriterAppend(cliWriter
, *str
++);
2483 static void cliPutp(void *p
, char ch
)
2485 bufWriterAppend(p
, ch
);
2488 static void cliPrintf(const char *fmt
, ...)
2492 tfp_format(cliWriter
, cliPutp
, fmt
, va
);
2496 static void cliWrite(uint8_t ch
)
2498 bufWriterAppend(cliWriter
, ch
);
2501 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
)
2504 char ftoaBuffer
[FTOA_BUFFER_SIZE
];
2506 void *ptr
= var
->ptr
;
2507 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
2508 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
2510 if ((var
->type
& VALUE_SECTION_MASK
) == CONTROL_RATE_VALUE
) {
2511 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
2514 switch (var
->type
& VALUE_TYPE_MASK
) {
2516 value
= *(uint8_t *)ptr
;
2520 value
= *(int8_t *)ptr
;
2524 value
= *(uint16_t *)ptr
;
2528 value
= *(int16_t *)ptr
;
2532 value
= *(uint32_t *)ptr
;
2536 if (full
&& (var
->type
& VALUE_MODE_MASK
) == MODE_DIRECT
) {
2537 cliPrintf("%s", ftoa((float)var
->config
.minmax
.min
, ftoaBuffer
));
2538 cliPrintf(" - %s", ftoa((float)var
->config
.minmax
.max
, ftoaBuffer
));
2540 cliPrintf("%s", ftoa(*(float *)ptr
, ftoaBuffer
));
2542 return; // return from case for float only
2545 switch(var
->type
& VALUE_MODE_MASK
) {
2548 cliPrintf("%d - %d", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
2550 cliPrintf("%d", value
);
2555 for (int i
=0; i
<lookupTables
[var
->config
.lookup
.tableIndex
].valueCount
; i
++) {
2556 cliPrintf("%s ", lookupTables
[var
->config
.lookup
.tableIndex
].values
[i
]);
2559 cliPrintf(lookupTables
[var
->config
.lookup
.tableIndex
].values
[value
]);
2565 static void cliPrintVarRange(const clivalue_t
*var
)
2567 switch (var
->type
& VALUE_MODE_MASK
) {
2568 case (MODE_DIRECT
): {
2569 cliPrintf("Allowed range: %d - %d\r\n", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
2572 case (MODE_LOOKUP
): {
2573 const lookupTableEntry_t
*tableEntry
= &lookupTables
[var
->config
.lookup
.tableIndex
];
2574 cliPrint("Allowed values:");
2576 for (i
= 0; i
< tableEntry
->valueCount
; i
++) {
2579 cliPrintf(" %s", tableEntry
->values
[i
]);
2587 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
)
2589 void *ptr
= var
->ptr
;
2590 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
2591 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
2593 if ((var
->type
& VALUE_SECTION_MASK
) == CONTROL_RATE_VALUE
) {
2594 ptr
= ((uint8_t *)ptr
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
2597 switch (var
->type
& VALUE_TYPE_MASK
) {
2600 *(int8_t *)ptr
= value
.int_value
;
2605 *(int16_t *)ptr
= value
.int_value
;
2609 *(uint32_t *)ptr
= value
.int_value
;
2613 *(float *)ptr
= (float)value
.float_value
;
2617 if (var
->pflags_to_set
) {
2618 persistentFlagSet(var
->pflags_to_set
);
2622 static void cliSet(char *cmdline
)
2626 const clivalue_t
*val
;
2629 len
= strlen(cmdline
);
2631 if (len
== 0 || (len
== 1 && cmdline
[0] == '*')) {
2632 cliPrint("Current settings: \r\n");
2633 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2634 val
= &valueTable
[i
];
2635 cliPrintf("%s = ", valueTable
[i
].name
);
2636 cliPrintVar(val
, len
); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
2639 } else if ((eqptr
= strstr(cmdline
, "=")) != NULL
) {
2642 char *lastNonSpaceCharacter
= eqptr
;
2643 while (*(lastNonSpaceCharacter
- 1) == ' ') {
2644 lastNonSpaceCharacter
--;
2646 uint8_t variableNameLength
= lastNonSpaceCharacter
- cmdline
;
2648 // skip the '=' and any ' ' characters
2650 while (*(eqptr
) == ' ') {
2654 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2655 val
= &valueTable
[i
];
2656 // ensure exact match when setting to prevent setting variables with shorter names
2657 if (strncasecmp(cmdline
, valueTable
[i
].name
, strlen(valueTable
[i
].name
)) == 0 && variableNameLength
== strlen(valueTable
[i
].name
)) {
2659 bool changeValue
= false;
2660 int_float_value_t tmp
= {0};
2661 switch (valueTable
[i
].type
& VALUE_MODE_MASK
) {
2663 if(*eqptr
!= 0 && strspn(eqptr
, "0123456789.+-") == strlen(eqptr
)) {
2667 value
= atoi(eqptr
);
2668 valuef
= fastA2F(eqptr
);
2670 if ((valuef
>= valueTable
[i
].config
.minmax
.min
&& valuef
<= valueTable
[i
].config
.minmax
.max
) // note: compare float value
2671 || (valueTable
[i
].config
.minmax
.min
== 0 && valueTable
[i
].config
.minmax
.max
== 0)) { // setting both min and max to zero allows full range
2673 if ((valueTable
[i
].type
& VALUE_TYPE_MASK
) == VAR_FLOAT
)
2674 tmp
.float_value
= valuef
;
2676 tmp
.int_value
= value
;
2684 const lookupTableEntry_t
*tableEntry
= &lookupTables
[valueTable
[i
].config
.lookup
.tableIndex
];
2685 bool matched
= false;
2686 for (uint8_t tableValueIndex
= 0; tableValueIndex
< tableEntry
->valueCount
&& !matched
; tableValueIndex
++) {
2687 matched
= strcasecmp(tableEntry
->values
[tableValueIndex
], eqptr
) == 0;
2690 tmp
.int_value
= tableValueIndex
;
2699 cliSetVar(val
, tmp
);
2701 cliPrintf("%s set to ", valueTable
[i
].name
);
2702 cliPrintVar(val
, 0);
2704 cliPrint("Invalid value.");
2705 cliPrintVarRange(val
);
2712 cliPrint("Invalid name\r\n");
2714 // no equals, check for matching variables.
2719 static void cliGet(char *cmdline
)
2722 const clivalue_t
*val
;
2723 int matchedCommands
= 0;
2725 for (i
= 0; i
< VALUE_COUNT
; i
++) {
2726 if (strstr(valueTable
[i
].name
, cmdline
)) {
2727 val
= &valueTable
[i
];
2728 cliPrintf("%s = ", valueTable
[i
].name
);
2729 cliPrintVar(val
, 0);
2731 cliPrintVarRange(val
);
2739 if (matchedCommands
) {
2743 cliPrint("Invalid name\r\n");
2746 static void cliStatus(char *cmdline
)
2750 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), System load: %d.%02d\r\n",
2751 millis() / 1000, vbat
, batteryCellCount
, getBatteryStateString(), averageSystemLoadPercent
/ 100, averageSystemLoadPercent
% 100);
2753 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock
/ 1000000));
2755 #if (FLASH_SIZE > 64)
2756 const uint32_t detectedSensorsMask
= sensorsMask();
2758 for (int i
= 0; i
< SENSOR_INDEX_COUNT
; i
++) {
2760 const uint32_t mask
= (1 << i
);
2761 if ((detectedSensorsMask
& mask
) && (mask
& SENSOR_NAMES_MASK
)) {
2762 const int sensorHardwareIndex
= detectedSensors
[i
];
2763 const char *sensorHardware
= sensorHardwareNames
[i
][sensorHardwareIndex
];
2765 cliPrintf(", %s=%s", sensorTypeNames
[i
], sensorHardware
);
2767 if (mask
== SENSOR_ACC
&& acc
.revisionCode
) {
2768 cliPrintf(".%c", acc
.revisionCode
);
2776 const uint16_t i2cErrorCounter
= i2cGetErrorCounter();
2778 const uint16_t i2cErrorCounter
= 0;
2781 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime
, i2cErrorCounter
, sizeof(master_t
));
2784 #ifndef SKIP_TASK_STATISTICS
2785 static void cliTasks(char *cmdline
)
2789 int averageLoadSum
= 0;
2791 cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
2792 for (cfTaskId_e taskId
= 0; taskId
< TASK_COUNT
; taskId
++) {
2793 cfTaskInfo_t taskInfo
;
2794 getTaskInfo(taskId
, &taskInfo
);
2795 if (taskInfo
.isEnabled
) {
2796 const int taskFrequency
= (int)(1000000.0f
/ ((float)taskInfo
.latestDeltaTime
));
2797 const int maxLoad
= (taskInfo
.maxExecutionTime
* taskFrequency
+ 5000) / 1000;
2798 const int averageLoad
= (taskInfo
.averageExecutionTime
* taskFrequency
+ 5000) / 1000;
2799 if (taskId
!= TASK_SERIAL
) {
2800 maxLoadSum
+= maxLoad
;
2801 averageLoadSum
+= averageLoad
;
2803 cliPrintf("%2d - %12s %6d %5d %5d %4d.%1d%% %4d.%1d%% %8d\r\n",
2804 taskId
, taskInfo
.taskName
, taskFrequency
, taskInfo
.maxExecutionTime
, taskInfo
.averageExecutionTime
,
2805 maxLoad
/10, maxLoad
%10, averageLoad
/10, averageLoad
%10, taskInfo
.totalExecutionTime
/ 1000);
2808 cliPrintf("Total (excluding SERIAL) %21d.%1d%% %4d.%1d%%\r\n", maxLoadSum
/10, maxLoadSum
%10, averageLoadSum
/10, averageLoadSum
%10);
2812 static void cliVersion(char *cmdline
)
2816 cliPrintf("# %s/%s %s %s / %s (%s)",
2826 static void cliPFlags(char *cmdline
)
2830 cliPrintf("# Persistent config flags: 0x%08x", masterConfig
.persistentFlags
);
2833 void cliProcess(void)
2839 // Be a little bit tricky. Flush the last inputs buffer, if any.
2840 bufWriterFlush(cliWriter
);
2842 while (serialRxBytesWaiting(cliPort
)) {
2843 uint8_t c
= serialRead(cliPort
);
2844 if (c
== '\t' || c
== '?') {
2845 // do tab completion
2846 const clicmd_t
*cmd
, *pstart
= NULL
, *pend
= NULL
;
2847 uint32_t i
= bufferIndex
;
2848 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2849 if (bufferIndex
&& (strncasecmp(cliBuffer
, cmd
->name
, bufferIndex
) != 0))
2855 if (pstart
) { /* Buffer matches one or more commands */
2856 for (; ; bufferIndex
++) {
2857 if (pstart
->name
[bufferIndex
] != pend
->name
[bufferIndex
])
2859 if (!pstart
->name
[bufferIndex
] && bufferIndex
< sizeof(cliBuffer
) - 2) {
2860 /* Unambiguous -- append a space */
2861 cliBuffer
[bufferIndex
++] = ' ';
2862 cliBuffer
[bufferIndex
] = '\0';
2865 cliBuffer
[bufferIndex
] = pstart
->name
[bufferIndex
];
2868 if (!bufferIndex
|| pstart
!= pend
) {
2869 /* Print list of ambiguous matches */
2870 cliPrint("\r\033[K");
2871 for (cmd
= pstart
; cmd
<= pend
; cmd
++) {
2872 cliPrint(cmd
->name
);
2876 i
= 0; /* Redraw prompt */
2878 for (; i
< bufferIndex
; i
++)
2879 cliWrite(cliBuffer
[i
]);
2880 } else if (!bufferIndex
&& c
== 4) { // CTRL-D
2883 } else if (c
== 12) { // NewPage / CTRL-L
2885 cliPrint("\033[2J\033[1;1H");
2887 } else if (bufferIndex
&& (c
== '\n' || c
== '\r')) {
2891 // Strip comment starting with # from line
2892 char *p
= cliBuffer
;
2895 bufferIndex
= (uint32_t)(p
- cliBuffer
);
2898 // Strip trailing whitespace
2899 while (bufferIndex
> 0 && cliBuffer
[bufferIndex
- 1] == ' ') {
2903 // Process non-empty lines
2904 if (bufferIndex
> 0) {
2905 cliBuffer
[bufferIndex
] = 0; // null terminate
2907 const clicmd_t
*cmd
;
2908 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
2909 if(!strncasecmp(cliBuffer
, cmd
->name
, strlen(cmd
->name
)) // command names match
2910 && !isalnum((unsigned)cliBuffer
[strlen(cmd
->name
)])) // next characted in bufffer is not alphanumeric (command is correctly terminated)
2913 if(cmd
< cmdTable
+ CMD_COUNT
)
2914 cmd
->func(cliBuffer
+ strlen(cmd
->name
) + 1);
2916 cliPrint("Unknown command, try 'help'");
2920 memset(cliBuffer
, 0, sizeof(cliBuffer
));
2922 // 'exit' will reset this flag, so we don't need to print prompt again
2927 } else if (c
== 127) {
2930 cliBuffer
[--bufferIndex
] = 0;
2931 cliPrint("\010 \010");
2933 } else if (bufferIndex
< sizeof(cliBuffer
) && c
>= 32 && c
<= 126) {
2934 if (!bufferIndex
&& c
== ' ')
2935 continue; // Ignore leading spaces
2936 cliBuffer
[bufferIndex
++] = c
;
2942 #ifndef SKIP_TASK_STATISTICS
2943 static void cliResource(char *cmdline
)
2946 cliPrintf("IO:\r\n----------------------\r\n");
2947 for (unsigned i
= 0; i
< DEFIO_IO_USED_COUNT
; i
++) {
2949 owner
= ownerNames
[ioRecs
[i
].owner
];
2951 const char* resource
;
2952 resource
= resourceNames
[ioRecs
[i
].resource
];
2954 if (ioRecs
[i
].index
> 0) {
2955 cliPrintf("%c%02d: %s%d %s\r\n", IO_GPIOPortIdx(ioRecs
+ i
) + 'A', IO_GPIOPinIdx(ioRecs
+ i
), owner
, ioRecs
[i
].index
, resource
);
2957 cliPrintf("%c%02d: %s %s\r\n", IO_GPIOPortIdx(ioRecs
+ i
) + 'A', IO_GPIOPinIdx(ioRecs
+ i
), owner
, resource
);
2963 void cliInit(serialConfig_t
*serialConfig
)
2965 UNUSED(serialConfig
);