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 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
29 // signal that we're in cli mode
34 #include "build/build_config.h"
35 #include "build/debug.h"
36 #include "build/version.h"
40 #include "common/axis.h"
41 #include "common/color.h"
42 #include "common/maths.h"
43 #include "common/printf.h"
44 #include "common/typeconversion.h"
46 #include "drivers/system.h"
47 #include "drivers/sensor.h"
48 #include "drivers/accgyro.h"
49 #include "drivers/compass.h"
50 #include "drivers/serial.h"
51 #include "drivers/bus_i2c.h"
52 #include "drivers/flash.h"
53 #include "drivers/io.h"
54 #include "drivers/io_impl.h"
55 #include "drivers/dma.h"
56 #include "drivers/timer.h"
57 #include "drivers/pwm_rx.h"
58 #include "drivers/sdcard.h"
59 #include "drivers/buf_writer.h"
60 #include "drivers/serial_escserial.h"
61 #include "drivers/vcd.h"
63 #include "fc/config.h"
64 #include "fc/rc_controls.h"
65 #include "fc/runtime_config.h"
67 #include "io/motors.h"
68 #include "io/servos.h"
70 #include "io/gimbal.h"
71 #include "io/serial.h"
72 #include "io/serial_cli.h"
73 #include "io/ledstrip.h"
74 #include "io/flashfs.h"
75 #include "io/beeper.h"
76 #include "io/asyncfatfs/asyncfatfs.h"
81 #include "rx/spektrum.h"
83 #include "scheduler/scheduler.h"
85 #include "sensors/battery.h"
86 #include "sensors/boardalignment.h"
87 #include "sensors/sensors.h"
88 #include "sensors/acceleration.h"
89 #include "sensors/gyro.h"
90 #include "sensors/compass.h"
91 #include "sensors/barometer.h"
93 #include "flight/pid.h"
94 #include "flight/imu.h"
95 #include "flight/mixer.h"
96 #include "flight/navigation.h"
97 #include "flight/failsafe.h"
99 #include "telemetry/telemetry.h"
100 #include "telemetry/frsky.h"
102 #include "config/config_eeprom.h"
103 #include "config/config_profile.h"
104 #include "config/config_master.h"
105 #include "config/feature.h"
107 extern uint16_t cycleTime
; // FIXME dependency on mw.c
109 void gpsEnablePassthrough(serialPort_t
*gpsPassthroughPort
);
111 static serialPort_t
*cliPort
;
112 static bufWriter_t
*cliWriter
;
113 static uint8_t cliWriteBuffer
[sizeof(*cliWriter
) + 16];
115 static void cliAux(char *cmdline
);
116 static void cliRxFail(char *cmdline
);
117 static void cliAdjustmentRange(char *cmdline
);
118 static void cliMotorMix(char *cmdline
);
119 static void cliDefaults(char *cmdline
);
120 void cliDfu(char *cmdLine
);
121 static void cliDump(char *cmdLine
);
122 static void cliDiff(char *cmdLine
);
123 static void printConfig(char *cmdLine
, bool doDiff
);
124 static void cliDumpProfile(uint8_t profileIndex
, uint8_t dumpMask
, master_t
*defaultProfile
);
125 static void cliDumpRateProfile(uint8_t rateProfileIndex
, uint8_t dumpMask
, master_t
*defaultProfile
) ;
126 static void cliExit(char *cmdline
);
127 static void cliFeature(char *cmdline
);
128 static void cliMotor(char *cmdline
);
129 static void cliName(char *cmdline
);
130 #if (FLASH_SIZE > 128)
131 static void cliPlaySound(char *cmdline
);
133 static void cliProfile(char *cmdline
);
134 static void cliRateProfile(char *cmdline
);
135 static void cliReboot(void);
136 static void cliRebootEx(bool bootLoader
);
137 static void cliSave(char *cmdline
);
138 static void cliSerial(char *cmdline
);
139 #ifndef SKIP_SERIAL_PASSTHROUGH
140 static void cliSerialPassthrough(char *cmdline
);
144 static void cliServo(char *cmdline
);
145 static void cliServoMix(char *cmdline
);
148 static void cliSet(char *cmdline
);
149 static void cliGet(char *cmdline
);
150 static void cliStatus(char *cmdline
);
151 #ifndef SKIP_TASK_STATISTICS
152 static void cliTasks(char *cmdline
);
154 static void cliVersion(char *cmdline
);
155 static void cliRxRange(char *cmdline
);
156 #if (FLASH_SIZE > 64)
157 static void printResource(uint8_t dumpMask
, master_t
*defaultConfig
);
158 static void cliResource(char *cmdline
);
161 static void cliGpsPassthrough(char *cmdline
);
164 static void cliEscPassthrough(char *cmdline
);
167 static void cliHelp(char *cmdline
);
168 static void cliMap(char *cmdline
);
171 static void cliLed(char *cmdline
);
172 static void cliColor(char *cmdline
);
173 static void cliModeColor(char *cmdline
);
176 #ifndef USE_QUAD_MIXER_ONLY
177 static void cliMixer(char *cmdline
);
181 static void cliFlashInfo(char *cmdline
);
182 static void cliFlashErase(char *cmdline
);
183 #ifdef USE_FLASH_TOOLS
184 static void cliFlashWrite(char *cmdline
);
185 static void cliFlashRead(char *cmdline
);
190 static void cliVtx(char *cmdline
);
194 static void cliSdInfo(char *cmdline
);
198 static void cliBeeper(char *cmdline
);
202 static char cliBuffer
[48];
203 static uint32_t bufferIndex
= 0;
206 DUMP_MASTER
= (1 << 0),
207 DUMP_PROFILE
= (1 << 1),
208 DUMP_RATES
= (1 << 2),
211 SHOW_DEFAULTS
= (1 << 5),
212 HIDE_UNUSED
= (1 << 6),
215 static const char* const emptyName
= "-";
217 #ifndef USE_QUAD_MIXER_ONLY
218 // sync this with mixerMode_e
219 static const char * const mixerNames
[] = {
220 "TRI", "QUADP", "QUADX", "BI",
221 "GIMBAL", "Y6", "HEX6",
222 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
223 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
224 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
225 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
229 // sync this with features_e
230 static const char * const featureNames
[] = {
231 "RX_PPM", "VBAT", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
232 "SERVO_TILT", "SOFTSERIAL", "GPS", "FAILSAFE",
233 "SONAR", "TELEMETRY", "CURRENT_METER", "3D", "RX_PARALLEL_PWM",
234 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
235 "BLACKBOX", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
236 "SDCARD", "VTX", "RX_SPI", "SOFTSPI", "ESC_TELEMETRY", NULL
239 // sync this with rxFailsafeChannelMode_e
240 static const char rxFailsafeModeCharacters
[] = "ahs";
242 static const rxFailsafeChannelMode_e rxFailsafeModesTable
[RX_FAILSAFE_TYPE_COUNT
][RX_FAILSAFE_MODE_COUNT
] = {
243 { RX_FAILSAFE_MODE_AUTO
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_INVALID
},
244 { RX_FAILSAFE_MODE_INVALID
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
}
247 #if (FLASH_SIZE > 64)
248 // sync this with sensors_e
249 static const char * const sensorTypeNames
[] = {
250 "GYRO", "ACC", "BARO", "MAG", "SONAR", "GPS", "GPS+MAG", NULL
253 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG)
255 static const char * const sensorHardwareNames
[4][12] = {
256 { "", "None", "MPU6050", "L3G4200D", "MPU3050", "L3GD20", "MPU6000", "MPU6500", "MPU9250", "ICM20689", "FAKE", NULL
},
257 { "", "None", "ADXL345", "MPU6050", "MMA845x", "BMA280", "LSM303DLHC", "MPU6000", "MPU6500", "ICM20689", "FAKE", NULL
},
258 { "", "None", "BMP085", "MS5611", "BMP280", NULL
},
259 { "", "None", "HMC5883", "AK8975", "AK8963", NULL
}
265 #ifndef SKIP_CLI_COMMAND_HELP
266 const char *description
;
269 void (*func
)(char *cmdline
);
272 #ifndef SKIP_CLI_COMMAND_HELP
273 #define CLI_COMMAND_DEF(name, description, args, method) \
281 #define CLI_COMMAND_DEF(name, description, args, method) \
288 // should be sorted a..z for bsearch()
289 const clicmd_t cmdTable
[] = {
290 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", NULL
, cliAdjustmentRange
),
291 CLI_COMMAND_DEF("aux", "configure modes", NULL
, cliAux
),
293 CLI_COMMAND_DEF("color", "configure colors", NULL
, cliColor
),
294 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL
, cliModeColor
),
296 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", NULL
, cliDefaults
),
297 CLI_COMMAND_DEF("dfu", "DFU mode on reboot", NULL
, cliDfu
),
298 CLI_COMMAND_DEF("diff", "list configuration changes from default",
299 "[master|profile|rates|all] {showdefaults}", cliDiff
),
300 CLI_COMMAND_DEF("dump", "dump configuration",
301 "[master|profile|rates|all] {showdefaults}", cliDump
),
302 CLI_COMMAND_DEF("exit", NULL
, NULL
, cliExit
),
303 CLI_COMMAND_DEF("feature", "configure features",
305 "\t<+|->[name]", cliFeature
),
307 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL
, cliFlashErase
),
308 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL
, cliFlashInfo
),
309 #ifdef USE_FLASH_TOOLS
310 CLI_COMMAND_DEF("flash_read", NULL
, "<length> <address>", cliFlashRead
),
311 CLI_COMMAND_DEF("flash_write", NULL
, "<address> <message>", cliFlashWrite
),
314 CLI_COMMAND_DEF("get", "get variable value",
317 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL
, cliGpsPassthrough
),
320 CLI_COMMAND_DEF("escprog", "passthrough esc to serial", "<mode [sk/bl/ki]> <index>", cliEscPassthrough
),
322 CLI_COMMAND_DEF("help", NULL
, NULL
, cliHelp
),
324 CLI_COMMAND_DEF("led", "configure leds", NULL
, cliLed
),
326 CLI_COMMAND_DEF("map", "configure rc channel order",
328 #ifndef USE_QUAD_MIXER_ONLY
329 CLI_COMMAND_DEF("mixer", "configure mixer",
331 "\t<name>", cliMixer
),
333 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL
, cliMotorMix
),
334 CLI_COMMAND_DEF("motor", "get/set motor",
335 "<index> [<value>]", cliMotor
),
336 #if (FLASH_SIZE > 128)
337 CLI_COMMAND_DEF("play_sound", NULL
,
338 "[<index>]\r\n", cliPlaySound
),
340 CLI_COMMAND_DEF("profile", "change profile",
341 "[<index>]", cliProfile
),
342 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile
),
343 #if (FLASH_SIZE > 64)
344 CLI_COMMAND_DEF("resource", "view currently used resources", NULL
, cliResource
),
346 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL
, cliRxRange
),
347 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL
, cliRxFail
),
348 CLI_COMMAND_DEF("save", "save and reboot", NULL
, cliSave
),
349 CLI_COMMAND_DEF("serial", "configure serial ports", NULL
, cliSerial
),
350 #ifndef SKIP_SERIAL_PASSTHROUGH
351 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port",
352 "<id> [baud] [mode] : passthrough to serial",
353 cliSerialPassthrough
),
356 CLI_COMMAND_DEF("servo", "configure servos", NULL
, cliServo
),
358 CLI_COMMAND_DEF("set", "change setting",
359 "[<name>=<value>]", cliSet
),
361 CLI_COMMAND_DEF("smix", "servo mixer",
362 "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
365 "\treverse <servo> <source> r|n", cliServoMix
),
368 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL
, cliSdInfo
),
370 CLI_COMMAND_DEF("status", "show status", NULL
, cliStatus
),
371 #ifndef SKIP_TASK_STATISTICS
372 CLI_COMMAND_DEF("tasks", "show task stats", NULL
, cliTasks
),
374 CLI_COMMAND_DEF("version", "show version", NULL
, cliVersion
),
376 CLI_COMMAND_DEF("beeper", "turn on/off beeper", "list\r\n"
377 "\t<+|->[name]", cliBeeper
),
380 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL
, cliVtx
),
382 CLI_COMMAND_DEF("name", "Name of craft", NULL
, cliName
),
384 #define CMD_COUNT (sizeof(cmdTable) / sizeof(clicmd_t))
386 static const char * const lookupTableOffOn
[] = {
390 static const char * const lookupTableUnit
[] = {
394 static const char * const lookupTableAlignment
[] = {
407 static const char * const lookupTableGPSProvider
[] = {
411 static const char * const lookupTableGPSSBASMode
[] = {
412 "AUTO", "EGNOS", "WAAS", "MSAS", "GAGAN"
416 static const char * const lookupTableCurrentSensor
[] = {
417 "NONE", "ADC", "VIRTUAL"
421 static const char * const lookupTableGimbalMode
[] = {
427 static const char * const lookupTableBlackboxDevice
[] = {
428 "SERIAL", "SPIFLASH", "SDCARD"
433 static const char * const lookupTableSerialRX
[] = {
448 // sync with rx_spi_protocol_e
449 static const char * const lookupTableRxSpi
[] = {
461 static const char * const lookupTableGyroLpf
[] = {
472 static const char * const lookupTableAccHardware
[] = {
488 static const char * const lookupTableBaroHardware
[] = {
498 static const char * const lookupTableMagHardware
[] = {
507 static const char * const lookupTableDebug
[DEBUG_COUNT
] = {
526 static const char * const lookupTableOsdType
[] = {
533 static const char * const lookupTableSuperExpoYaw
[] = {
534 "OFF", "ON", "ALWAYS"
537 static const char * const lookupTablePwmProtocol
[] = {
538 "OFF", "ONESHOT125", "ONESHOT42", "MULTISHOT", "BRUSHED",
540 "DSHOT600", "DSHOT300", "DSHOT150"
544 static const char * const lookupTableRcInterpolation
[] = {
545 "OFF", "PRESET", "AUTO", "MANUAL"
548 static const char * const lookupTableLowpassType
[] = {
549 "PT1", "BIQUAD", "FIR"
552 static const char * const lookupTableFailsafe
[] = {
556 typedef struct lookupTableEntry_s
{
557 const char * const *values
;
558 const uint8_t valueCount
;
559 } lookupTableEntry_t
;
570 TABLE_BLACKBOX_DEVICE
,
572 TABLE_CURRENT_SENSOR
,
592 TABLE_MOTOR_PWM_PROTOCOL
,
593 TABLE_RC_INTERPOLATION
,
599 } lookupTableIndex_e
;
601 static const lookupTableEntry_t lookupTables
[] = {
602 { lookupTableOffOn
, sizeof(lookupTableOffOn
) / sizeof(char *) },
603 { lookupTableUnit
, sizeof(lookupTableUnit
) / sizeof(char *) },
604 { lookupTableAlignment
, sizeof(lookupTableAlignment
) / sizeof(char *) },
606 { lookupTableGPSProvider
, sizeof(lookupTableGPSProvider
) / sizeof(char *) },
607 { lookupTableGPSSBASMode
, sizeof(lookupTableGPSSBASMode
) / sizeof(char *) },
610 { lookupTableBlackboxDevice
, sizeof(lookupTableBlackboxDevice
) / sizeof(char *) },
612 { lookupTableCurrentSensor
, sizeof(lookupTableCurrentSensor
) / sizeof(char *) },
614 { lookupTableGimbalMode
, sizeof(lookupTableGimbalMode
) / sizeof(char *) },
617 { lookupTableSerialRX
, sizeof(lookupTableSerialRX
) / sizeof(char *) },
620 { lookupTableRxSpi
, sizeof(lookupTableRxSpi
) / sizeof(char *) },
622 { lookupTableGyroLpf
, sizeof(lookupTableGyroLpf
) / sizeof(char *) },
623 { lookupTableAccHardware
, sizeof(lookupTableAccHardware
) / sizeof(char *) },
625 { lookupTableBaroHardware
, sizeof(lookupTableBaroHardware
) / sizeof(char *) },
628 { lookupTableMagHardware
, sizeof(lookupTableMagHardware
) / sizeof(char *) },
630 { lookupTableDebug
, sizeof(lookupTableDebug
) / sizeof(char *) },
631 { lookupTableSuperExpoYaw
, sizeof(lookupTableSuperExpoYaw
) / sizeof(char *) },
632 { lookupTablePwmProtocol
, sizeof(lookupTablePwmProtocol
) / sizeof(char *) },
633 { lookupTableRcInterpolation
, sizeof(lookupTableRcInterpolation
) / sizeof(char *) },
634 { lookupTableLowpassType
, sizeof(lookupTableLowpassType
) / sizeof(char *) },
635 { lookupTableFailsafe
, sizeof(lookupTableFailsafe
) / sizeof(char *) },
637 { lookupTableOsdType
, sizeof(lookupTableOsdType
) / sizeof(char *) },
641 #define VALUE_TYPE_OFFSET 0
642 #define VALUE_SECTION_OFFSET 4
643 #define VALUE_MODE_OFFSET 6
647 VAR_UINT8
= (0 << VALUE_TYPE_OFFSET
),
648 VAR_INT8
= (1 << VALUE_TYPE_OFFSET
),
649 VAR_UINT16
= (2 << VALUE_TYPE_OFFSET
),
650 VAR_INT16
= (3 << VALUE_TYPE_OFFSET
),
651 VAR_UINT32
= (4 << VALUE_TYPE_OFFSET
),
652 VAR_FLOAT
= (5 << VALUE_TYPE_OFFSET
),
655 MASTER_VALUE
= (0 << VALUE_SECTION_OFFSET
),
656 PROFILE_VALUE
= (1 << VALUE_SECTION_OFFSET
),
657 PROFILE_RATE_VALUE
= (2 << VALUE_SECTION_OFFSET
),
659 MODE_DIRECT
= (0 << VALUE_MODE_OFFSET
),
660 MODE_LOOKUP
= (1 << VALUE_MODE_OFFSET
)
663 #define VALUE_TYPE_MASK (0x0F)
664 #define VALUE_SECTION_MASK (0x30)
665 #define VALUE_MODE_MASK (0xC0)
667 typedef struct cliMinMaxConfig_s
{
672 typedef struct cliLookupTableConfig_s
{
673 const lookupTableIndex_e tableIndex
;
674 } cliLookupTableConfig_t
;
677 cliLookupTableConfig_t lookup
;
678 cliMinMaxConfig_t minmax
;
683 const uint8_t type
; // see cliValueFlag_e
685 const cliValueConfig_t config
;
688 const clivalue_t valueTable
[] = {
689 { "mid_rc", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.midrc
, .config
.minmax
= { 1200, 1700 } },
690 { "min_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.mincheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
691 { "max_check", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.maxcheck
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
692 { "rssi_channel", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_channel
, .config
.minmax
= { 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
} },
693 { "rssi_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rssi_scale
, .config
.minmax
= { RSSI_SCALE_MIN
, RSSI_SCALE_MAX
} },
694 { "rc_interpolation", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rcInterpolation
, .config
.lookup
= { TABLE_RC_INTERPOLATION
} },
695 { "rc_interpolation_interval", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.rcInterpolationInterval
, .config
.minmax
= { 1, 50 } },
696 { "rssi_ppm_invert", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.rssi_ppm_invert
, .config
.lookup
= { TABLE_OFF_ON
} },
697 { "input_filtering_mode", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.inputFilteringMode
, .config
.lookup
= { TABLE_OFF_ON
} },
698 { "roll_yaw_cam_mix_degrees", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.fpvCamAngleDegrees
, .config
.minmax
= { 0, 50 } },
699 { "max_aux_channels", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.max_aux_channel
, .config
.minmax
= { 0, 13 } },
700 { "debug_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.debug_mode
, .config
.lookup
= { TABLE_DEBUG
} },
702 { "min_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motorConfig
.minthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
703 { "max_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motorConfig
.maxthrottle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
704 { "min_command", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motorConfig
.mincommand
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
706 { "digital_idle_percent", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.motorConfig
.digitalIdleOffsetPercent
, .config
.minmax
= { 0, 20} },
708 { "max_esc_throttle_jump", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motorConfig
.maxEscThrottleJumpMs
, .config
.minmax
= { 0, 1000 } },
710 { "3d_deadband_low", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_low
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} }, // FIXME upper limit should match code in the mixer, 1500 currently
711 { "3d_deadband_high", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_high
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} }, // FIXME lower limit should match code in the mixer, 1500 currently,
712 { "3d_neutral", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.neutral3d
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
713 { "3d_deadband_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.flight3DConfig
.deadband3d_throttle
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
715 { "use_unsynced_pwm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.motorConfig
.useUnsyncedPwm
, .config
.lookup
= { TABLE_OFF_ON
} },
716 { "motor_pwm_protocol", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.motorConfig
.motorPwmProtocol
, .config
.lookup
= { TABLE_MOTOR_PWM_PROTOCOL
} },
717 { "motor_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.motorConfig
.motorPwmRate
, .config
.minmax
= { 200, 32000 } },
719 { "disarm_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.armingConfig
.disarm_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
} },
720 { "gyro_cal_on_first_arm", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.armingConfig
.gyro_cal_on_first_arm
, .config
.lookup
= { TABLE_OFF_ON
} },
721 { "auto_disarm_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.armingConfig
.auto_disarm_delay
, .config
.minmax
= { 0, 60 } },
722 { "small_angle", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.imuConfig
.small_angle
, .config
.minmax
= { 0, 180 } },
724 { "fixedwing_althold_dir", VAR_INT8
| MASTER_VALUE
, &masterConfig
.airplaneConfig
.fixedwing_althold_dir
, .config
.minmax
= { -1, 1 } },
726 { "reboot_character", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.serialConfig
.reboot_character
, .config
.minmax
= { 48, 126 } },
729 { "gps_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.provider
, .config
.lookup
= { TABLE_GPS_PROVIDER
} },
730 { "gps_sbas_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.sbasMode
, .config
.lookup
= { TABLE_GPS_SBAS_MODE
} },
731 { "gps_auto_config", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoConfig
, .config
.lookup
= { TABLE_OFF_ON
} },
732 { "gps_auto_baud", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsConfig
.autoBaud
, .config
.lookup
= { TABLE_OFF_ON
} },
734 { "gps_pos_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOS
], .config
.minmax
= { 0, 200 } },
735 { "gps_pos_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOS
], .config
.minmax
= { 0, 200 } },
736 { "gps_pos_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOS
], .config
.minmax
= { 0, 200 } },
737 { "gps_posr_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDPOSR
], .config
.minmax
= { 0, 200 } },
738 { "gps_posr_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDPOSR
], .config
.minmax
= { 0, 200 } },
739 { "gps_posr_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDPOSR
], .config
.minmax
= { 0, 200 } },
740 { "gps_nav_p", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDNAVR
], .config
.minmax
= { 0, 200 } },
741 { "gps_nav_i", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDNAVR
], .config
.minmax
= { 0, 200 } },
742 { "gps_nav_d", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDNAVR
], .config
.minmax
= { 0, 200 } },
743 { "gps_wp_radius", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gpsProfile
.gps_wp_radius
, .config
.minmax
= { 0, 2000 } },
744 { "nav_controls_heading", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gpsProfile
.nav_controls_heading
, .config
.lookup
= { TABLE_OFF_ON
} },
745 { "nav_speed_min", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gpsProfile
.nav_speed_min
, .config
.minmax
= { 10, 2000 } },
746 { "nav_speed_max", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gpsProfile
.nav_speed_max
, .config
.minmax
= { 10, 2000 } },
747 { "nav_slew_rate", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gpsProfile
.nav_slew_rate
, .config
.minmax
= { 0, 100 } },
751 { "gtune_loP_rll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_ROLL
], .config
.minmax
= { 10, 200 } },
752 { "gtune_loP_ptch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_PITCH
], .config
.minmax
= { 10, 200 } },
753 { "gtune_loP_yw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_lolimP
[FD_YAW
], .config
.minmax
= { 10, 200 } },
754 { "gtune_hiP_rll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_ROLL
], .config
.minmax
= { 0, 200 } },
755 { "gtune_hiP_ptch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_PITCH
], .config
.minmax
= { 0, 200 } },
756 { "gtune_hiP_yw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_hilimP
[FD_YAW
], .config
.minmax
= { 0, 200 } },
757 { "gtune_pwr", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_pwr
, .config
.minmax
= { 0, 10 } },
758 { "gtune_settle_time", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_settle_time
, .config
.minmax
= { 200, 1000 } },
759 { "gtune_average_cycles", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.gtune_average_cycles
, .config
.minmax
= { 8, 128 } },
763 { "beeper_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.beeperConfig
.isInverted
, .config
.lookup
= { TABLE_OFF_ON
} },
764 { "beeper_od", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.beeperConfig
.isOpenDrain
, .config
.lookup
= { TABLE_OFF_ON
} },
768 { "serialrx_provider", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.serialrx_provider
, .config
.lookup
= { TABLE_SERIAL_RX
} },
771 { "sbus_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rxConfig
.sbus_inversion
, .config
.lookup
= { TABLE_OFF_ON
} },
774 { "spektrum_sat_bind", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.spektrum_sat_bind
, .config
.minmax
= { SPEKTRUM_SAT_BIND_DISABLED
, SPEKTRUM_SAT_BIND_MAX
} },
775 { "spektrum_sat_bind_autoreset",VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rxConfig
.spektrum_sat_bind_autoreset
, .config
.minmax
= { 0, 1} },
779 { "telemetry_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_switch
, .config
.lookup
= { TABLE_OFF_ON
} },
780 { "telemetry_inversion", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.telemetry_inversion
, .config
.lookup
= { TABLE_OFF_ON
} },
781 { "frsky_default_lattitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLatitude
, .config
.minmax
= { -90.0, 90.0 } },
782 { "frsky_default_longitude", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.gpsNoFixLongitude
, .config
.minmax
= { -180.0, 180.0 } },
783 { "frsky_coordinates_format", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_coordinate_format
, .config
.minmax
= { 0, FRSKY_FORMAT_NMEA
} },
784 { "frsky_unit", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.frsky_unit
, .config
.lookup
= { TABLE_UNIT
} },
785 { "frsky_vfas_precision", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.frsky_vfas_precision
, .config
.minmax
= { FRSKY_VFAS_PRECISION_LOW
, FRSKY_VFAS_PRECISION_HIGH
} },
786 { "frsky_vfas_cell_voltage", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.frsky_vfas_cell_voltage
, .config
.lookup
= { TABLE_OFF_ON
} },
787 { "hott_alarm_sound_interval", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.telemetryConfig
.hottAlarmSoundInterval
, .config
.minmax
= { 0, 120 } },
788 { "pid_values_as_telemetry", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.telemetryConfig
.pidValuesAsTelemetry
, .config
.lookup
= {TABLE_OFF_ON
} },
791 { "battery_capacity", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.batteryCapacity
, .config
.minmax
= { 0, 20000 } },
792 { "vbat_scale", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatscale
, .config
.minmax
= { VBAT_SCALE_MIN
, VBAT_SCALE_MAX
} },
793 { "vbat_max_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmaxcellvoltage
, .config
.minmax
= { 10, 50 } },
794 { "vbat_min_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatmincellvoltage
, .config
.minmax
= { 10, 50 } },
795 { "vbat_warning_cell_voltage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbatwarningcellvoltage
, .config
.minmax
= { 10, 50 } },
796 { "vbat_hysteresis", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.vbathysteresis
, .config
.minmax
= { 0, 250 } },
797 { "current_meter_scale", VAR_INT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterScale
, .config
.minmax
= { -16000, 16000 } },
798 { "current_meter_offset", VAR_INT16
| MASTER_VALUE
, &masterConfig
.batteryConfig
.currentMeterOffset
, .config
.minmax
= { -16000, 16000 } },
799 { "multiwii_current_meter_output", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.multiwiiCurrentMeterOutput
, .config
.lookup
= { TABLE_OFF_ON
} },
800 { "current_meter_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.currentMeterType
, .config
.lookup
= { TABLE_CURRENT_SENSOR
} },
801 { "battery_notpresent_level", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.batterynotpresentlevel
, .config
.minmax
= { 0, 200 } },
802 { "use_vbat_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.useVBatAlerts
, .config
.lookup
= { TABLE_OFF_ON
} },
803 { "use_consumption_alerts", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.batteryConfig
.useConsumptionAlerts
, .config
.lookup
= { TABLE_OFF_ON
} },
804 { "consumption_warning_percentage", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.batteryConfig
.consumptionWarningPercentage
, .config
.minmax
= { 0, 100 } },
805 { "align_gyro", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.gyro_align
, .config
.lookup
= { TABLE_ALIGNMENT
} },
806 { "align_acc", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.acc_align
, .config
.lookup
= { TABLE_ALIGNMENT
} },
807 { "align_mag", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorAlignmentConfig
.mag_align
, .config
.lookup
= { TABLE_ALIGNMENT
} },
809 { "align_board_roll", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.rollDegrees
, .config
.minmax
= { -180, 360 } },
810 { "align_board_pitch", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.pitchDegrees
, .config
.minmax
= { -180, 360 } },
811 { "align_board_yaw", VAR_INT16
| MASTER_VALUE
, &masterConfig
.boardAlignment
.yawDegrees
, .config
.minmax
= { -180, 360 } },
813 { "max_angle_inclination", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.max_angle_inclination
, .config
.minmax
= { 100, 900 } },
814 { "gyro_lpf", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyroConfig
.gyro_lpf
, .config
.lookup
= { TABLE_GYRO_LPF
} },
815 { "gyro_sync_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_sync_denom
, .config
.minmax
= { 1, 8 } },
816 { "gyro_lowpass_type", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gyroConfig
.gyro_soft_lpf_type
, .config
.lookup
= { TABLE_LOWPASS_TYPE
} },
817 { "gyro_lowpass", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_soft_lpf_hz
, .config
.minmax
= { 0, 255 } },
818 { "gyro_notch1_hz", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_soft_notch_hz_1
, .config
.minmax
= { 0, 1000 } },
819 { "gyro_notch1_cutoff", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_soft_notch_cutoff_1
, .config
.minmax
= { 1, 1000 } },
820 { "gyro_notch2_hz", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_soft_notch_hz_2
, .config
.minmax
= { 0, 1000 } },
821 { "gyro_notch2_cutoff", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyro_soft_notch_cutoff_2
, .config
.minmax
= { 1, 1000 } },
822 { "moron_threshold", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.gyroConfig
.gyroMovementCalibrationThreshold
, .config
.minmax
= { 0, 128 } },
823 { "imu_dcm_kp", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.imuConfig
.dcm_kp
, .config
.minmax
= { 0, 50000 } },
824 { "imu_dcm_ki", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.imuConfig
.dcm_ki
, .config
.minmax
= { 0, 50000 } },
826 { "alt_hold_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rcControlsConfig
.alt_hold_deadband
, .config
.minmax
= { 1, 250 } },
827 { "alt_hold_fast_change", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.rcControlsConfig
.alt_hold_fast_change
, .config
.lookup
= { TABLE_OFF_ON
} },
828 { "deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rcControlsConfig
.deadband
, .config
.minmax
= { 0, 32 } },
829 { "yaw_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.rcControlsConfig
.yaw_deadband
, .config
.minmax
= { 0, 100 } },
831 { "throttle_correction_value", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.throttleCorrectionConfig
.throttle_correction_value
, .config
.minmax
= { 0, 150 } },
832 { "throttle_correction_angle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.throttleCorrectionConfig
.throttle_correction_angle
, .config
.minmax
= { 1, 900 } },
834 { "yaw_control_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.rcControlsConfig
.yaw_control_direction
, .config
.minmax
= { -1, 1 } },
836 { "yaw_motor_direction", VAR_INT8
| MASTER_VALUE
, &masterConfig
.mixerConfig
.yaw_motor_direction
, .config
.minmax
= { -1, 1 } },
837 { "yaw_p_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_p_limit
, .config
.minmax
= { YAW_P_LIMIT_MIN
, YAW_P_LIMIT_MAX
} },
838 { "pidsum_limit", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.pidSumLimit
, .config
.minmax
= { 0.1, 1.0 } },
840 { "servo_center_pulse", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servoConfig
.servoCenterPulse
, .config
.minmax
= { PWM_RANGE_ZERO
, PWM_RANGE_MAX
} },
841 { "tri_unarmed_servo", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.servoMixerConfig
.tri_unarmed_servo
, .config
.lookup
= { TABLE_OFF_ON
} },
842 { "servo_lowpass_freq", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servoMixerConfig
.servo_lowpass_freq
, .config
.minmax
= { 10, 400} },
843 { "servo_lowpass_enable", VAR_INT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.servoMixerConfig
.servo_lowpass_enable
, .config
.lookup
= { TABLE_OFF_ON
} },
844 { "servo_pwm_rate", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.servoConfig
.servoPwmRate
, .config
.minmax
= { 50, 498 } },
845 { "gimbal_mode", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.gimbalConfig
.mode
, .config
.lookup
= { TABLE_GIMBAL_MODE
} },
848 { "rc_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rcRate8
, .config
.minmax
= { 0, 255 } },
849 { "rc_rate_yaw", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rcYawRate8
, .config
.minmax
= { 0, 255 } },
850 { "rc_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rcExpo8
, .config
.minmax
= { 0, 100 } },
851 { "rc_yaw_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rcYawExpo8
, .config
.minmax
= { 0, 100 } },
852 { "thr_mid", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].thrMid8
, .config
.minmax
= { 0, 100 } },
853 { "thr_expo", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].thrExpo8
, .config
.minmax
= { 0, 100 } },
854 { "roll_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rates
[FD_ROLL
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
} },
855 { "pitch_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rates
[FD_PITCH
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX
} },
856 { "yaw_srate", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].rates
[FD_YAW
], .config
.minmax
= { 0, CONTROL_RATE_CONFIG_YAW_RATE_MAX
} },
857 { "tpa_rate", VAR_UINT8
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].dynThrPID
, .config
.minmax
= { 0, CONTROL_RATE_CONFIG_TPA_MAX
} },
858 { "tpa_breakpoint", VAR_UINT16
| PROFILE_RATE_VALUE
, &masterConfig
.profile
[0].controlRateProfile
[0].tpa_breakpoint
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
} },
859 { "airmode_activate_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.airModeActivateThreshold
, .config
.minmax
= {1000, 2000 } },
861 { "failsafe_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_delay
, .config
.minmax
= { 0, 200 } },
862 { "failsafe_off_delay", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_off_delay
, .config
.minmax
= { 0, 200 } },
863 { "failsafe_throttle", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle
, .config
.minmax
= { PWM_RANGE_MIN
, PWM_RANGE_MAX
} },
864 { "failsafe_kill_switch", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_kill_switch
, .config
.lookup
= { TABLE_OFF_ON
} },
865 { "failsafe_throttle_low_delay",VAR_UINT16
| MASTER_VALUE
, &masterConfig
.failsafeConfig
.failsafe_throttle_low_delay
, .config
.minmax
= { 0, 300 } },
866 { "failsafe_procedure", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.failsafeConfig
.failsafe_procedure
, .config
.lookup
= { TABLE_FAILSAFE
} },
868 { "rx_min_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_min_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
} },
869 { "rx_max_usec", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.rxConfig
.rx_max_usec
, .config
.minmax
= { PWM_PULSE_MIN
, PWM_PULSE_MAX
} },
871 { "acc_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorSelectionConfig
.acc_hardware
, .config
.lookup
= { TABLE_ACC_HARDWARE
} },
872 { "acc_lpf_hz", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.accelerometerConfig
.acc_lpf_hz
, .config
.minmax
= { 0, 400 } },
873 { "accxy_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.imuConfig
.accDeadband
.xy
, .config
.minmax
= { 0, 100 } },
874 { "accz_deadband", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.imuConfig
.accDeadband
.z
, .config
.minmax
= { 0, 100 } },
875 { "acc_unarmedcal", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.imuConfig
.acc_unarmedcal
, .config
.lookup
= { TABLE_OFF_ON
} },
876 { "acc_trim_pitch", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accelerometerTrims
.values
.pitch
, .config
.minmax
= { -300, 300 } },
877 { "acc_trim_roll", VAR_INT16
| MASTER_VALUE
, &masterConfig
.accelerometerTrims
.values
.roll
, .config
.minmax
= { -300, 300 } },
880 { "baro_tab_size", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.barometerConfig
.baro_sample_count
, .config
.minmax
= { 0, BARO_SAMPLE_COUNT_MAX
} },
881 { "baro_noise_lpf", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.barometerConfig
.baro_noise_lpf
, .config
.minmax
= { 0 , 1 } },
882 { "baro_cf_vel", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.barometerConfig
.baro_cf_vel
, .config
.minmax
= { 0 , 1 } },
883 { "baro_cf_alt", VAR_FLOAT
| MASTER_VALUE
, &masterConfig
.barometerConfig
.baro_cf_alt
, .config
.minmax
= { 0 , 1 } },
884 { "baro_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorSelectionConfig
.baro_hardware
, .config
.lookup
= { TABLE_BARO_HARDWARE
} },
888 { "mag_hardware", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sensorSelectionConfig
.mag_hardware
, .config
.lookup
= { TABLE_MAG_HARDWARE
} },
889 { "mag_declination", VAR_INT16
| MASTER_VALUE
, &masterConfig
.compassConfig
.mag_declination
, .config
.minmax
= { -18000, 18000 } },
891 { "dterm_lowpass_type", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.dterm_filter_type
, .config
.lookup
= { TABLE_LOWPASS_TYPE
} },
892 { "dterm_lowpass", VAR_INT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_lpf_hz
, .config
.minmax
= {0, 500 } },
893 { "dterm_notch_hz", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_notch_hz
, .config
.minmax
= { 0, 500 } },
894 { "dterm_notch_cutoff", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dterm_notch_cutoff
, .config
.minmax
= { 1, 500 } },
895 { "vbat_pid_compensation", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.vbatPidCompensation
, .config
.lookup
= { TABLE_OFF_ON
} },
896 { "pid_at_min_throttle", VAR_UINT8
| PROFILE_VALUE
| MODE_LOOKUP
, &masterConfig
.profile
[0].pidProfile
.pidAtMinThrottle
, .config
.lookup
= { TABLE_OFF_ON
} },
897 { "iterm_throttle_gain", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.itermThrottleGain
, .config
.minmax
= {0, 200 } },
898 { "setpoint_relax_ratio", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.setpointRelaxRatio
, .config
.minmax
= {0, 100 } },
899 { "dterm_setpoint_weight", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.dtermSetpointWeight
, .config
.minmax
= {0, 255 } },
900 { "yaw_rate_accel_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yawRateAccelLimit
, .config
.minmax
= {0, 1000 } },
901 { "rate_accel_limit", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.rateAccelLimit
, .config
.minmax
= {0, 1000 } },
903 { "accum_threshold", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.rollPitchItermIgnoreRate
, .config
.minmax
= {15, 1000 } },
904 { "yaw_accum_threshold", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yawItermIgnoreRate
, .config
.minmax
= {15, 1000 } },
905 { "yaw_lowpass", VAR_UINT16
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.yaw_lpf_hz
, .config
.minmax
= {0, 500 } },
906 { "pid_process_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.pid_process_denom
, .config
.minmax
= { 1, 8 } },
908 { "p_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PITCH
], .config
.minmax
= { 0, 200 } },
909 { "i_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PITCH
], .config
.minmax
= { 0, 200 } },
910 { "d_pitch", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PITCH
], .config
.minmax
= { 0, 200 } },
911 { "p_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[ROLL
], .config
.minmax
= { 0, 200 } },
912 { "i_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[ROLL
], .config
.minmax
= { 0, 200 } },
913 { "d_roll", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[ROLL
], .config
.minmax
= { 0, 200 } },
914 { "p_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[YAW
], .config
.minmax
= { 0, 200 } },
915 { "i_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[YAW
], .config
.minmax
= { 0, 200 } },
916 { "d_yaw", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[YAW
], .config
.minmax
= { 0, 200 } },
918 { "p_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDALT
], .config
.minmax
= { 0, 200 } },
919 { "i_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDALT
], .config
.minmax
= { 0, 200 } },
920 { "d_alt", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDALT
], .config
.minmax
= { 0, 200 } },
922 { "p_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDLEVEL
], .config
.minmax
= { 0, 200 } },
923 { "i_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDLEVEL
], .config
.minmax
= { 0, 200 } },
924 { "d_level", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDLEVEL
], .config
.minmax
= { 0, 200 } },
926 { "p_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.P8
[PIDVEL
], .config
.minmax
= { 0, 200 } },
927 { "i_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.I8
[PIDVEL
], .config
.minmax
= { 0, 200 } },
928 { "d_vel", VAR_UINT8
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.D8
[PIDVEL
], .config
.minmax
= { 0, 200 } },
930 { "level_sensitivity", VAR_FLOAT
| PROFILE_VALUE
, &masterConfig
.profile
[0].pidProfile
.levelSensitivity
, .config
.minmax
= { 0.1, 3.0 } },
933 { "blackbox_rate_num", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackboxConfig
.rate_num
, .config
.minmax
= { 1, 32 } },
934 { "blackbox_rate_denom", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.blackboxConfig
.rate_denom
, .config
.minmax
= { 1, 32 } },
935 { "blackbox_device", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.blackboxConfig
.device
, .config
.lookup
= { TABLE_BLACKBOX_DEVICE
} },
936 { "blackbox_on_motor_test", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.blackboxConfig
.on_motor_test
, .config
.lookup
= { TABLE_OFF_ON
} },
940 { "vtx_band", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vtx_band
, .config
.minmax
= { 1, 5 } },
941 { "vtx_channel", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vtx_channel
, .config
.minmax
= { 1, 8 } },
942 { "vtx_mode", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vtx_mode
, .config
.minmax
= { 0, 2 } },
943 { "vtx_mhz", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.vtx_mhz
, .config
.minmax
= { 5600, 5950 } },
947 { "magzero_x", VAR_INT16
| MASTER_VALUE
, &masterConfig
.sensorTrims
.magZero
.raw
[X
], .config
.minmax
= { -32768, 32767 } },
948 { "magzero_y", VAR_INT16
| MASTER_VALUE
, &masterConfig
.sensorTrims
.magZero
.raw
[Y
], .config
.minmax
= { -32768, 32767 } },
949 { "magzero_z", VAR_INT16
| MASTER_VALUE
, &masterConfig
.sensorTrims
.magZero
.raw
[Z
], .config
.minmax
= { -32768, 32767 } },
952 { "ledstrip_visual_beeper", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.ledStripConfig
.ledstrip_visual_beeper
, .config
.lookup
= { TABLE_OFF_ON
} },
955 { "vtx_channel", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vtx_channel
, .config
.minmax
= { 0, 39 } },
956 { "vtx_power", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vtx_power
, .config
.minmax
= { 0, 1 } },
959 { "sdcard_dma", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.sdcardConfig
.useDma
, .config
.lookup
= { TABLE_OFF_ON
} },
962 { "osd_units", VAR_UINT8
| MASTER_VALUE
| MODE_LOOKUP
, &masterConfig
.osdProfile
.units
, .config
.lookup
= { TABLE_UNIT
} },
964 { "osd_rssi_alarm", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.osdProfile
.rssi_alarm
, .config
.minmax
= { 0, 100 } },
965 { "osd_cap_alarm", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.cap_alarm
, .config
.minmax
= { 0, 20000 } },
966 { "osd_time_alarm", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.time_alarm
, .config
.minmax
= { 0, 60 } },
967 { "osd_alt_alarm", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.alt_alarm
, .config
.minmax
= { 0, 10000 } },
969 { "osd_main_voltage_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_MAIN_BATT_VOLTAGE
], .config
.minmax
= { 0, 65536 } },
970 { "osd_rssi_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_RSSI_VALUE
], .config
.minmax
= { 0, 65536 } },
971 { "osd_flytimer_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_FLYTIME
], .config
.minmax
= { 0, 65536 } },
972 { "osd_ontime_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_ONTIME
], .config
.minmax
= { 0, 65536 } },
973 { "osd_flymode_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_FLYMODE
], .config
.minmax
= { 0, 65536 } },
974 { "osd_throttle_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_THROTTLE_POS
], .config
.minmax
= { 0, 65536 } },
975 { "osd_vtx_channel_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_VTX_CHANNEL
], .config
.minmax
= { 0, 65536 } },
976 { "osd_crosshairs", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_CROSSHAIRS
], .config
.minmax
= { 0, 65536 } },
977 { "osd_artificial_horizon", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_ARTIFICIAL_HORIZON
], .config
.minmax
= { 0, 65536 } },
978 { "osd_current_draw_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_CURRENT_DRAW
], .config
.minmax
= { 0, 65536 } },
979 { "osd_mah_drawn_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_MAH_DRAWN
], .config
.minmax
= { 0, 65536 } },
980 { "osd_craft_name_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_CRAFT_NAME
], .config
.minmax
= { 0, 65536 } },
981 { "osd_gps_speed_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_GPS_SPEED
], .config
.minmax
= { 0, 65536 } },
982 { "osd_gps_sats_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_GPS_SATS
], .config
.minmax
= { 0, 65536 } },
983 { "osd_altitude_pos", VAR_UINT16
| MASTER_VALUE
, &masterConfig
.osdProfile
.item_pos
[OSD_ALTITUDE
], .config
.minmax
= { 0, 65536 } },
986 { "vcd_video_system", VAR_UINT8
| MASTER_VALUE
, &masterConfig
.vcdProfile
.video_system
, .config
.minmax
= { 0, 2 } },
987 { "vcd_h_offset", VAR_INT8
| MASTER_VALUE
, &masterConfig
.vcdProfile
.h_offset
, .config
.minmax
= { -32, 31 } },
988 { "vcd_v_offset", VAR_INT8
| MASTER_VALUE
, &masterConfig
.vcdProfile
.v_offset
, .config
.minmax
= { -15, 16 } },
992 #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t))
999 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
);
1000 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
);
1001 static void cliPrintVarDefault(const clivalue_t
*var
, uint32_t full
, master_t
*defaultConfig
);
1002 static void cliPrintVarRange(const clivalue_t
*var
);
1003 static void cliPrint(const char *str
);
1004 static void cliPrintf(const char *fmt
, ...);
1005 static void cliWrite(uint8_t ch
);
1007 static bool cliDumpPrintf(uint8_t dumpMask
, bool equalsDefault
, const char *format
, ...);
1008 static bool cliDefaultPrintf(uint8_t dumpMask
, bool equalsDefault
, const char *format
, ...);
1010 #ifndef CLI_MINIMAL_VERBOSITY
1011 static void cliRepeat(const char *str
, uint8_t len
)
1013 for (int i
= 0; i
< len
; i
++) {
1020 static void cliPrompt(void)
1023 bufWriterFlush(cliWriter
);
1026 static void cliShowParseError(void)
1028 cliPrint("Parse error\r\n");
1031 static void cliShowArgumentRangeError(char *name
, int min
, int max
)
1033 cliPrintf("%s must be between %d and %d\r\n", name
, min
, max
);
1036 static char *nextArg(char *currentArg
)
1038 char *ptr
= strchr(currentArg
, ' ');
1039 while (ptr
&& *ptr
== ' ') {
1046 static char *processChannelRangeArgs(char *ptr
, channelRange_t
*range
, uint8_t *validArgumentCount
)
1050 for (uint32_t argIndex
= 0; argIndex
< 2; argIndex
++) {
1054 val
= CHANNEL_VALUE_TO_STEP(val
);
1055 if (val
>= MIN_MODE_RANGE_STEP
&& val
<= MAX_MODE_RANGE_STEP
) {
1056 if (argIndex
== 0) {
1057 range
->startStep
= val
;
1059 range
->endStep
= val
;
1061 (*validArgumentCount
)++;
1069 // Check if a string's length is zero
1070 static bool isEmpty(const char *string
)
1072 return *string
== '\0';
1075 static void printRxFail(uint8_t dumpMask
, master_t
*defaultConfig
)
1077 // print out rxConfig failsafe settings
1078 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
;
1079 rxFailsafeChannelConfiguration_t
*channelFailsafeConfigurationDefault
;
1082 for (uint32_t channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
1083 channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[channel
];
1084 channelFailsafeConfigurationDefault
= &defaultConfig
->rxConfig
.failsafe_channel_configurations
[channel
];
1085 equalsDefault
= channelFailsafeConfiguration
->mode
== channelFailsafeConfigurationDefault
->mode
1086 && channelFailsafeConfiguration
->step
== channelFailsafeConfigurationDefault
->step
;
1087 requireValue
= channelFailsafeConfiguration
->mode
== RX_FAILSAFE_MODE_SET
;
1089 const char *format
= "rxfail %u %c %d\r\n";
1090 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1092 rxFailsafeModeCharacters
[channelFailsafeConfigurationDefault
->mode
],
1093 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfigurationDefault
->step
)
1095 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1097 rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
],
1098 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration
->step
)
1101 const char *format
= "rxfail %u %c\r\n";
1102 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1104 rxFailsafeModeCharacters
[channelFailsafeConfigurationDefault
->mode
]
1106 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1108 rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
]
1114 static void cliRxFail(char *cmdline
)
1119 if (isEmpty(cmdline
)) {
1120 // print out rxConfig failsafe settings
1121 for (channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
1122 cliRxFail(itoa(channel
, buf
, 10));
1125 char *ptr
= cmdline
;
1126 channel
= atoi(ptr
++);
1127 if ((channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
)) {
1129 rxFailsafeChannelConfiguration_t
*channelFailsafeConfiguration
= &masterConfig
.rxConfig
.failsafe_channel_configurations
[channel
];
1132 rxFailsafeChannelType_e type
= (channel
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_TYPE_FLIGHT
: RX_FAILSAFE_TYPE_AUX
;
1133 rxFailsafeChannelMode_e mode
= channelFailsafeConfiguration
->mode
;
1134 bool requireValue
= channelFailsafeConfiguration
->mode
== RX_FAILSAFE_MODE_SET
;
1138 char *p
= strchr(rxFailsafeModeCharacters
, *(ptr
));
1140 uint8_t requestedMode
= p
- rxFailsafeModeCharacters
;
1141 mode
= rxFailsafeModesTable
[type
][requestedMode
];
1143 mode
= RX_FAILSAFE_MODE_INVALID
;
1145 if (mode
== RX_FAILSAFE_MODE_INVALID
) {
1146 cliShowParseError();
1150 requireValue
= mode
== RX_FAILSAFE_MODE_SET
;
1154 if (!requireValue
) {
1155 cliShowParseError();
1159 value
= CHANNEL_VALUE_TO_RXFAIL_STEP(value
);
1160 if (value
> MAX_RXFAIL_RANGE_STEP
) {
1161 cliPrint("Value out of range\r\n");
1165 channelFailsafeConfiguration
->step
= value
;
1166 } else if (requireValue
) {
1167 cliShowParseError();
1170 channelFailsafeConfiguration
->mode
= mode
;
1174 char modeCharacter
= rxFailsafeModeCharacters
[channelFailsafeConfiguration
->mode
];
1176 // double use of cliPrintf below
1177 // 1. acknowledge interpretation on command,
1178 // 2. query current setting on single item,
1181 cliPrintf("rxfail %u %c %d\r\n",
1184 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfiguration
->step
)
1187 cliPrintf("rxfail %u %c\r\n",
1193 cliShowArgumentRangeError("channel", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
- 1);
1198 static void printAux(uint8_t dumpMask
, master_t
*defaultConfig
)
1200 // print out aux channel settings
1201 modeActivationCondition_t
*mac
;
1202 modeActivationCondition_t
*macDefault
;
1204 for (uint32_t i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
1205 mac
= &masterConfig
.modeActivationConditions
[i
];
1206 macDefault
= &defaultConfig
->modeActivationConditions
[i
];
1207 equalsDefault
= mac
->modeId
== macDefault
->modeId
1208 && mac
->auxChannelIndex
== macDefault
->auxChannelIndex
1209 && mac
->range
.startStep
== macDefault
->range
.startStep
1210 && mac
->range
.endStep
== macDefault
->range
.endStep
;
1211 const char *format
= "aux %u %u %u %u %u\r\n";
1212 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1215 macDefault
->auxChannelIndex
,
1216 MODE_STEP_TO_CHANNEL_VALUE(macDefault
->range
.startStep
),
1217 MODE_STEP_TO_CHANNEL_VALUE(macDefault
->range
.endStep
)
1219 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1222 mac
->auxChannelIndex
,
1223 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
1224 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
)
1229 static void cliAux(char *cmdline
)
1234 if (isEmpty(cmdline
)) {
1235 printAux(DUMP_MASTER
, NULL
);
1239 if (i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
) {
1240 modeActivationCondition_t
*mac
= &masterConfig
.modeActivationConditions
[i
];
1241 uint8_t validArgumentCount
= 0;
1245 if (val
>= 0 && val
< CHECKBOX_ITEM_COUNT
) {
1247 validArgumentCount
++;
1253 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1254 mac
->auxChannelIndex
= val
;
1255 validArgumentCount
++;
1258 ptr
= processChannelRangeArgs(ptr
, &mac
->range
, &validArgumentCount
);
1260 if (validArgumentCount
!= 4) {
1261 memset(mac
, 0, sizeof(modeActivationCondition_t
));
1264 cliShowArgumentRangeError("index", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT
- 1);
1269 static void printSerial(uint8_t dumpMask
, master_t
*defaultConfig
)
1271 serialConfig_t
*serialConfig
;
1272 serialConfig_t
*serialConfigDefault
;
1274 for (uint32_t i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
1275 serialConfig
= &masterConfig
.serialConfig
;
1276 if (!serialIsPortAvailable(serialConfig
->portConfigs
[i
].identifier
)) {
1279 serialConfigDefault
= &defaultConfig
->serialConfig
;
1280 equalsDefault
= serialConfig
->portConfigs
[i
].identifier
== serialConfigDefault
->portConfigs
[i
].identifier
1281 && serialConfig
->portConfigs
[i
].functionMask
== serialConfigDefault
->portConfigs
[i
].functionMask
1282 && serialConfig
->portConfigs
[i
].msp_baudrateIndex
== serialConfigDefault
->portConfigs
[i
].msp_baudrateIndex
1283 && serialConfig
->portConfigs
[i
].gps_baudrateIndex
== serialConfigDefault
->portConfigs
[i
].gps_baudrateIndex
1284 && serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
== serialConfigDefault
->portConfigs
[i
].telemetry_baudrateIndex
1285 && serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
== serialConfigDefault
->portConfigs
[i
].blackbox_baudrateIndex
;
1286 const char *format
= "serial %d %d %ld %ld %ld %ld\r\n";
1287 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1288 serialConfigDefault
->portConfigs
[i
].identifier
,
1289 serialConfigDefault
->portConfigs
[i
].functionMask
,
1290 baudRates
[serialConfigDefault
->portConfigs
[i
].msp_baudrateIndex
],
1291 baudRates
[serialConfigDefault
->portConfigs
[i
].gps_baudrateIndex
],
1292 baudRates
[serialConfigDefault
->portConfigs
[i
].telemetry_baudrateIndex
],
1293 baudRates
[serialConfigDefault
->portConfigs
[i
].blackbox_baudrateIndex
]
1295 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1296 serialConfig
->portConfigs
[i
].identifier
,
1297 serialConfig
->portConfigs
[i
].functionMask
,
1298 baudRates
[serialConfig
->portConfigs
[i
].msp_baudrateIndex
],
1299 baudRates
[serialConfig
->portConfigs
[i
].gps_baudrateIndex
],
1300 baudRates
[serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
],
1301 baudRates
[serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
]
1306 static void cliSerial(char *cmdline
)
1311 if (isEmpty(cmdline
)) {
1312 printSerial(DUMP_MASTER
, NULL
);
1316 serialPortConfig_t portConfig
;
1317 memset(&portConfig
, 0 , sizeof(portConfig
));
1319 serialPortConfig_t
*currentConfig
;
1321 uint8_t validArgumentCount
= 0;
1326 currentConfig
= serialFindPortConfiguration(val
);
1327 if (currentConfig
) {
1328 portConfig
.identifier
= val
;
1329 validArgumentCount
++;
1335 portConfig
.functionMask
= val
& 0xFFFF;
1336 validArgumentCount
++;
1339 for (i
= 0; i
< 4; i
++) {
1347 uint8_t baudRateIndex
= lookupBaudRateIndex(val
);
1348 if (baudRates
[baudRateIndex
] != (uint32_t) val
) {
1354 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_1000000
) {
1357 portConfig
.msp_baudrateIndex
= baudRateIndex
;
1360 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1363 portConfig
.gps_baudrateIndex
= baudRateIndex
;
1366 if (baudRateIndex
!= BAUD_AUTO
&& baudRateIndex
> BAUD_115200
) {
1369 portConfig
.telemetry_baudrateIndex
= baudRateIndex
;
1372 if (baudRateIndex
< BAUD_19200
|| baudRateIndex
> BAUD_250000
) {
1375 portConfig
.blackbox_baudrateIndex
= baudRateIndex
;
1379 validArgumentCount
++;
1382 if (validArgumentCount
< 6) {
1383 cliShowParseError();
1387 memcpy(currentConfig
, &portConfig
, sizeof(portConfig
));
1391 #ifndef SKIP_SERIAL_PASSTHROUGH
1392 static void cliSerialPassthrough(char *cmdline
)
1394 if (isEmpty(cmdline
)) {
1395 cliShowParseError();
1402 char* tok
= strtok(cmdline
, " ");
1405 while (tok
!= NULL
) {
1414 if (strstr(tok
, "rx") || strstr(tok
, "RX"))
1416 if (strstr(tok
, "tx") || strstr(tok
, "TX"))
1421 tok
= strtok(NULL
, " ");
1424 serialPort_t
*passThroughPort
;
1425 serialPortUsage_t
*passThroughPortUsage
= findSerialPortUsageByIdentifier(id
);
1426 if (!passThroughPortUsage
|| passThroughPortUsage
->serialPort
== NULL
) {
1428 printf("Port %d is not open, you must specify baud\r\n", id
);
1434 passThroughPort
= openSerialPort(id
, FUNCTION_NONE
, NULL
,
1436 SERIAL_NOT_INVERTED
);
1437 if (!passThroughPort
) {
1438 printf("Port %d could not be opened\r\n", id
);
1441 printf("Port %d opened, baud=%d\r\n", id
, baud
);
1443 passThroughPort
= passThroughPortUsage
->serialPort
;
1444 // If the user supplied a mode, override the port's mode, otherwise
1445 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1446 printf("Port %d already open\r\n", id
);
1447 if (mode
&& passThroughPort
->mode
!= mode
) {
1448 printf("Adjusting mode from configured value %d to %d\r\n",
1449 passThroughPort
->mode
, mode
);
1450 serialSetMode(passThroughPort
, mode
);
1452 // If this port has a rx callback associated we need to remove it now.
1453 // Otherwise no data will be pushed in the serial port buffer!
1454 if (passThroughPort
->rxCallback
) {
1455 printf("Removing rxCallback from port\r\n");
1456 passThroughPort
->rxCallback
= 0;
1460 printf("Relaying data to device on port %d, Reset your board to exit "
1461 "serial passthrough mode.\r\n", id
);
1463 serialPassthrough(cliPort
, passThroughPort
, NULL
, NULL
);
1467 static void printAdjustmentRange(uint8_t dumpMask
, master_t
*defaultConfig
)
1469 // print out adjustment ranges channel settings
1470 adjustmentRange_t
*ar
;
1471 adjustmentRange_t
*arDefault
;
1473 for (uint32_t i
= 0; i
< MAX_ADJUSTMENT_RANGE_COUNT
; i
++) {
1474 ar
= &masterConfig
.adjustmentRanges
[i
];
1475 arDefault
= &defaultConfig
->adjustmentRanges
[i
];
1476 equalsDefault
= ar
->auxChannelIndex
== arDefault
->auxChannelIndex
1477 && ar
->range
.startStep
== arDefault
->range
.startStep
1478 && ar
->range
.endStep
== arDefault
->range
.endStep
1479 && ar
->adjustmentFunction
== arDefault
->adjustmentFunction
1480 && ar
->auxSwitchChannelIndex
== arDefault
->auxSwitchChannelIndex
1481 && ar
->adjustmentIndex
== arDefault
->adjustmentIndex
;
1482 const char *format
= "adjrange %u %u %u %u %u %u %u\r\n";
1483 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1485 arDefault
->adjustmentIndex
,
1486 arDefault
->auxChannelIndex
,
1487 MODE_STEP_TO_CHANNEL_VALUE(arDefault
->range
.startStep
),
1488 MODE_STEP_TO_CHANNEL_VALUE(arDefault
->range
.endStep
),
1489 arDefault
->adjustmentFunction
,
1490 arDefault
->auxSwitchChannelIndex
1492 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1494 ar
->adjustmentIndex
,
1495 ar
->auxChannelIndex
,
1496 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
1497 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
1498 ar
->adjustmentFunction
,
1499 ar
->auxSwitchChannelIndex
1504 static void cliAdjustmentRange(char *cmdline
)
1509 if (isEmpty(cmdline
)) {
1510 printAdjustmentRange(DUMP_MASTER
, NULL
);
1514 if (i
< MAX_ADJUSTMENT_RANGE_COUNT
) {
1515 adjustmentRange_t
*ar
= &masterConfig
.adjustmentRanges
[i
];
1516 uint8_t validArgumentCount
= 0;
1521 if (val
>= 0 && val
< MAX_SIMULTANEOUS_ADJUSTMENT_COUNT
) {
1522 ar
->adjustmentIndex
= val
;
1523 validArgumentCount
++;
1529 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1530 ar
->auxChannelIndex
= val
;
1531 validArgumentCount
++;
1535 ptr
= processChannelRangeArgs(ptr
, &ar
->range
, &validArgumentCount
);
1540 if (val
>= 0 && val
< ADJUSTMENT_FUNCTION_COUNT
) {
1541 ar
->adjustmentFunction
= val
;
1542 validArgumentCount
++;
1548 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1549 ar
->auxSwitchChannelIndex
= val
;
1550 validArgumentCount
++;
1554 if (validArgumentCount
!= 6) {
1555 memset(ar
, 0, sizeof(adjustmentRange_t
));
1556 cliShowParseError();
1559 cliShowArgumentRangeError("index", 0, MAX_ADJUSTMENT_RANGE_COUNT
- 1);
1564 #ifndef USE_QUAD_MIXER_ONLY
1565 static void printMotorMix(uint8_t dumpMask
, master_t
*defaultConfig
)
1571 for (uint32_t i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1572 if (masterConfig
.customMotorMixer
[i
].throttle
== 0.0f
)
1574 float thr
= masterConfig
.customMotorMixer
[i
].throttle
;
1575 float roll
= masterConfig
.customMotorMixer
[i
].roll
;
1576 float pitch
= masterConfig
.customMotorMixer
[i
].pitch
;
1577 float yaw
= masterConfig
.customMotorMixer
[i
].yaw
;
1578 float thrDefault
= defaultConfig
->customMotorMixer
[i
].throttle
;
1579 float rollDefault
= defaultConfig
->customMotorMixer
[i
].roll
;
1580 float pitchDefault
= defaultConfig
->customMotorMixer
[i
].pitch
;
1581 float yawDefault
= defaultConfig
->customMotorMixer
[i
].yaw
;
1582 bool equalsDefault
= thr
== thrDefault
&& roll
== rollDefault
&& pitch
== pitchDefault
&& yaw
== yawDefault
;
1584 const char *format
= "mmix %d %s %s %s %s\r\n";
1585 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1587 ftoa(thrDefault
, buf0
),
1588 ftoa(rollDefault
, buf1
),
1589 ftoa(pitchDefault
, buf2
),
1590 ftoa(yawDefault
, buf3
));
1591 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1599 #endif // USE_QUAD_MIXER_ONLY
1601 static void cliMotorMix(char *cmdline
)
1603 #ifdef USE_QUAD_MIXER_ONLY
1610 if (isEmpty(cmdline
)) {
1611 printMotorMix(DUMP_MASTER
, NULL
);
1612 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1613 // erase custom mixer
1614 for (uint32_t i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++)
1615 masterConfig
.customMotorMixer
[i
].throttle
= 0.0f
;
1616 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1617 ptr
= nextArg(cmdline
);
1620 for (uint32_t i
= 0; ; i
++) {
1621 if (mixerNames
[i
] == NULL
) {
1622 cliPrint("Invalid name\r\n");
1625 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1626 mixerLoadMix(i
, masterConfig
.customMotorMixer
);
1627 cliPrintf("Loaded %s\r\n", mixerNames
[i
]);
1635 uint32_t i
= atoi(ptr
); // get motor number
1636 if (i
< MAX_SUPPORTED_MOTORS
) {
1639 masterConfig
.customMotorMixer
[i
].throttle
= fastA2F(ptr
);
1644 masterConfig
.customMotorMixer
[i
].roll
= fastA2F(ptr
);
1649 masterConfig
.customMotorMixer
[i
].pitch
= fastA2F(ptr
);
1654 masterConfig
.customMotorMixer
[i
].yaw
= fastA2F(ptr
);
1658 cliShowParseError();
1660 printMotorMix(DUMP_MASTER
, NULL
);
1663 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
1669 static void printRxRange(uint8_t dumpMask
, master_t
*defaultConfig
)
1671 rxChannelRangeConfiguration_t
*channelRangeConfiguration
;
1672 rxChannelRangeConfiguration_t
*channelRangeConfigurationDefault
;
1674 for (uint32_t i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
1675 channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1676 channelRangeConfigurationDefault
= &defaultConfig
->rxConfig
.channelRanges
[i
];
1677 equalsDefault
= channelRangeConfiguration
->min
== channelRangeConfigurationDefault
->min
1678 && channelRangeConfiguration
->max
== channelRangeConfigurationDefault
->max
;
1679 const char *format
= "rxrange %u %u %u\r\n";
1680 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1682 channelRangeConfigurationDefault
->min
,
1683 channelRangeConfigurationDefault
->max
1685 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1687 channelRangeConfiguration
->min
,
1688 channelRangeConfiguration
->max
1693 static void cliRxRange(char *cmdline
)
1695 int i
, validArgumentCount
= 0;
1698 if (isEmpty(cmdline
)) {
1699 printRxRange(DUMP_MASTER
, NULL
);
1700 } else if (strcasecmp(cmdline
, "reset") == 0) {
1701 resetAllRxChannelRangeConfigurations(masterConfig
.rxConfig
.channelRanges
);
1705 if (i
>= 0 && i
< NON_AUX_CHANNEL_COUNT
) {
1706 int rangeMin
, rangeMax
;
1710 rangeMin
= atoi(ptr
);
1711 validArgumentCount
++;
1716 rangeMax
= atoi(ptr
);
1717 validArgumentCount
++;
1720 if (validArgumentCount
!= 2) {
1721 cliShowParseError();
1722 } else if (rangeMin
< PWM_PULSE_MIN
|| rangeMin
> PWM_PULSE_MAX
|| rangeMax
< PWM_PULSE_MIN
|| rangeMax
> PWM_PULSE_MAX
) {
1723 cliShowParseError();
1725 rxChannelRangeConfiguration_t
*channelRangeConfiguration
= &masterConfig
.rxConfig
.channelRanges
[i
];
1726 channelRangeConfiguration
->min
= rangeMin
;
1727 channelRangeConfiguration
->max
= rangeMax
;
1730 cliShowArgumentRangeError("channel", 0, NON_AUX_CHANNEL_COUNT
- 1);
1736 static void printLed(uint8_t dumpMask
, master_t
*defaultConfig
)
1739 ledConfig_t ledConfig
;
1740 ledConfig_t ledConfigDefault
;
1741 char ledConfigBuffer
[20];
1742 char ledConfigDefaultBuffer
[20];
1743 for (uint32_t i
= 0; i
< LED_MAX_STRIP_LENGTH
; i
++) {
1744 ledConfig
= masterConfig
.ledStripConfig
.ledConfigs
[i
];
1745 ledConfigDefault
= defaultConfig
->ledStripConfig
.ledConfigs
[i
];
1746 equalsDefault
= ledConfig
== ledConfigDefault
;
1747 generateLedConfig(&ledConfig
, ledConfigBuffer
, sizeof(ledConfigBuffer
));
1748 generateLedConfig(&ledConfigDefault
, ledConfigDefaultBuffer
, sizeof(ledConfigDefaultBuffer
));
1749 const char *format
= "led %u %s\r\n";
1750 cliDefaultPrintf(dumpMask
, equalsDefault
, format
, i
, ledConfigDefaultBuffer
);
1751 cliDumpPrintf(dumpMask
, equalsDefault
, format
, i
, ledConfigBuffer
);
1755 static void cliLed(char *cmdline
)
1760 if (isEmpty(cmdline
)) {
1761 printLed(DUMP_MASTER
, NULL
);
1765 if (i
< LED_MAX_STRIP_LENGTH
) {
1766 ptr
= nextArg(cmdline
);
1767 if (!parseLedStripConfig(i
, ptr
)) {
1768 cliShowParseError();
1771 cliShowArgumentRangeError("index", 0, LED_MAX_STRIP_LENGTH
- 1);
1776 static void printColor(uint8_t dumpMask
, master_t
*defaultConfig
)
1779 hsvColor_t
*colorDefault
;
1781 for (uint32_t i
= 0; i
< LED_CONFIGURABLE_COLOR_COUNT
; i
++) {
1782 color
= &masterConfig
.ledStripConfig
.colors
[i
];
1783 colorDefault
= &defaultConfig
->ledStripConfig
.colors
[i
];
1784 equalsDefault
= color
->h
== colorDefault
->h
1785 && color
->s
== colorDefault
->s
1786 && color
->v
== colorDefault
->v
;
1787 const char *format
= "color %u %d,%u,%u\r\n";
1788 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1794 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1803 static void cliColor(char *cmdline
)
1808 if (isEmpty(cmdline
)) {
1809 printColor(DUMP_MASTER
, NULL
);
1813 if (i
< LED_CONFIGURABLE_COLOR_COUNT
) {
1814 ptr
= nextArg(cmdline
);
1815 if (!parseColor(i
, ptr
)) {
1816 cliShowParseError();
1819 cliShowArgumentRangeError("index", 0, LED_CONFIGURABLE_COLOR_COUNT
- 1);
1824 static void printModeColor(uint8_t dumpMask
, master_t
*defaultConfig
)
1826 for (uint32_t i
= 0; i
< LED_MODE_COUNT
; i
++) {
1827 for (uint32_t j
= 0; j
< LED_DIRECTION_COUNT
; j
++) {
1828 int colorIndex
= masterConfig
.ledStripConfig
.modeColors
[i
].color
[j
];
1829 int colorIndexDefault
= defaultConfig
->ledStripConfig
.modeColors
[i
].color
[j
];
1830 const char *format
= "mode_color %u %u %u\r\n";
1831 cliDefaultPrintf(dumpMask
, colorIndex
== colorIndexDefault
, format
, i
, j
, colorIndexDefault
);
1832 cliDumpPrintf(dumpMask
, colorIndex
== colorIndexDefault
, format
, i
, j
, colorIndex
);
1836 const char *format
= "mode_color %u %u %u\r\n";
1837 for (uint32_t j
= 0; j
< LED_SPECIAL_COLOR_COUNT
; j
++) {
1838 int colorIndex
= masterConfig
.ledStripConfig
.specialColors
.color
[j
];
1839 int colorIndexDefault
= defaultConfig
->ledStripConfig
.specialColors
.color
[j
];
1840 cliDefaultPrintf(dumpMask
, colorIndex
== colorIndexDefault
, format
, LED_SPECIAL
, j
, colorIndexDefault
);
1841 cliDumpPrintf(dumpMask
, colorIndex
== colorIndexDefault
, format
, LED_SPECIAL
, j
, colorIndex
);
1844 int ledStripAuxChannel
= masterConfig
.ledStripConfig
.ledstrip_aux_channel
;
1845 int ledStripAuxChannelDefault
= defaultConfig
->ledStripConfig
.ledstrip_aux_channel
;
1846 cliDefaultPrintf(dumpMask
, ledStripAuxChannel
== ledStripAuxChannelDefault
, format
, LED_AUX_CHANNEL
, 0, ledStripAuxChannelDefault
);
1847 cliDumpPrintf(dumpMask
, ledStripAuxChannel
== ledStripAuxChannelDefault
, format
, LED_AUX_CHANNEL
, 0, ledStripAuxChannel
);
1850 static void cliModeColor(char *cmdline
)
1852 if (isEmpty(cmdline
)) {
1853 printModeColor(DUMP_MASTER
, NULL
);
1855 enum {MODE
= 0, FUNCTION
, COLOR
, ARGS_COUNT
};
1856 int args
[ARGS_COUNT
];
1858 char* ptr
= strtok(cmdline
, " ");
1859 while (ptr
&& argNo
< ARGS_COUNT
) {
1860 args
[argNo
++] = atoi(ptr
);
1861 ptr
= strtok(NULL
, " ");
1864 if (ptr
!= NULL
|| argNo
!= ARGS_COUNT
) {
1865 cliShowParseError();
1869 int modeIdx
= args
[MODE
];
1870 int funIdx
= args
[FUNCTION
];
1871 int color
= args
[COLOR
];
1872 if(!setModeColor(modeIdx
, funIdx
, color
)) {
1873 cliShowParseError();
1876 // values are validated
1877 cliPrintf("mode_color %u %u %u\r\n", modeIdx
, funIdx
, color
);
1883 static void printServo(uint8_t dumpMask
, master_t
*defaultConfig
)
1885 // print out servo settings
1886 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
1887 servoParam_t
*servoConf
= &masterConfig
.servoConf
[i
];
1888 servoParam_t
*servoConfDefault
= &defaultConfig
->servoConf
[i
];
1889 bool equalsDefault
= servoConf
->min
== servoConfDefault
->min
1890 && servoConf
->max
== servoConfDefault
->max
1891 && servoConf
->middle
== servoConfDefault
->middle
1892 && servoConf
->angleAtMin
== servoConfDefault
->angleAtMax
1893 && servoConf
->rate
== servoConfDefault
->rate
1894 && servoConf
->forwardFromChannel
== servoConfDefault
->forwardFromChannel
;
1895 const char *format
= "servo %u %d %d %d %d %d %d %d\r\n";
1896 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
1898 servoConfDefault
->min
,
1899 servoConfDefault
->max
,
1900 servoConfDefault
->middle
,
1901 servoConfDefault
->angleAtMin
,
1902 servoConfDefault
->angleAtMax
,
1903 servoConfDefault
->rate
,
1904 servoConfDefault
->forwardFromChannel
1906 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
1911 servoConf
->angleAtMin
,
1912 servoConf
->angleAtMax
,
1914 servoConf
->forwardFromChannel
1919 static void cliServo(char *cmdline
)
1921 enum { SERVO_ARGUMENT_COUNT
= 8 };
1922 int16_t arguments
[SERVO_ARGUMENT_COUNT
];
1924 servoParam_t
*servo
;
1929 if (isEmpty(cmdline
)) {
1930 printServo(DUMP_MASTER
, NULL
);
1932 int validArgumentCount
= 0;
1936 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
1938 // If command line doesn't fit the format, don't modify the config
1940 if (*ptr
== '-' || (*ptr
>= '0' && *ptr
<= '9')) {
1941 if (validArgumentCount
>= SERVO_ARGUMENT_COUNT
) {
1942 cliShowParseError();
1946 arguments
[validArgumentCount
++] = atoi(ptr
);
1950 } while (*ptr
>= '0' && *ptr
<= '9');
1951 } else if (*ptr
== ' ') {
1954 cliShowParseError();
1959 enum {INDEX
= 0, MIN
, MAX
, MIDDLE
, ANGLE_AT_MIN
, ANGLE_AT_MAX
, RATE
, FORWARD
};
1961 i
= arguments
[INDEX
];
1963 // Check we got the right number of args and the servo index is correct (don't validate the other values)
1964 if (validArgumentCount
!= SERVO_ARGUMENT_COUNT
|| i
< 0 || i
>= MAX_SUPPORTED_SERVOS
) {
1965 cliShowParseError();
1969 servo
= &masterConfig
.servoConf
[i
];
1972 arguments
[MIN
] < PWM_PULSE_MIN
|| arguments
[MIN
] > PWM_PULSE_MAX
||
1973 arguments
[MAX
] < PWM_PULSE_MIN
|| arguments
[MAX
] > PWM_PULSE_MAX
||
1974 arguments
[MIDDLE
] < arguments
[MIN
] || arguments
[MIDDLE
] > arguments
[MAX
] ||
1975 arguments
[MIN
] > arguments
[MAX
] || arguments
[MAX
] < arguments
[MIN
] ||
1976 arguments
[RATE
] < -100 || arguments
[RATE
] > 100 ||
1977 arguments
[FORWARD
] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
||
1978 arguments
[ANGLE_AT_MIN
] < 0 || arguments
[ANGLE_AT_MIN
] > 180 ||
1979 arguments
[ANGLE_AT_MAX
] < 0 || arguments
[ANGLE_AT_MAX
] > 180
1981 cliShowParseError();
1985 servo
->min
= arguments
[1];
1986 servo
->max
= arguments
[2];
1987 servo
->middle
= arguments
[3];
1988 servo
->angleAtMin
= arguments
[4];
1989 servo
->angleAtMax
= arguments
[5];
1990 servo
->rate
= arguments
[6];
1991 servo
->forwardFromChannel
= arguments
[7];
1997 static void printServoMix(uint8_t dumpMask
, master_t
*defaultConfig
)
1999 for (uint32_t i
= 0; i
< MAX_SERVO_RULES
; i
++) {
2000 servoMixer_t customServoMixer
= masterConfig
.customServoMixer
[i
];
2001 servoMixer_t customServoMixerDefault
= defaultConfig
->customServoMixer
[i
];
2002 if (customServoMixer
.rate
== 0) {
2006 bool equalsDefault
= customServoMixer
.targetChannel
== customServoMixerDefault
.targetChannel
2007 && customServoMixer
.inputSource
== customServoMixerDefault
.inputSource
2008 && customServoMixer
.rate
== customServoMixerDefault
.rate
2009 && customServoMixer
.speed
== customServoMixerDefault
.speed
2010 && customServoMixer
.min
== customServoMixerDefault
.min
2011 && customServoMixer
.max
== customServoMixerDefault
.max
2012 && customServoMixer
.box
== customServoMixerDefault
.box
;
2014 const char *format
= "smix %d %d %d %d %d %d %d %d\r\n";
2015 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
2017 customServoMixerDefault
.targetChannel
,
2018 customServoMixerDefault
.inputSource
,
2019 customServoMixerDefault
.rate
,
2020 customServoMixerDefault
.speed
,
2021 customServoMixerDefault
.min
,
2022 customServoMixerDefault
.max
,
2023 customServoMixerDefault
.box
2025 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
2027 customServoMixer
.targetChannel
,
2028 customServoMixer
.inputSource
,
2029 customServoMixer
.rate
,
2030 customServoMixer
.speed
,
2031 customServoMixer
.min
,
2032 customServoMixer
.max
,
2033 customServoMixer
.box
2039 // print servo directions
2040 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2041 servoParam_t
*servoConf
= &masterConfig
.servoConf
[i
];
2042 servoParam_t
*servoConfDefault
= &defaultConfig
->servoConf
[i
];
2043 bool equalsDefault
= servoConf
->reversedSources
== servoConfDefault
->reversedSources
;
2044 for (uint32_t channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
2045 equalsDefault
= ~(servoConf
->reversedSources
^ servoConfDefault
->reversedSources
) & (1 << channel
);
2046 const char *format
= "smix reverse %d %d r\r\n";
2047 if (servoConfDefault
->reversedSources
& (1 << channel
)) {
2048 cliDefaultPrintf(dumpMask
, equalsDefault
, format
, i
, channel
);
2050 if (servoConf
->reversedSources
& (1 << channel
)) {
2051 cliDumpPrintf(dumpMask
, equalsDefault
, format
, i
, channel
);
2057 static void cliServoMix(char *cmdline
)
2061 int args
[8], check
= 0;
2062 len
= strlen(cmdline
);
2065 printServoMix(DUMP_MASTER
, NULL
);
2066 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
2067 // erase custom mixer
2068 memset(masterConfig
.customServoMixer
, 0, sizeof(masterConfig
.customServoMixer
));
2069 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2070 masterConfig
.servoConf
[i
].reversedSources
= 0;
2072 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
2073 ptr
= nextArg(cmdline
);
2076 for (uint32_t i
= 0; ; i
++) {
2077 if (mixerNames
[i
] == NULL
) {
2078 cliPrintf("Invalid name\r\n");
2081 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
2082 servoMixerLoadMix(i
, masterConfig
.customServoMixer
);
2083 cliPrintf("Loaded %s\r\n", mixerNames
[i
]);
2089 } else if (strncasecmp(cmdline
, "reverse", 7) == 0) {
2090 enum {SERVO
= 0, INPUT
, REVERSE
, ARGS_COUNT
};
2091 ptr
= strchr(cmdline
, ' ');
2096 for (uint32_t inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
2097 cliPrintf("\ti%d", inputSource
);
2100 for (uint32_t servoIndex
= 0; servoIndex
< MAX_SUPPORTED_SERVOS
; servoIndex
++) {
2101 cliPrintf("%d", servoIndex
);
2102 for (uint32_t inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
2103 cliPrintf("\t%s ", (masterConfig
.servoConf
[servoIndex
].reversedSources
& (1 << inputSource
)) ? "r" : "n");
2109 ptr
= strtok(ptr
, " ");
2110 while (ptr
!= NULL
&& check
< ARGS_COUNT
- 1) {
2111 args
[check
++] = atoi(ptr
);
2112 ptr
= strtok(NULL
, " ");
2115 if (ptr
== NULL
|| check
!= ARGS_COUNT
- 1) {
2116 cliShowParseError();
2120 if (args
[SERVO
] >= 0 && args
[SERVO
] < MAX_SUPPORTED_SERVOS
2121 && args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
2122 && (*ptr
== 'r' || *ptr
== 'n')) {
2124 masterConfig
.servoConf
[args
[SERVO
]].reversedSources
|= 1 << args
[INPUT
];
2126 masterConfig
.servoConf
[args
[SERVO
]].reversedSources
&= ~(1 << args
[INPUT
]);
2128 cliShowParseError();
2130 cliServoMix("reverse");
2132 enum {RULE
= 0, TARGET
, INPUT
, RATE
, SPEED
, MIN
, MAX
, BOX
, ARGS_COUNT
};
2133 ptr
= strtok(cmdline
, " ");
2134 while (ptr
!= NULL
&& check
< ARGS_COUNT
) {
2135 args
[check
++] = atoi(ptr
);
2136 ptr
= strtok(NULL
, " ");
2139 if (ptr
!= NULL
|| check
!= ARGS_COUNT
) {
2140 cliShowParseError();
2144 int32_t i
= args
[RULE
];
2145 if (i
>= 0 && i
< MAX_SERVO_RULES
&&
2146 args
[TARGET
] >= 0 && args
[TARGET
] < MAX_SUPPORTED_SERVOS
&&
2147 args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
&&
2148 args
[RATE
] >= -100 && args
[RATE
] <= 100 &&
2149 args
[SPEED
] >= 0 && args
[SPEED
] <= MAX_SERVO_SPEED
&&
2150 args
[MIN
] >= 0 && args
[MIN
] <= 100 &&
2151 args
[MAX
] >= 0 && args
[MAX
] <= 100 && args
[MIN
] < args
[MAX
] &&
2152 args
[BOX
] >= 0 && args
[BOX
] <= MAX_SERVO_BOXES
) {
2153 masterConfig
.customServoMixer
[i
].targetChannel
= args
[TARGET
];
2154 masterConfig
.customServoMixer
[i
].inputSource
= args
[INPUT
];
2155 masterConfig
.customServoMixer
[i
].rate
= args
[RATE
];
2156 masterConfig
.customServoMixer
[i
].speed
= args
[SPEED
];
2157 masterConfig
.customServoMixer
[i
].min
= args
[MIN
];
2158 masterConfig
.customServoMixer
[i
].max
= args
[MAX
];
2159 masterConfig
.customServoMixer
[i
].box
= args
[BOX
];
2162 cliShowParseError();
2170 static void cliWriteBytes(const uint8_t *buffer
, int count
)
2179 static void cliSdInfo(char *cmdline
) {
2182 cliPrint("SD card: ");
2184 if (!sdcard_isInserted()) {
2185 cliPrint("None inserted\r\n");
2189 if (!sdcard_isInitialized()) {
2190 cliPrint("Startup failed\r\n");
2194 const sdcardMetadata_t
*metadata
= sdcard_getMetadata();
2196 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
2197 metadata
->manufacturerID
,
2198 metadata
->numBlocks
/ 2, /* One block is half a kB */
2199 metadata
->productionMonth
,
2200 metadata
->productionYear
,
2201 metadata
->productRevisionMajor
,
2202 metadata
->productRevisionMinor
2205 cliWriteBytes((uint8_t*)metadata
->productName
, sizeof(metadata
->productName
));
2207 cliPrint("'\r\n" "Filesystem: ");
2209 switch (afatfs_getFilesystemState()) {
2210 case AFATFS_FILESYSTEM_STATE_READY
:
2213 case AFATFS_FILESYSTEM_STATE_INITIALIZATION
:
2214 cliPrint("Initializing");
2216 case AFATFS_FILESYSTEM_STATE_UNKNOWN
:
2217 case AFATFS_FILESYSTEM_STATE_FATAL
:
2220 switch (afatfs_getLastError()) {
2221 case AFATFS_ERROR_BAD_MBR
:
2222 cliPrint(" - no FAT MBR partitions");
2224 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER
:
2225 cliPrint(" - bad FAT header");
2227 case AFATFS_ERROR_GENERIC
:
2228 case AFATFS_ERROR_NONE
:
2229 ; // Nothing more detailed to print
2241 static void cliFlashInfo(char *cmdline
)
2243 const flashGeometry_t
*layout
= flashfsGetGeometry();
2247 cliPrintf("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u\r\n",
2248 layout
->sectors
, layout
->sectorSize
, layout
->pagesPerSector
, layout
->pageSize
, layout
->totalSize
, flashfsGetOffset());
2251 static void cliFlashErase(char *cmdline
)
2255 cliPrintf("Erasing...\r\n");
2256 flashfsEraseCompletely();
2258 while (!flashfsIsReady()) {
2262 cliPrintf("Done.\r\n");
2265 #ifdef USE_FLASH_TOOLS
2267 static void cliFlashWrite(char *cmdline
)
2269 uint32_t address
= atoi(cmdline
);
2270 char *text
= strchr(cmdline
, ' ');
2273 cliShowParseError();
2275 flashfsSeekAbs(address
);
2276 flashfsWrite((uint8_t*)text
, strlen(text
), true);
2279 cliPrintf("Wrote %u bytes at %u.\r\n", strlen(text
), address
);
2283 static void cliFlashRead(char *cmdline
)
2285 uint32_t address
= atoi(cmdline
);
2290 char *nextArg
= strchr(cmdline
, ' ');
2293 cliShowParseError();
2295 length
= atoi(nextArg
);
2297 cliPrintf("Reading %u bytes at %u:\r\n", length
, address
);
2299 while (length
> 0) {
2300 int bytesRead
= flashfsReadAbs(address
, buffer
, length
< sizeof(buffer
) ? length
: sizeof(buffer
));
2302 for (int i
= 0; i
< bytesRead
; i
++) {
2303 cliWrite(buffer
[i
]);
2306 length
-= bytesRead
;
2307 address
+= bytesRead
;
2309 if (bytesRead
== 0) {
2310 //Assume we reached the end of the volume or something fatal happened
2322 static void printVtx(uint8_t dumpMask
, master_t
*defaultConfig
)
2324 // print out vtx channel settings
2325 vtxChannelActivationCondition_t
*cac
;
2326 vtxChannelActivationCondition_t
*cacDefault
;
2328 for (uint32_t i
= 0; i
< MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
; i
++) {
2329 cac
= &masterConfig
.vtxChannelActivationConditions
[i
];
2330 cacDefault
= &defaultConfig
->vtxChannelActivationConditions
[i
];
2331 equalsDefault
= cac
->auxChannelIndex
== cacDefault
->auxChannelIndex
2332 && cac
->band
== cacDefault
->band
2333 && cac
->channel
== cacDefault
->channel
2334 && cac
->range
.startStep
== cacDefault
->range
.startStep
2335 && cac
->range
.endStep
== cacDefault
->range
.endStep
;
2336 const char *format
= "vtx %u %u %u %u %u %u\r\n";
2337 cliDefaultPrintf(dumpMask
, equalsDefault
, format
,
2339 cacDefault
->auxChannelIndex
,
2341 cacDefault
->channel
,
2342 MODE_STEP_TO_CHANNEL_VALUE(cacDefault
->range
.startStep
),
2343 MODE_STEP_TO_CHANNEL_VALUE(cacDefault
->range
.endStep
)
2345 cliDumpPrintf(dumpMask
, equalsDefault
, format
,
2347 cac
->auxChannelIndex
,
2350 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.startStep
),
2351 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.endStep
)
2356 static void cliVtx(char *cmdline
)
2361 if (isEmpty(cmdline
)) {
2362 printVtx(DUMP_MASTER
, NULL
);
2366 if (i
< MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
) {
2367 vtxChannelActivationCondition_t
*cac
= &masterConfig
.vtxChannelActivationConditions
[i
];
2368 uint8_t validArgumentCount
= 0;
2372 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
2373 cac
->auxChannelIndex
= val
;
2374 validArgumentCount
++;
2380 if (val
>= VTX_BAND_MIN
&& val
<= VTX_BAND_MAX
) {
2382 validArgumentCount
++;
2388 if (val
>= VTX_CHANNEL_MIN
&& val
<= VTX_CHANNEL_MAX
) {
2390 validArgumentCount
++;
2393 ptr
= processChannelRangeArgs(ptr
, &cac
->range
, &validArgumentCount
);
2395 if (validArgumentCount
!= 5) {
2396 memset(cac
, 0, sizeof(vtxChannelActivationCondition_t
));
2399 cliShowArgumentRangeError("index", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
- 1);
2405 static void printName(uint8_t dumpMask
)
2407 bool equalsDefault
= strlen(masterConfig
.name
) == 0;
2408 cliDumpPrintf(dumpMask
, equalsDefault
, "name %s\r\n", equalsDefault
? emptyName
: masterConfig
.name
);
2411 static void cliName(char *cmdline
)
2413 uint32_t len
= strlen(cmdline
);
2415 memset(masterConfig
.name
, 0, ARRAYLEN(masterConfig
.name
));
2416 if (strncmp(cmdline
, emptyName
, len
)) {
2417 strncpy(masterConfig
.name
, cmdline
, MIN(len
, MAX_NAME_LENGTH
));
2420 printName(DUMP_MASTER
);
2423 static void printFeature(uint8_t dumpMask
, master_t
*defaultConfig
)
2425 uint32_t mask
= featureMask();
2426 uint32_t defaultMask
= defaultConfig
->enabledFeatures
;
2427 for (uint32_t i
= 0; ; i
++) { // disable all feature first
2428 if (featureNames
[i
] == NULL
)
2430 const char *format
= "feature -%s\r\n";
2431 cliDefaultPrintf(dumpMask
, (defaultMask
| ~mask
) & (1 << i
), format
, featureNames
[i
]);
2432 cliDumpPrintf(dumpMask
, (~defaultMask
| mask
) & (1 << i
), format
, featureNames
[i
]);
2434 for (uint32_t i
= 0; ; i
++) { // reenable what we want.
2435 if (featureNames
[i
] == NULL
)
2437 const char *format
= "feature %s\r\n";
2438 if (defaultMask
& (1 << i
)) {
2439 cliDefaultPrintf(dumpMask
, (~defaultMask
| mask
) & (1 << i
), format
, featureNames
[i
]);
2441 if (mask
& (1 << i
)) {
2442 cliDumpPrintf(dumpMask
, (defaultMask
| ~mask
) & (1 << i
), format
, featureNames
[i
]);
2447 static void cliFeature(char *cmdline
)
2449 uint32_t len
= strlen(cmdline
);
2450 uint32_t mask
= featureMask();
2453 cliPrint("Enabled: ");
2454 for (uint32_t i
= 0; ; i
++) {
2455 if (featureNames
[i
] == NULL
)
2457 if (mask
& (1 << i
))
2458 cliPrintf("%s ", featureNames
[i
]);
2461 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
2462 cliPrint("Available: ");
2463 for (uint32_t i
= 0; ; i
++) {
2464 if (featureNames
[i
] == NULL
)
2466 cliPrintf("%s ", featureNames
[i
]);
2471 bool remove
= false;
2472 if (cmdline
[0] == '-') {
2475 cmdline
++; // skip over -
2479 for (uint32_t i
= 0; ; i
++) {
2480 if (featureNames
[i
] == NULL
) {
2481 cliPrint("Invalid name\r\n");
2485 if (strncasecmp(cmdline
, featureNames
[i
], len
) == 0) {
2489 if (mask
& FEATURE_GPS
) {
2490 cliPrint("unavailable\r\n");
2495 if (mask
& FEATURE_SONAR
) {
2496 cliPrint("unavailable\r\n");
2502 cliPrint("Disabled");
2505 cliPrint("Enabled");
2507 cliPrintf(" %s\r\n", featureNames
[i
]);
2515 static void printBeeper(uint8_t dumpMask
, master_t
*defaultConfig
)
2517 uint8_t beeperCount
= beeperTableEntryCount();
2518 uint32_t mask
= getBeeperOffMask();
2519 uint32_t defaultMask
= defaultConfig
->beeper_off_flags
;
2520 for (int32_t i
= 0; i
< beeperCount
- 2; i
++) {
2521 const char *formatOff
= "beeper -%s\r\n";
2522 const char *formatOn
= "beeper %s\r\n";
2523 cliDefaultPrintf(dumpMask
, ~(mask
^ defaultMask
) & (1 << i
), mask
& (1 << i
) ? formatOn
: formatOff
, beeperNameForTableIndex(i
));
2524 cliDumpPrintf(dumpMask
, ~(mask
^ defaultMask
) & (1 << i
), mask
& (1 << i
) ? formatOff
: formatOn
, beeperNameForTableIndex(i
));
2528 static void cliBeeper(char *cmdline
)
2530 uint32_t len
= strlen(cmdline
);
2531 uint8_t beeperCount
= beeperTableEntryCount();
2532 uint32_t mask
= getBeeperOffMask();
2535 cliPrintf("Disabled:");
2536 for (int32_t i
= 0; ; i
++) {
2537 if (i
== beeperCount
- 2){
2542 if (mask
& (1 << i
))
2543 cliPrintf(" %s", beeperNameForTableIndex(i
));
2546 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
2547 cliPrint("Available:");
2548 for (uint32_t i
= 0; i
< beeperCount
; i
++)
2549 cliPrintf(" %s", beeperNameForTableIndex(i
));
2553 bool remove
= false;
2554 if (cmdline
[0] == '-') {
2555 remove
= true; // this is for beeper OFF condition
2560 for (uint32_t i
= 0; ; i
++) {
2561 if (i
== beeperCount
) {
2562 cliPrint("Invalid name\r\n");
2565 if (strncasecmp(cmdline
, beeperNameForTableIndex(i
), len
) == 0) {
2566 if (remove
) { // beeper off
2567 if (i
== BEEPER_ALL
-1)
2568 beeperOffSetAll(beeperCount
-2);
2570 if (i
== BEEPER_PREFERENCE
-1)
2571 setBeeperOffMask(getPreferredBeeperOffMask());
2576 cliPrint("Disabled");
2579 if (i
== BEEPER_ALL
-1)
2580 beeperOffClearAll();
2582 if (i
== BEEPER_PREFERENCE
-1)
2583 setPreferredBeeperOffMask(getBeeperOffMask());
2586 beeperOffClear(mask
);
2588 cliPrint("Enabled");
2590 cliPrintf(" %s\r\n", beeperNameForTableIndex(i
));
2598 static void printMap(uint8_t dumpMask
, master_t
*defaultConfig
)
2600 bool equalsDefault
= true;
2602 char bufDefault
[16];
2604 for (i
= 0; i
< MAX_MAPPABLE_RX_INPUTS
; i
++) {
2605 buf
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
2606 bufDefault
[defaultConfig
->rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
2607 equalsDefault
= equalsDefault
&& (masterConfig
.rxConfig
.rcmap
[i
] == defaultConfig
->rxConfig
.rcmap
[i
]);
2611 const char *formatMap
= "map %s\r\n";
2612 cliDefaultPrintf(dumpMask
, equalsDefault
, formatMap
, bufDefault
);
2613 cliDumpPrintf(dumpMask
, equalsDefault
, formatMap
, buf
);
2616 static void cliMap(char *cmdline
)
2621 len
= strlen(cmdline
);
2625 for (uint32_t i
= 0; i
< 8; i
++)
2626 cmdline
[i
] = toupper((unsigned char)cmdline
[i
]);
2627 for (uint32_t i
= 0; i
< 8; i
++) {
2628 if (strchr(rcChannelLetters
, cmdline
[i
]) && !strchr(cmdline
+ i
+ 1, cmdline
[i
]))
2630 cliShowParseError();
2633 parseRcChannels(cmdline
, &masterConfig
.rxConfig
);
2637 for (i
= 0; i
< 8; i
++)
2638 out
[masterConfig
.rxConfig
.rcmap
[i
]] = rcChannelLetters
[i
];
2640 cliPrintf("%s\r\n", out
);
2643 void *getValuePointer(const clivalue_t
*value
)
2645 void *ptr
= value
->ptr
;
2647 if ((value
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
2648 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
2651 if ((value
->type
& VALUE_SECTION_MASK
) == PROFILE_RATE_VALUE
) {
2652 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
2658 static void *getDefaultPointer(void *valuePointer
, master_t
*defaultConfig
)
2660 return ((uint8_t *)valuePointer
) - (uint32_t)&masterConfig
+ (uint32_t)defaultConfig
;
2663 static bool valueEqualsDefault(const clivalue_t
*value
, master_t
*defaultConfig
)
2665 void *ptr
= getValuePointer(value
);
2667 void *ptrDefault
= getDefaultPointer(ptr
, defaultConfig
);
2669 bool result
= false;
2670 switch (value
->type
& VALUE_TYPE_MASK
) {
2672 result
= *(uint8_t *)ptr
== *(uint8_t *)ptrDefault
;
2676 result
= *(int8_t *)ptr
== *(int8_t *)ptrDefault
;
2680 result
= *(uint16_t *)ptr
== *(uint16_t *)ptrDefault
;
2684 result
= *(int16_t *)ptr
== *(int16_t *)ptrDefault
;
2688 result
= *(uint32_t *)ptr
== *(uint32_t *)ptrDefault
;
2692 result
= *(float *)ptr
== *(float *)ptrDefault
;
2698 static void dumpValues(uint16_t valueSection
, uint8_t dumpMask
, master_t
*defaultConfig
)
2700 const clivalue_t
*value
;
2701 for (uint32_t i
= 0; i
< VALUE_COUNT
; i
++) {
2702 value
= &valueTable
[i
];
2704 if ((value
->type
& VALUE_SECTION_MASK
) != valueSection
) {
2708 const char *format
= "set %s = ";
2709 if (cliDefaultPrintf(dumpMask
, valueEqualsDefault(value
, defaultConfig
), format
, valueTable
[i
].name
)) {
2710 cliPrintVarDefault(value
, 0, defaultConfig
);
2713 if (cliDumpPrintf(dumpMask
, valueEqualsDefault(value
, defaultConfig
), format
, valueTable
[i
].name
)) {
2714 cliPrintVar(value
, 0);
2720 static void cliDump(char *cmdline
)
2722 printConfig(cmdline
, false);
2725 static void cliDiff(char *cmdline
)
2727 printConfig(cmdline
, true);
2730 char *checkCommand(char *cmdLine
, const char *command
)
2732 if(!strncasecmp(cmdLine
, command
, strlen(command
)) // command names match
2733 && !isalnum((unsigned)cmdLine
[strlen(command
)])) { // next characted in bufffer is not alphanumeric (command is correctly terminated)
2734 return cmdLine
+ strlen(command
) + 1;
2740 static void printConfig(char *cmdline
, bool doDiff
)
2742 uint8_t dumpMask
= DUMP_MASTER
;
2744 if ((options
= checkCommand(cmdline
, "master"))) {
2745 dumpMask
= DUMP_MASTER
; // only
2746 } else if ((options
= checkCommand(cmdline
, "profile"))) {
2747 dumpMask
= DUMP_PROFILE
; // only
2748 } else if ((options
= checkCommand(cmdline
, "rates"))) {
2749 dumpMask
= DUMP_RATES
; // only
2750 } else if ((options
= checkCommand(cmdline
, "all"))) {
2751 dumpMask
= DUMP_ALL
; // all profiles and rates
2756 static master_t defaultConfig
;
2758 dumpMask
= dumpMask
| DO_DIFF
;
2761 createDefaultConfig(&defaultConfig
);
2763 if (checkCommand(options
, "showdefaults")) {
2764 dumpMask
= dumpMask
| SHOW_DEFAULTS
; // add default values as comments for changed values
2767 if ((dumpMask
& DUMP_MASTER
) || (dumpMask
& DUMP_ALL
)) {
2768 #ifndef CLI_MINIMAL_VERBOSITY
2769 cliPrint("\r\n# version\r\n");
2773 #ifndef CLI_MINIMAL_VERBOSITY
2774 if ((dumpMask
& (DUMP_ALL
| DO_DIFF
)) == (DUMP_ALL
| DO_DIFF
)) {
2775 cliPrint("\r\n# reset configuration to default settings\r\ndefaults\r\n");
2778 cliPrint("\r\n# name\r\n");
2780 printName(dumpMask
);
2782 #ifndef CLI_MINIMAL_VERBOSITY
2783 cliPrint("\r\n# resources\r\n");
2785 printResource(dumpMask
, &defaultConfig
);
2787 #ifndef USE_QUAD_MIXER_ONLY
2788 #ifndef CLI_MINIMAL_VERBOSITY
2789 cliPrint("\r\n# mixer\r\n");
2791 const bool equalsDefault
= masterConfig
.mixerConfig
.mixerMode
== defaultConfig
.mixerConfig
.mixerMode
;
2792 const char *formatMixer
= "mixer %s\r\n";
2793 cliDefaultPrintf(dumpMask
, equalsDefault
, formatMixer
, mixerNames
[defaultConfig
.mixerConfig
.mixerMode
- 1]);
2794 cliDumpPrintf(dumpMask
, equalsDefault
, formatMixer
, mixerNames
[masterConfig
.mixerConfig
.mixerMode
- 1]);
2796 cliDumpPrintf(dumpMask
, masterConfig
.customMotorMixer
[0].throttle
== 0.0f
, "\r\nmmix reset\r\n\r\n");
2798 printMotorMix(dumpMask
, &defaultConfig
);
2801 #ifndef CLI_MINIMAL_VERBOSITY
2802 cliPrint("\r\n# servo\r\n");
2804 printServo(dumpMask
, &defaultConfig
);
2806 #ifndef CLI_MINIMAL_VERBOSITY
2807 cliPrint("\r\n# servo mix\r\n");
2809 // print custom servo mixer if exists
2810 cliDumpPrintf(dumpMask
, masterConfig
.customServoMixer
[0].rate
== 0, "smix reset\r\n\r\n");
2811 printServoMix(dumpMask
, &defaultConfig
);
2815 #ifndef CLI_MINIMAL_VERBOSITY
2816 cliPrint("\r\n# feature\r\n");
2818 printFeature(dumpMask
, &defaultConfig
);
2821 #ifndef CLI_MINIMAL_VERBOSITY
2822 cliPrint("\r\n# beeper\r\n");
2824 printBeeper(dumpMask
, &defaultConfig
);
2827 #ifndef CLI_MINIMAL_VERBOSITY
2828 cliPrint("\r\n# map\r\n");
2830 printMap(dumpMask
, &defaultConfig
);
2832 #ifndef CLI_MINIMAL_VERBOSITY
2833 cliPrint("\r\n# serial\r\n");
2835 printSerial(dumpMask
, &defaultConfig
);
2838 #ifndef CLI_MINIMAL_VERBOSITY
2839 cliPrint("\r\n# led\r\n");
2841 printLed(dumpMask
, &defaultConfig
);
2843 #ifndef CLI_MINIMAL_VERBOSITY
2844 cliPrint("\r\n# color\r\n");
2846 printColor(dumpMask
, &defaultConfig
);
2848 #ifndef CLI_MINIMAL_VERBOSITY
2849 cliPrint("\r\n# mode_color\r\n");
2851 printModeColor(dumpMask
, &defaultConfig
);
2854 #ifndef CLI_MINIMAL_VERBOSITY
2855 cliPrint("\r\n# aux\r\n");
2857 printAux(dumpMask
, &defaultConfig
);
2859 #ifndef CLI_MINIMAL_VERBOSITY
2860 cliPrint("\r\n# adjrange\r\n");
2862 printAdjustmentRange(dumpMask
, &defaultConfig
);
2864 #ifndef CLI_MINIMAL_VERBOSITY
2865 cliPrint("\r\n# rxrange\r\n");
2867 printRxRange(dumpMask
, &defaultConfig
);
2870 #ifndef CLI_MINIMAL_VERBOSITY
2871 cliPrint("\r\n# vtx\r\n");
2873 printVtx(dumpMask
, &defaultConfig
);
2876 #ifndef CLI_MINIMAL_VERBOSITY
2877 cliPrint("\r\n# rxfail\r\n");
2879 printRxFail(dumpMask
, &defaultConfig
);
2881 #ifndef CLI_MINIMAL_VERBOSITY
2882 cliPrint("\r\n# master\r\n");
2884 dumpValues(MASTER_VALUE
, dumpMask
, &defaultConfig
);
2886 if (dumpMask
& DUMP_ALL
) {
2887 uint8_t activeProfile
= masterConfig
.current_profile_index
;
2888 for (uint32_t profileCount
=0; profileCount
<MAX_PROFILE_COUNT
;profileCount
++) {
2889 cliDumpProfile(profileCount
, dumpMask
, &defaultConfig
);
2891 uint8_t currentRateIndex
= currentProfile
->activeRateProfile
;
2892 for (uint32_t rateCount
= 0; rateCount
<MAX_RATEPROFILES
; rateCount
++) {
2893 cliDumpRateProfile(rateCount
, dumpMask
, &defaultConfig
);
2896 changeControlRateProfile(currentRateIndex
);
2897 #ifndef CLI_MINIMAL_VERBOSITY
2898 cliPrint("\r\n# restore original rateprofile selection\r\n");
2903 changeProfile(activeProfile
);
2904 #ifndef CLI_MINIMAL_VERBOSITY
2905 cliPrint("\r\n# restore original profile selection\r\n");
2908 cliPrint("\r\n# save configuration\r\nsave\r\n");
2911 cliDumpProfile(masterConfig
.current_profile_index
, dumpMask
, &defaultConfig
);
2912 cliDumpRateProfile(currentProfile
->activeRateProfile
, dumpMask
, &defaultConfig
);
2916 if (dumpMask
& DUMP_PROFILE
) {
2917 cliDumpProfile(masterConfig
.current_profile_index
, dumpMask
, &defaultConfig
);
2920 if (dumpMask
& DUMP_RATES
) {
2921 cliDumpRateProfile(currentProfile
->activeRateProfile
, dumpMask
, &defaultConfig
);
2925 static void cliDumpProfile(uint8_t profileIndex
, uint8_t dumpMask
, master_t
*defaultConfig
)
2927 if (profileIndex
>= MAX_PROFILE_COUNT
) {
2931 changeProfile(profileIndex
);
2932 #ifndef CLI_MINIMAL_VERBOSITY
2933 cliPrint("\r\n# profile\r\n");
2937 dumpValues(PROFILE_VALUE
, dumpMask
, defaultConfig
);
2941 static void cliDumpRateProfile(uint8_t rateProfileIndex
, uint8_t dumpMask
, master_t
*defaultConfig
)
2943 if (rateProfileIndex
>= MAX_RATEPROFILES
) {
2947 changeControlRateProfile(rateProfileIndex
);
2948 #ifndef CLI_MINIMAL_VERBOSITY
2949 cliPrint("\r\n# rateprofile\r\n");
2953 dumpValues(PROFILE_RATE_VALUE
, dumpMask
, defaultConfig
);
2956 void cliEnter(serialPort_t
*serialPort
)
2959 cliPort
= serialPort
;
2960 setPrintfSerialPort(cliPort
);
2961 cliWriter
= bufWriterInit(cliWriteBuffer
, sizeof(cliWriteBuffer
),
2962 (bufWrite_t
)serialWriteBufShim
, serialPort
);
2964 #ifndef CLI_MINIMAL_VERBOSITY
2965 cliPrint("\r\nEntering CLI Mode, type 'exit' to return, or 'help'\r\n");
2968 ENABLE_ARMING_FLAG(PREVENT_ARMING
);
2971 static void cliExit(char *cmdline
)
2975 #ifndef CLI_MINIMAL_VERBOSITY
2976 cliPrint("\r\nLeaving CLI mode, unsaved changes lost.\r\n");
2978 bufWriterFlush(cliWriter
);
2983 // incase a motor was left running during motortest, clear it here
2984 mixerResetDisarmedMotors();
2991 static void cliGpsPassthrough(char *cmdline
)
2995 gpsEnablePassthrough(cliPort
);
2999 #ifdef USE_ESCSERIAL
3000 static void cliEscPassthrough(char *cmdline
)
3008 if (isEmpty(cmdline
)) {
3009 cliShowParseError();
3013 pch
= strtok_r(cmdline
, " ", &saveptr
);
3014 while (pch
!= NULL
) {
3017 if(strncasecmp(pch
, "sk", strlen(pch
)) == 0)
3021 else if(strncasecmp(pch
, "bl", strlen(pch
)) == 0)
3025 else if(strncasecmp(pch
, "ki", strlen(pch
)) == 0)
3029 else if(strncasecmp(pch
, "cc", strlen(pch
)) == 0)
3035 cliShowParseError();
3041 if(mode
== 2 && index
== 255)
3043 printf("passthru on all pwm outputs enabled\r\n");
3046 if ((index
>= 0) && (index
< USABLE_TIMER_CHANNEL_COUNT
)) {
3047 printf("passthru at pwm output %d enabled\r\n", index
);
3050 printf("invalid pwm output, valid range: 1 to %d\r\n", USABLE_TIMER_CHANNEL_COUNT
);
3057 pch
= strtok_r(NULL
, " ", &saveptr
);
3059 escEnablePassthrough(cliPort
,index
,mode
);
3063 static void cliHelp(char *cmdline
)
3067 for (uint32_t i
= 0; i
< CMD_COUNT
; i
++) {
3068 cliPrint(cmdTable
[i
].name
);
3069 #ifndef SKIP_CLI_COMMAND_HELP
3070 if (cmdTable
[i
].description
) {
3071 cliPrintf(" - %s", cmdTable
[i
].description
);
3073 if (cmdTable
[i
].args
) {
3074 cliPrintf("\r\n\t%s", cmdTable
[i
].args
);
3081 #ifndef USE_QUAD_MIXER_ONLY
3082 static void cliMixer(char *cmdline
)
3086 len
= strlen(cmdline
);
3089 cliPrintf("Mixer: %s\r\n", mixerNames
[masterConfig
.mixerConfig
.mixerMode
- 1]);
3091 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
3092 cliPrint("Available mixers: ");
3093 for (uint32_t i
= 0; ; i
++) {
3094 if (mixerNames
[i
] == NULL
)
3096 cliPrintf("%s ", mixerNames
[i
]);
3102 for (uint32_t i
= 0; ; i
++) {
3103 if (mixerNames
[i
] == NULL
) {
3104 cliPrint("Invalid name\r\n");
3107 if (strncasecmp(cmdline
, mixerNames
[i
], len
) == 0) {
3108 masterConfig
.mixerConfig
.mixerMode
= i
+ 1;
3117 static void cliMotor(char *cmdline
)
3119 int motor_index
= 0;
3120 int motor_value
= 0;
3125 if (isEmpty(cmdline
)) {
3126 cliShowParseError();
3130 pch
= strtok_r(cmdline
, " ", &saveptr
);
3131 while (pch
!= NULL
) {
3134 motor_index
= atoi(pch
);
3137 motor_value
= atoi(pch
);
3141 pch
= strtok_r(NULL
, " ", &saveptr
);
3144 if (motor_index
< 0 || motor_index
>= MAX_SUPPORTED_MOTORS
) {
3145 cliShowArgumentRangeError("index", 0, MAX_SUPPORTED_MOTORS
- 1);
3150 if (motor_value
< PWM_RANGE_MIN
|| motor_value
> PWM_RANGE_MAX
) {
3151 cliShowArgumentRangeError("value", 1000, 2000);
3154 motor_disarmed
[motor_index
] = convertExternalToMotor(motor_value
);
3158 cliPrintf("motor %d: %d\r\n", motor_index
, convertMotorToExternal(motor_disarmed
[motor_index
]));
3161 #if (FLASH_SIZE > 128)
3162 static void cliPlaySound(char *cmdline
)
3166 static int lastSoundIdx
= -1;
3168 if (isEmpty(cmdline
)) {
3169 i
= lastSoundIdx
+ 1; //next sound index
3170 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
3171 while (true) { //no name for index; try next one
3172 if (++i
>= beeperTableEntryCount())
3173 i
= 0; //if end then wrap around to first entry
3174 if ((name
=beeperNameForTableIndex(i
)) != NULL
)
3175 break; //if name OK then play sound below
3176 if (i
== lastSoundIdx
+ 1) { //prevent infinite loop
3177 cliPrintf("Error playing sound\r\n");
3182 } else { //index value was given
3184 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
3185 cliPrintf("No sound for index %d\r\n", i
);
3191 cliPrintf("Playing sound %d: %s\r\n", i
, name
);
3192 beeper(beeperModeForTableIndex(i
));
3196 static void cliProfile(char *cmdline
)
3200 if (isEmpty(cmdline
)) {
3201 cliPrintf("profile %d\r\n", getCurrentProfile());
3205 if (i
>= 0 && i
< MAX_PROFILE_COUNT
) {
3206 masterConfig
.current_profile_index
= i
;
3214 static void cliRateProfile(char *cmdline
)
3218 if (isEmpty(cmdline
)) {
3219 cliPrintf("rateprofile %d\r\n", getCurrentControlRateProfile());
3223 if (i
>= 0 && i
< MAX_RATEPROFILES
) {
3224 changeControlRateProfile(i
);
3230 static void cliReboot(void)
3235 static void cliRebootEx(bool bootLoader
)
3237 cliPrint("\r\nRebooting");
3238 bufWriterFlush(cliWriter
);
3239 waitForSerialPortToFinishTransmitting(cliPort
);
3242 systemResetToBootloader();
3248 static void cliSave(char *cmdline
)
3257 static void cliDefaults(char *cmdline
)
3261 cliPrint("Resetting to defaults");
3266 static void cliPrint(const char *str
)
3269 bufWriterAppend(cliWriter
, *str
++);
3273 static void cliPutp(void *p
, char ch
)
3275 bufWriterAppend(p
, ch
);
3278 static bool cliDumpPrintf(uint8_t dumpMask
, bool equalsDefault
, const char *format
, ...)
3280 if (!((dumpMask
& DO_DIFF
) && equalsDefault
)) {
3282 va_start(va
, format
);
3283 tfp_format(cliWriter
, cliPutp
, format
, va
);
3292 static bool cliDefaultPrintf(uint8_t dumpMask
, bool equalsDefault
, const char *format
, ...)
3294 if ((dumpMask
& SHOW_DEFAULTS
) && !equalsDefault
) {
3298 va_start(va
, format
);
3299 tfp_format(cliWriter
, cliPutp
, format
, va
);
3308 static void cliPrintf(const char *fmt
, ...)
3312 tfp_format(cliWriter
, cliPutp
, fmt
, va
);
3316 static void cliWrite(uint8_t ch
)
3318 bufWriterAppend(cliWriter
, ch
);
3321 static void printValuePointer(const clivalue_t
*var
, void *valuePointer
, uint32_t full
)
3326 switch (var
->type
& VALUE_TYPE_MASK
) {
3328 value
= *(uint8_t *)valuePointer
;
3332 value
= *(int8_t *)valuePointer
;
3336 value
= *(uint16_t *)valuePointer
;
3340 value
= *(int16_t *)valuePointer
;
3344 value
= *(uint32_t *)valuePointer
;
3348 cliPrintf("%s", ftoa(*(float *)valuePointer
, buf
));
3349 if (full
&& (var
->type
& VALUE_MODE_MASK
) == MODE_DIRECT
) {
3350 cliPrintf(" %s", ftoa((float)var
->config
.minmax
.min
, buf
));
3351 cliPrintf(" %s", ftoa((float)var
->config
.minmax
.max
, buf
));
3353 return; // return from case for float only
3356 switch(var
->type
& VALUE_MODE_MASK
) {
3358 cliPrintf("%d", value
);
3360 cliPrintf(" %d %d", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
3364 cliPrintf(lookupTables
[var
->config
.lookup
.tableIndex
].values
[value
]);
3369 static void cliPrintVar(const clivalue_t
*var
, uint32_t full
)
3371 void *ptr
= getValuePointer(var
);
3373 printValuePointer(var
, ptr
, full
);
3376 static void cliPrintVarDefault(const clivalue_t
*var
, uint32_t full
, master_t
*defaultConfig
)
3378 void *ptr
= getValuePointer(var
);
3380 void *defaultPtr
= getDefaultPointer(ptr
, defaultConfig
);
3382 printValuePointer(var
, defaultPtr
, full
);
3385 static void cliPrintVarRange(const clivalue_t
*var
)
3387 switch (var
->type
& VALUE_MODE_MASK
) {
3388 case (MODE_DIRECT
): {
3389 cliPrintf("Allowed range: %d - %d\r\n", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
3392 case (MODE_LOOKUP
): {
3393 const lookupTableEntry_t
*tableEntry
= &lookupTables
[var
->config
.lookup
.tableIndex
];
3394 cliPrint("Allowed values:");
3395 for (uint32_t i
= 0; i
< tableEntry
->valueCount
; i
++) {
3398 cliPrintf(" %s", tableEntry
->values
[i
]);
3406 static void cliSetVar(const clivalue_t
*var
, const int_float_value_t value
)
3408 void *ptr
= var
->ptr
;
3409 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_VALUE
) {
3410 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
);
3412 if ((var
->type
& VALUE_SECTION_MASK
) == PROFILE_RATE_VALUE
) {
3413 ptr
= ((uint8_t *)ptr
) + (sizeof(profile_t
) * masterConfig
.current_profile_index
) + (sizeof(controlRateConfig_t
) * getCurrentControlRateProfile());
3416 switch (var
->type
& VALUE_TYPE_MASK
) {
3419 *(int8_t *)ptr
= value
.int_value
;
3424 *(int16_t *)ptr
= value
.int_value
;
3428 *(uint32_t *)ptr
= value
.int_value
;
3432 *(float *)ptr
= (float)value
.float_value
;
3437 static void cliSet(char *cmdline
)
3440 const clivalue_t
*val
;
3443 len
= strlen(cmdline
);
3445 if (len
== 0 || (len
== 1 && cmdline
[0] == '*')) {
3446 cliPrint("Current settings: \r\n");
3447 for (uint32_t i
= 0; i
< VALUE_COUNT
; i
++) {
3448 val
= &valueTable
[i
];
3449 cliPrintf("%s = ", valueTable
[i
].name
);
3450 cliPrintVar(val
, len
); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
3453 } else if ((eqptr
= strstr(cmdline
, "=")) != NULL
) {
3456 char *lastNonSpaceCharacter
= eqptr
;
3457 while (*(lastNonSpaceCharacter
- 1) == ' ') {
3458 lastNonSpaceCharacter
--;
3460 uint8_t variableNameLength
= lastNonSpaceCharacter
- cmdline
;
3462 // skip the '=' and any ' ' characters
3464 while (*(eqptr
) == ' ') {
3468 for (uint32_t i
= 0; i
< VALUE_COUNT
; i
++) {
3469 val
= &valueTable
[i
];
3470 // ensure exact match when setting to prevent setting variables with shorter names
3471 if (strncasecmp(cmdline
, valueTable
[i
].name
, strlen(valueTable
[i
].name
)) == 0 && variableNameLength
== strlen(valueTable
[i
].name
)) {
3473 bool changeValue
= false;
3474 int_float_value_t tmp
= { 0 };
3475 switch (valueTable
[i
].type
& VALUE_MODE_MASK
) {
3480 value
= atoi(eqptr
);
3481 valuef
= fastA2F(eqptr
);
3483 if (valuef
>= valueTable
[i
].config
.minmax
.min
&& valuef
<= valueTable
[i
].config
.minmax
.max
) { // note: compare float value
3485 if ((valueTable
[i
].type
& VALUE_TYPE_MASK
) == VAR_FLOAT
)
3486 tmp
.float_value
= valuef
;
3488 tmp
.int_value
= value
;
3495 const lookupTableEntry_t
*tableEntry
= &lookupTables
[valueTable
[i
].config
.lookup
.tableIndex
];
3496 bool matched
= false;
3497 for (uint32_t tableValueIndex
= 0; tableValueIndex
< tableEntry
->valueCount
&& !matched
; tableValueIndex
++) {
3498 matched
= strcasecmp(tableEntry
->values
[tableValueIndex
], eqptr
) == 0;
3501 tmp
.int_value
= tableValueIndex
;
3510 cliSetVar(val
, tmp
);
3512 cliPrintf("%s set to ", valueTable
[i
].name
);
3513 cliPrintVar(val
, 0);
3515 cliPrint("Invalid value\r\n");
3516 cliPrintVarRange(val
);
3522 cliPrint("Invalid name\r\n");
3524 // no equals, check for matching variables.
3529 static void cliGet(char *cmdline
)
3531 const clivalue_t
*val
;
3532 int matchedCommands
= 0;
3534 for (uint32_t i
= 0; i
< VALUE_COUNT
; i
++) {
3535 if (strstr(valueTable
[i
].name
, cmdline
)) {
3536 val
= &valueTable
[i
];
3537 cliPrintf("%s = ", valueTable
[i
].name
);
3538 cliPrintVar(val
, 0);
3540 cliPrintVarRange(val
);
3548 if (matchedCommands
) {
3552 cliPrint("Invalid name\r\n");
3555 static void cliStatus(char *cmdline
)
3559 cliPrintf("System Uptime: %d seconds, Voltage: %d * 0.1V (%dS battery - %s), CPU:%d%%\r\n",
3563 getBatteryStateString(),
3564 constrain(averageSystemLoadPercent
, 0, 100)
3567 cliPrintf("CPU Clock=%dMHz", (SystemCoreClock
/ 1000000));
3569 #if (FLASH_SIZE > 64) && !defined(CLI_MINIMAL_VERBOSITY)
3571 uint32_t detectedSensorsMask
= sensorsMask();
3573 for (uint32_t i
= 0; ; i
++) {
3575 if (sensorTypeNames
[i
] == NULL
)
3579 if ((detectedSensorsMask
& mask
) && (mask
& SENSOR_NAMES_MASK
)) {
3580 const char *sensorHardware
;
3581 uint8_t sensorHardwareIndex
= detectedSensors
[i
];
3582 sensorHardware
= sensorHardwareNames
[i
][sensorHardwareIndex
];
3584 cliPrintf(", %s=%s", sensorTypeNames
[i
], sensorHardware
);
3586 if (mask
== SENSOR_ACC
&& acc
.revisionCode
) {
3587 cliPrintf(".%c", acc
.revisionCode
);
3595 uint16_t i2cErrorCounter
= i2cGetErrorCounter();
3597 uint16_t i2cErrorCounter
= 0;
3600 cliPrintf("Cycle Time: %d, I2C Errors: %d, config size: %d\r\n", cycleTime
, i2cErrorCounter
, sizeof(master_t
));
3607 #ifndef SKIP_TASK_STATISTICS
3608 static void cliTasks(char *cmdline
)
3612 int averageLoadSum
= 0;
3614 #ifndef CLI_MINIMAL_VERBOSITY
3615 cliPrintf("Task list rate/hz max/us avg/us maxload avgload total/ms\r\n");
3617 for (cfTaskId_e taskId
= 0; taskId
< TASK_COUNT
; taskId
++) {
3618 cfTaskInfo_t taskInfo
;
3619 getTaskInfo(taskId
, &taskInfo
);
3620 if (taskInfo
.isEnabled
) {
3622 int subTaskFrequency
;
3623 if (taskId
== TASK_GYROPID
) {
3624 subTaskFrequency
= (int)(1000000.0f
/ ((float)cycleTime
));
3625 taskFrequency
= subTaskFrequency
/ masterConfig
.pid_process_denom
;
3626 if (masterConfig
.pid_process_denom
> 1) {
3627 cliPrintf("%02d - (%13s) ", taskId
, taskInfo
.taskName
);
3629 taskFrequency
= subTaskFrequency
;
3630 cliPrintf("%02d - (%9s/%3s) ", taskId
, taskInfo
.subTaskName
, taskInfo
.taskName
);
3633 taskFrequency
= (int)(1000000.0f
/ ((float)taskInfo
.latestDeltaTime
));
3634 cliPrintf("%02d - (%13s) ", taskId
, taskInfo
.taskName
);
3636 const int maxLoad
= (taskInfo
.maxExecutionTime
* taskFrequency
+ 5000) / 1000;
3637 const int averageLoad
= (taskInfo
.averageExecutionTime
* taskFrequency
+ 5000) / 1000;
3638 if (taskId
!= TASK_SERIAL
) {
3639 maxLoadSum
+= maxLoad
;
3640 averageLoadSum
+= averageLoad
;
3642 cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n",
3643 taskFrequency
, taskInfo
.maxExecutionTime
, taskInfo
.averageExecutionTime
,
3644 maxLoad
/10, maxLoad
%10, averageLoad
/10, averageLoad
%10, taskInfo
.totalExecutionTime
/ 1000);
3645 if (taskId
== TASK_GYROPID
&& masterConfig
.pid_process_denom
> 1) {
3646 cliPrintf(" - (%13s) %6d\r\n", taskInfo
.subTaskName
, subTaskFrequency
);
3650 cfCheckFuncInfo_t checkFuncInfo
;
3651 getCheckFuncInfo(&checkFuncInfo
);
3652 cliPrintf("RX Check Function %17d %7d %25d\r\n", checkFuncInfo
.maxExecutionTime
, checkFuncInfo
.averageExecutionTime
, checkFuncInfo
.totalExecutionTime
/ 1000);
3653 cliPrintf("Total (excluding SERIAL) %23d.%1d%% %4d.%1d%%\r\n", maxLoadSum
/10, maxLoadSum
%10, averageLoadSum
/10, averageLoadSum
%10);
3657 static void cliVersion(char *cmdline
)
3661 cliPrintf("# %s/%s %s %s / %s (%s)\r\n",
3671 void cliProcess(void)
3677 // Be a little bit tricky. Flush the last inputs buffer, if any.
3678 bufWriterFlush(cliWriter
);
3680 while (serialRxBytesWaiting(cliPort
)) {
3681 uint8_t c
= serialRead(cliPort
);
3682 if (c
== '\t' || c
== '?') {
3683 // do tab completion
3684 const clicmd_t
*cmd
, *pstart
= NULL
, *pend
= NULL
;
3685 uint32_t i
= bufferIndex
;
3686 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
3687 if (bufferIndex
&& (strncasecmp(cliBuffer
, cmd
->name
, bufferIndex
) != 0))
3693 if (pstart
) { /* Buffer matches one or more commands */
3694 for (; ; bufferIndex
++) {
3695 if (pstart
->name
[bufferIndex
] != pend
->name
[bufferIndex
])
3697 if (!pstart
->name
[bufferIndex
] && bufferIndex
< sizeof(cliBuffer
) - 2) {
3698 /* Unambiguous -- append a space */
3699 cliBuffer
[bufferIndex
++] = ' ';
3700 cliBuffer
[bufferIndex
] = '\0';
3703 cliBuffer
[bufferIndex
] = pstart
->name
[bufferIndex
];
3706 if (!bufferIndex
|| pstart
!= pend
) {
3707 /* Print list of ambiguous matches */
3708 cliPrint("\r\033[K");
3709 for (cmd
= pstart
; cmd
<= pend
; cmd
++) {
3710 cliPrint(cmd
->name
);
3714 i
= 0; /* Redraw prompt */
3716 for (; i
< bufferIndex
; i
++)
3717 cliWrite(cliBuffer
[i
]);
3718 } else if (!bufferIndex
&& c
== 4) { // CTRL-D
3721 } else if (c
== 12) { // NewPage / CTRL-L
3723 cliPrint("\033[2J\033[1;1H");
3725 } else if (bufferIndex
&& (c
== '\n' || c
== '\r')) {
3729 // Strip comment starting with # from line
3730 char *p
= cliBuffer
;
3733 bufferIndex
= (uint32_t)(p
- cliBuffer
);
3736 // Strip trailing whitespace
3737 while (bufferIndex
> 0 && cliBuffer
[bufferIndex
- 1] == ' ') {
3741 // Process non-empty lines
3742 if (bufferIndex
> 0) {
3743 cliBuffer
[bufferIndex
] = 0; // null terminate
3745 const clicmd_t
*cmd
;
3747 for (cmd
= cmdTable
; cmd
< cmdTable
+ CMD_COUNT
; cmd
++) {
3748 if ((options
= checkCommand(cliBuffer
, cmd
->name
))) {
3752 if(cmd
< cmdTable
+ CMD_COUNT
)
3755 cliPrint("Unknown command, try 'help'");
3759 memset(cliBuffer
, 0, sizeof(cliBuffer
));
3761 // 'exit' will reset this flag, so we don't need to print prompt again
3766 } else if (c
== 127) {
3769 cliBuffer
[--bufferIndex
] = 0;
3770 cliPrint("\010 \010");
3772 } else if (bufferIndex
< sizeof(cliBuffer
) && c
>= 32 && c
<= 126) {
3773 if (!bufferIndex
&& c
== ' ')
3774 continue; // Ignore leading spaces
3775 cliBuffer
[bufferIndex
++] = c
;
3781 #if (FLASH_SIZE > 64)
3784 const uint8_t owner
;
3786 const uint8_t maxIndex
;
3787 } cliResourceValue_t
;
3789 const cliResourceValue_t resourceTable
[] = {
3791 { OWNER_BEEPER
, &masterConfig
.beeperConfig
.ioTag
, 0 },
3793 { OWNER_MOTOR
, &masterConfig
.motorConfig
.ioTags
[0], MAX_SUPPORTED_MOTORS
},
3795 { OWNER_SERVO
, &masterConfig
.servoConfig
.ioTags
[0], MAX_SUPPORTED_SERVOS
},
3797 #if defined(USE_PWM) || defined(USE_PPM)
3798 { OWNER_PPMINPUT
, &masterConfig
.ppmConfig
.ioTag
, 0 },
3799 { OWNER_PWMINPUT
, &masterConfig
.pwmConfig
.ioTags
[0], PWM_INPUT_PORT_COUNT
},
3802 { OWNER_SONAR_TRIGGER
, &masterConfig
.sonarConfig
.triggerTag
, 0 },
3803 { OWNER_SONAR_ECHO
, &masterConfig
.sonarConfig
.echoTag
, 0 },
3806 { OWNER_LED_STRIP
, &masterConfig
.ledStripConfig
.ioTag
, 0 },
3810 static void printResource(uint8_t dumpMask
, master_t
*defaultConfig
)
3812 for (unsigned int i
= 0; i
< ARRAYLEN(resourceTable
); i
++) {
3814 owner
= ownerNames
[resourceTable
[i
].owner
];
3816 if (resourceTable
[i
].maxIndex
> 0) {
3817 for (int index
= 0; index
< resourceTable
[i
].maxIndex
; index
++) {
3818 ioTag_t ioTag
= *(resourceTable
[i
].ptr
+ index
);
3819 ioTag_t ioTagDefault
= *(resourceTable
[i
].ptr
+ index
- (uint32_t)&masterConfig
+ (uint32_t)defaultConfig
);
3821 bool equalsDefault
= ioTag
== ioTagDefault
;
3822 const char *format
= "resource %s %d %c%02d\r\n";
3823 const char *formatUnassigned
= "resource %s %d NONE\r\n";
3824 if (!ioTagDefault
) {
3825 cliDefaultPrintf(dumpMask
, equalsDefault
, formatUnassigned
, owner
, RESOURCE_INDEX(index
));
3827 cliDefaultPrintf(dumpMask
, equalsDefault
, format
, owner
, RESOURCE_INDEX(index
), IO_GPIOPortIdxByTag(ioTagDefault
) + 'A', IO_GPIOPinIdxByTag(ioTagDefault
));
3830 if (!(dumpMask
& HIDE_UNUSED
)) {
3831 cliDumpPrintf(dumpMask
, equalsDefault
, formatUnassigned
, owner
, RESOURCE_INDEX(index
));
3834 cliDumpPrintf(dumpMask
, equalsDefault
, format
, owner
, RESOURCE_INDEX(index
), IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
));
3838 ioTag_t ioTag
= *resourceTable
[i
].ptr
;
3839 ioTag_t ioTagDefault
= *(resourceTable
[i
].ptr
- (uint32_t)&masterConfig
+ (uint32_t)defaultConfig
);
3841 bool equalsDefault
= ioTag
== ioTagDefault
;
3842 const char *format
= "resource %s %c%02d\r\n";
3843 const char *formatUnassigned
= "resource %s NONE\r\n";
3844 if (!ioTagDefault
) {
3845 cliDefaultPrintf(dumpMask
, equalsDefault
, formatUnassigned
, owner
);
3847 cliDefaultPrintf(dumpMask
, equalsDefault
, format
, owner
, IO_GPIOPortIdxByTag(ioTagDefault
) + 'A', IO_GPIOPinIdxByTag(ioTagDefault
));
3850 if (!(dumpMask
& HIDE_UNUSED
)) {
3851 cliDumpPrintf(dumpMask
, equalsDefault
, formatUnassigned
, owner
);
3854 cliDumpPrintf(dumpMask
, equalsDefault
, format
, owner
, IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
));
3860 #ifndef CLI_MINIMAL_VERBOSITY
3861 static bool resourceCheck(uint8_t resourceIndex
, uint8_t index
, ioTag_t tag
)
3863 const char * format
= "\r\n* %s * %c%d also used by %s";
3864 for (int r
= 0; r
< (int)ARRAYLEN(resourceTable
); r
++) {
3865 for (int i
= 0; i
< (resourceTable
[r
].maxIndex
== 0 ? 1 : resourceTable
[r
].maxIndex
); i
++) {
3866 if (*(resourceTable
[r
].ptr
+ i
) == tag
) {
3868 if (r
== resourceIndex
) {
3875 cliPrintf(format
, error
? "ERROR" : "WARNING", DEFIO_TAG_GPIOID(tag
) + 'A', DEFIO_TAG_PIN(tag
), ownerNames
[resourceTable
[r
].owner
]);
3876 if (resourceTable
[r
].maxIndex
> 0) {
3877 cliPrintf(" %d", RESOURCE_INDEX(i
));
3889 static void cliResource(char *cmdline
)
3891 int len
= strlen(cmdline
);
3894 printResource(DUMP_MASTER
| HIDE_UNUSED
, NULL
);
3897 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
3898 #ifndef CLI_MINIMAL_VERBOSITY
3899 cliPrintf("Currently active IO resource assignments:\r\n(reboot to update)\r\n");
3902 for (int i
= 0; i
< DEFIO_IO_USED_COUNT
; i
++) {
3904 owner
= ownerNames
[ioRecs
[i
].owner
];
3906 if (ioRecs
[i
].index
> 0) {
3907 cliPrintf("%c%02d: %s %d\r\n", IO_GPIOPortIdx(ioRecs
+ i
) + 'A', IO_GPIOPinIdx(ioRecs
+ i
), owner
, ioRecs
[i
].index
);
3909 cliPrintf("%c%02d: %s \r\n", IO_GPIOPortIdx(ioRecs
+ i
) + 'A', IO_GPIOPinIdx(ioRecs
+ i
), owner
);
3913 cliPrintf("\r\n\r\nCurrently active DMA:\r\n");
3914 #ifndef CLI_MINIMAL_VERBOSITY
3917 for (int i
= 0; i
< DMA_MAX_DESCRIPTORS
; i
++) {
3919 owner
= ownerNames
[dmaGetOwner(i
)];
3921 cliPrintf(DMA_OUTPUT_STRING
, i
/ DMA_MOD_VALUE
+ 1, (i
% DMA_MOD_VALUE
) + DMA_MOD_OFFSET
);
3922 uint8_t resourceIndex
= dmaGetResourceIndex(i
);
3923 if (resourceIndex
> 0) {
3924 cliPrintf(" %s %d\r\n", owner
, resourceIndex
);
3926 cliPrintf(" %s\r\n", owner
);
3930 #ifndef CLI_MINIMAL_VERBOSITY
3931 cliPrintf("\r\nUse: 'resource' to see how to change resources.\r\n");
3937 uint8_t resourceIndex
= 0;
3942 pch
= strtok_r(cmdline
, " ", &saveptr
);
3943 for (resourceIndex
= 0; ; resourceIndex
++) {
3944 if (resourceIndex
>= ARRAYLEN(resourceTable
)) {
3945 cliPrint("Invalid resource\r\n");
3949 if (strncasecmp(pch
, ownerNames
[resourceTable
[resourceIndex
].owner
], len
) == 0) {
3954 if (resourceTable
[resourceIndex
].maxIndex
> 0) {
3955 pch
= strtok_r(NULL
, " ", &saveptr
);
3958 if (index
<= 0 || index
> resourceTable
[resourceIndex
].maxIndex
) {
3959 cliShowArgumentRangeError("index", 1, resourceTable
[resourceIndex
].maxIndex
);
3965 pch
= strtok_r(NULL
, " ", &saveptr
);
3966 ioTag_t
*tag
= (ioTag_t
*)(resourceTable
[resourceIndex
].ptr
+ index
);
3969 if (strlen(pch
) > 0) {
3970 if (strcasecmp(pch
, "NONE") == 0) {
3972 cliPrintf("Resource is freed!\r\n");
3975 uint8_t port
= (*pch
) - 'A';
3977 port
= (*pch
) - 'a';
3984 ioRec_t
*rec
= IO_Rec(IOGetByTag(DEFIO_TAG_MAKE(port
, pin
)));
3986 #ifndef CLI_MINIMAL_VERBOSITY
3987 if (!resourceCheck(resourceIndex
, index
, DEFIO_TAG_MAKE(port
, pin
))) {
3990 cliPrintf("Resource is set to %c%02d!\r\n", port
+ 'A', pin
);
3992 cliPrintf("Set to %c%02d!", port
+ 'A', pin
);
3994 *tag
= DEFIO_TAG_MAKE(port
, pin
);
3996 cliPrintf("Resource is invalid!\r\n");
4004 cliShowParseError();
4008 void cliDfu(char *cmdLine
)
4011 #ifndef CLI_MINIMAL_VERBOSITY
4012 cliPrint("\r\nRestarting in DFU mode");
4017 void cliInit(serialConfig_t
*serialConfig
)
4019 UNUSED(serialConfig
);