2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
31 // FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
32 // signal that we're in cli mode
37 #include "blackbox/blackbox.h"
39 #include "build/build_config.h"
40 #include "build/debug.h"
41 #include "build/version.h"
43 #include "cli/settings.h"
47 #include "common/axis.h"
48 #include "common/color.h"
49 #include "common/maths.h"
50 #include "common/printf.h"
51 #include "common/printf_serial.h"
52 #include "common/strtol.h"
53 #include "common/time.h"
54 #include "common/typeconversion.h"
55 #include "common/utils.h"
57 #include "config/config.h"
58 #include "config/config_eeprom.h"
59 #include "config/feature.h"
60 #include "config/simplified_tuning.h"
62 #include "drivers/accgyro/accgyro.h"
63 #include "drivers/adc.h"
64 #include "drivers/buf_writer.h"
65 #include "drivers/bus_i2c.h"
66 #include "drivers/bus_spi.h"
67 #include "drivers/dma.h"
68 #include "drivers/dma_reqmap.h"
69 #include "drivers/dshot.h"
70 #include "drivers/dshot_command.h"
71 #include "drivers/dshot_dpwm.h"
72 #include "drivers/pwm_output_dshot_shared.h"
73 #include "drivers/camera_control.h"
74 #include "drivers/compass/compass.h"
75 #include "drivers/display.h"
76 #include "drivers/dma.h"
77 #include "drivers/flash.h"
78 #include "drivers/inverter.h"
79 #include "drivers/io.h"
80 #include "drivers/io_impl.h"
81 #include "drivers/light_led.h"
82 #include "drivers/motor.h"
83 #include "drivers/rangefinder/rangefinder_hcsr04.h"
84 #include "drivers/resource.h"
85 #include "drivers/sdcard.h"
86 #include "drivers/sensor.h"
87 #include "drivers/serial.h"
88 #include "drivers/serial_escserial.h"
89 #include "drivers/sound_beeper.h"
90 #include "drivers/stack_check.h"
91 #include "drivers/system.h"
92 #include "drivers/time.h"
93 #include "drivers/timer.h"
94 #include "drivers/transponder_ir.h"
95 #include "drivers/usb_msc.h"
96 #include "drivers/vtx_common.h"
97 #include "drivers/vtx_table.h"
99 #include "fc/board_info.h"
100 #include "fc/controlrate_profile.h"
103 #include "fc/rc_adjustments.h"
104 #include "fc/rc_controls.h"
105 #include "fc/runtime_config.h"
107 #include "flight/failsafe.h"
108 #include "flight/imu.h"
109 #include "flight/mixer.h"
110 #include "flight/pid.h"
111 #include "flight/position.h"
112 #include "flight/servos.h"
114 #include "io/asyncfatfs/asyncfatfs.h"
115 #include "io/beeper.h"
116 #include "io/flashfs.h"
117 #include "io/gimbal.h"
119 #include "io/ledstrip.h"
120 #include "io/serial.h"
121 #include "io/transponder_ir.h"
122 #include "io/usb_msc.h"
123 #include "io/vtx_control.h"
127 #include "msp/msp_box.h"
128 #include "msp/msp_protocol.h"
133 #include "pg/beeper.h"
134 #include "pg/beeper_dev.h"
135 #include "pg/board.h"
136 #include "pg/bus_i2c.h"
137 #include "pg/bus_spi.h"
138 #include "pg/gyrodev.h"
139 #include "pg/max7456.h"
141 #include "pg/motor.h"
142 #include "pg/pinio.h"
143 #include "pg/pin_pull_up_down.h"
145 #include "pg/pg_ids.h"
147 #include "pg/rx_pwm.h"
148 #include "pg/rx_spi_cc2500.h"
149 #include "pg/rx_spi_expresslrs.h"
150 #include "pg/serial_uart.h"
152 #include "pg/timerio.h"
153 #include "pg/timerup.h"
155 #include "pg/vtx_table.h"
157 #include "rx/rx_bind.h"
158 #include "rx/rx_spi.h"
160 #include "scheduler/scheduler.h"
162 #include "sensors/acceleration.h"
163 #include "sensors/adcinternal.h"
164 #include "sensors/barometer.h"
165 #include "sensors/battery.h"
166 #include "sensors/boardalignment.h"
167 #include "sensors/compass.h"
168 #include "sensors/gyro.h"
169 #include "sensors/gyro_init.h"
170 #include "sensors/sensors.h"
172 #include "telemetry/frsky_hub.h"
173 #include "telemetry/telemetry.h"
177 static serialPort_t
*cliPort
= NULL
;
179 // Space required to set array parameters
180 #define CLI_IN_BUFFER_SIZE 256
181 #define CLI_OUT_BUFFER_SIZE 64
183 static bufWriter_t cliWriterDesc
;
184 static bufWriter_t
*cliWriter
= NULL
;
185 static bufWriter_t
*cliErrorWriter
= NULL
;
186 static uint8_t cliWriteBuffer
[CLI_OUT_BUFFER_SIZE
];
188 static char cliBuffer
[CLI_IN_BUFFER_SIZE
];
189 static uint32_t bufferIndex
= 0;
191 static bool configIsInCopy
= false;
193 #define CURRENT_PROFILE_INDEX -1
194 static int8_t pidProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
195 static int8_t rateProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
198 static bool commandBatchActive
= false;
199 static bool commandBatchError
= false;
202 #if defined(USE_BOARD_INFO)
203 static bool boardInformationUpdated
= false;
204 #if defined(USE_SIGNATURE)
205 static bool signatureUpdated
= false;
207 #endif // USE_BOARD_INFO
209 static const char* const emptyName
= "-";
210 static const char* const emptyString
= "";
212 #if !defined(USE_CUSTOM_DEFAULTS)
213 #define CUSTOM_DEFAULTS_START ((char*)0)
214 #define CUSTOM_DEFAULTS_END ((char *)0)
216 extern char __custom_defaults_start
;
217 extern char __custom_defaults_end
;
218 #define CUSTOM_DEFAULTS_START (&__custom_defaults_start)
219 #define CUSTOM_DEFAULTS_END (&__custom_defaults_end)
221 static bool processingCustomDefaults
= false;
222 static char cliBufferTemp
[CLI_IN_BUFFER_SIZE
];
224 #define CUSTOM_DEFAULTS_START_PREFIX ("# " FC_FIRMWARE_NAME)
226 #define MAX_CHANGESET_ID_LENGTH 8
227 #define MAX_DATE_LENGTH 20
229 static bool customDefaultsHeaderParsed
= false;
230 static bool customDefaultsFound
= false;
234 #if defined(USE_CUSTOM_DEFAULTS_ADDRESS)
235 static char __attribute__ ((section(".custom_defaults_start_address"))) *customDefaultsStart
= CUSTOM_DEFAULTS_START
;
236 static char __attribute__ ((section(".custom_defaults_end_address"))) *customDefaultsEnd
= CUSTOM_DEFAULTS_END
;
239 #define ERROR_INVALID_NAME "INVALID NAME: %s"
240 #define ERROR_MESSAGE "%s CANNOT BE CHANGED. CURRENT VALUE: '%s'"
242 #ifndef USE_QUAD_MIXER_ONLY
243 // sync this with mixerMode_e
244 static const char * const mixerNames
[] = {
245 "TRI", "QUADP", "QUADX", "BI",
246 "GIMBAL", "Y6", "HEX6",
247 "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX",
248 "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4",
249 "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER",
250 "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL
254 // sync this with features_e
255 static const char * const featureNames
[] = {
256 "RX_PPM", "", "INFLIGHT_ACC_CAL", "RX_SERIAL", "MOTOR_STOP",
257 "SERVO_TILT", "SOFTSERIAL", "GPS", "",
258 "RANGEFINDER", "TELEMETRY", "", "3D", "RX_PARALLEL_PWM",
259 "RX_MSP", "RSSI_ADC", "LED_STRIP", "DISPLAY", "OSD",
260 "", "CHANNEL_FORWARDING", "TRANSPONDER", "AIRMODE",
261 "", "", "RX_SPI", "", "ESC_SENSOR", "ANTI_GRAVITY", "", NULL
264 // sync this with rxFailsafeChannelMode_e
265 static const char rxFailsafeModeCharacters
[] = "ahs";
267 static const rxFailsafeChannelMode_e rxFailsafeModesTable
[RX_FAILSAFE_TYPE_COUNT
][RX_FAILSAFE_MODE_COUNT
] = {
268 { RX_FAILSAFE_MODE_AUTO
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
},
269 { RX_FAILSAFE_MODE_INVALID
, RX_FAILSAFE_MODE_HOLD
, RX_FAILSAFE_MODE_SET
}
272 #if defined(USE_SENSOR_NAMES)
273 // sync this with sensors_e
274 static const char *const sensorTypeNames
[] = {
275 "GYRO", "ACC", "BARO", "MAG", "RANGEFINDER", "GPS", "GPS+MAG", NULL
278 #define SENSOR_NAMES_MASK (SENSOR_GYRO | SENSOR_ACC | SENSOR_BARO | SENSOR_MAG | SENSOR_RANGEFINDER)
280 static const char * const *sensorHardwareNames
[] = {
281 lookupTableGyroHardware
, lookupTableAccHardware
, lookupTableBaroHardware
, lookupTableMagHardware
, lookupTableRangefinderHardware
283 #endif // USE_SENSOR_NAMES
285 // Needs to be aligned with mcuTypeId_e
286 static const char *mcuTypeNames
[] = {
296 "H743 (Rev Unknown)",
306 static const char *configurationStates
[] = { "UNCONFIGURED", "CUSTOM DEFAULTS", "CONFIGURED" };
308 typedef enum dumpFlags_e
{
309 DUMP_MASTER
= (1 << 0),
310 DUMP_PROFILE
= (1 << 1),
311 DUMP_RATES
= (1 << 2),
314 SHOW_DEFAULTS
= (1 << 5),
315 HIDE_UNUSED
= (1 << 6),
316 HARDWARE_ONLY
= (1 << 7),
320 typedef bool printFn(dumpFlags_t dumpMask
, bool equalsDefault
, const char *format
, ...);
323 REBOOT_TARGET_FIRMWARE
,
324 REBOOT_TARGET_BOOTLOADER_ROM
,
325 REBOOT_TARGET_BOOTLOADER_FLASH
,
328 typedef struct serialPassthroughPort_s
{
333 } serialPassthroughPort_t
;
335 static void cliWriterFlushInternal(bufWriter_t
*writer
)
338 bufWriterFlush(writer
);
342 static void cliPrintInternal(bufWriter_t
*writer
, const char *str
)
346 bufWriterAppend(writer
, *str
++);
348 cliWriterFlushInternal(writer
);
352 static void cliWriterFlush(void)
354 cliWriterFlushInternal(cliWriter
);
357 void cliPrint(const char *str
)
359 cliPrintInternal(cliWriter
, str
);
362 void cliPrintLinefeed(void)
367 void cliPrintLine(const char *str
)
374 #define cliPrintHashLine(str)
376 static void cliPrintHashLine(const char *str
)
383 static void cliPutp(void *p
, char ch
)
385 bufWriterAppend(p
, ch
);
388 static void cliPrintfva(const char *format
, va_list va
)
391 tfp_format(cliWriter
, cliPutp
, format
, va
);
396 static bool cliDumpPrintLinef(dumpFlags_t dumpMask
, bool equalsDefault
, const char *format
, ...)
398 if (!((dumpMask
& DO_DIFF
) && equalsDefault
)) {
400 va_start(va
, format
);
401 cliPrintfva(format
, va
);
410 static void cliWrite(uint8_t ch
)
413 bufWriterAppend(cliWriter
, ch
);
417 static bool cliDefaultPrintLinef(dumpFlags_t dumpMask
, bool equalsDefault
, const char *format
, ...)
419 if ((dumpMask
& SHOW_DEFAULTS
) && !equalsDefault
) {
423 va_start(va
, format
);
424 cliPrintfva(format
, va
);
433 void cliPrintf(const char *format
, ...)
436 va_start(va
, format
);
437 cliPrintfva(format
, va
);
442 void cliPrintLinef(const char *format
, ...)
445 va_start(va
, format
);
446 cliPrintfva(format
, va
);
451 static void cliPrintErrorVa(const char *cmdName
, const char *format
, va_list va
)
453 if (cliErrorWriter
) {
454 cliPrintInternal(cliErrorWriter
, "###ERROR IN ");
455 cliPrintInternal(cliErrorWriter
, cmdName
);
456 cliPrintInternal(cliErrorWriter
, ": ");
458 tfp_format(cliErrorWriter
, cliPutp
, format
, va
);
461 cliPrintInternal(cliErrorWriter
, "###");
465 if (commandBatchActive
) {
466 commandBatchError
= true;
471 static void cliPrintError(const char *cmdName
, const char *format
, ...)
474 va_start(va
, format
);
475 cliPrintErrorVa(cmdName
, format
, va
);
478 // Supply our own linefeed in case we are printing inside a custom defaults operation
479 // TODO: Fix this by rewriting the entire CLI to have self contained line feeds
480 // instead of expecting the directly following command to supply the line feed.
481 cliPrintInternal(cliErrorWriter
, "\r\n");
485 static void cliPrintErrorLinef(const char *cmdName
, const char *format
, ...)
488 va_start(va
, format
);
489 cliPrintErrorVa(cmdName
, format
, va
);
490 cliPrintInternal(cliErrorWriter
, "\r\n");
493 static void getMinMax(const clivalue_t
*var
, int *min
, int *max
)
495 switch (var
->type
& VALUE_TYPE_MASK
) {
498 *min
= var
->config
.minmaxUnsigned
.min
;
499 *max
= var
->config
.minmaxUnsigned
.max
;
503 *min
= var
->config
.minmax
.min
;
504 *max
= var
->config
.minmax
.max
;
510 static void printValuePointer(const char *cmdName
, const clivalue_t
*var
, const void *valuePointer
, bool full
)
512 if ((var
->type
& VALUE_MODE_MASK
) == MODE_ARRAY
) {
513 for (int i
= 0; i
< var
->config
.array
.length
; i
++) {
514 switch (var
->type
& VALUE_TYPE_MASK
) {
518 cliPrintf("%d", ((uint8_t *)valuePointer
)[i
]);
523 cliPrintf("%d", ((int8_t *)valuePointer
)[i
]);
528 cliPrintf("%d", ((uint16_t *)valuePointer
)[i
]);
533 cliPrintf("%d", ((int16_t *)valuePointer
)[i
]);
538 cliPrintf("%u", ((uint32_t *)valuePointer
)[i
]);
542 if (i
< var
->config
.array
.length
- 1) {
549 switch (var
->type
& VALUE_TYPE_MASK
) {
551 value
= *(uint8_t *)valuePointer
;
555 value
= *(int8_t *)valuePointer
;
559 value
= *(uint16_t *)valuePointer
;
563 value
= *(int16_t *)valuePointer
;
567 value
= *(uint32_t *)valuePointer
;
572 bool valueIsCorrupted
= false;
573 switch (var
->type
& VALUE_MODE_MASK
) {
575 if ((var
->type
& VALUE_TYPE_MASK
) == VAR_UINT32
) {
576 cliPrintf("%u", (uint32_t)value
);
577 if ((uint32_t)value
> var
->config
.u32Max
) {
578 valueIsCorrupted
= true;
580 cliPrintf(" 0 %u", var
->config
.u32Max
);
585 getMinMax(var
, &min
, &max
);
587 cliPrintf("%d", value
);
588 if ((value
< min
) || (value
> max
)) {
589 valueIsCorrupted
= true;
591 cliPrintf(" %d %d", min
, max
);
596 if (value
< lookupTables
[var
->config
.lookup
.tableIndex
].valueCount
) {
597 cliPrint(lookupTables
[var
->config
.lookup
.tableIndex
].values
[value
]);
599 valueIsCorrupted
= true;
603 if (value
& 1 << var
->config
.bitpos
) {
610 cliPrintf("%s", (strlen((char *)valuePointer
) == 0) ? "-" : (char *)valuePointer
);
614 if (valueIsCorrupted
) {
616 cliPrintError(cmdName
, "CORRUPTED CONFIG: %s = %d", var
->name
, value
);
622 static bool valuePtrEqualsDefault(const clivalue_t
*var
, const void *ptr
, const void *ptrDefault
)
625 int elementCount
= 1;
626 uint32_t mask
= 0xffffffff;
628 if ((var
->type
& VALUE_MODE_MASK
) == MODE_ARRAY
) {
629 elementCount
= var
->config
.array
.length
;
631 if ((var
->type
& VALUE_MODE_MASK
) == MODE_BITSET
) {
632 mask
= 1 << var
->config
.bitpos
;
634 for (int i
= 0; i
< elementCount
; i
++) {
635 switch (var
->type
& VALUE_TYPE_MASK
) {
637 result
= result
&& (((uint8_t *)ptr
)[i
] & mask
) == (((uint8_t *)ptrDefault
)[i
] & mask
);
641 result
= result
&& ((int8_t *)ptr
)[i
] == ((int8_t *)ptrDefault
)[i
];
645 result
= result
&& (((uint16_t *)ptr
)[i
] & mask
) == (((uint16_t *)ptrDefault
)[i
] & mask
);
648 result
= result
&& ((int16_t *)ptr
)[i
] == ((int16_t *)ptrDefault
)[i
];
651 result
= result
&& (((uint32_t *)ptr
)[i
] & mask
) == (((uint32_t *)ptrDefault
)[i
] & mask
);
659 static const char *cliPrintSectionHeading(dumpFlags_t dumpMask
, bool outputFlag
, const char *headingStr
)
661 if (headingStr
&& (!(dumpMask
& DO_DIFF
) || outputFlag
)) {
662 cliPrintHashLine(headingStr
);
669 static void backupPgConfig(const pgRegistry_t
*pg
)
671 memcpy(pg
->copy
, pg
->address
, pg
->size
);
674 static void restorePgConfig(const pgRegistry_t
*pg
, uint16_t notToRestoreGroupId
)
676 if (!notToRestoreGroupId
|| pgN(pg
) != notToRestoreGroupId
) {
677 memcpy(pg
->address
, pg
->copy
, pg
->size
);
681 static void backupConfigs(void)
683 if (configIsInCopy
) {
691 configIsInCopy
= true;
694 static void restoreConfigs(uint16_t notToRestoreGroupId
)
696 if (!configIsInCopy
) {
701 restorePgConfig(pg
, notToRestoreGroupId
);
704 configIsInCopy
= false;
707 #if defined(USE_RESOURCE_MGMT) || defined(USE_TIMER_MGMT)
708 static bool isReadingConfigFromCopy(void)
710 return configIsInCopy
;
714 static bool isWritingConfigToCopy(void)
716 return configIsInCopy
717 #if defined(USE_CUSTOM_DEFAULTS)
718 && !processingCustomDefaults
723 #if defined(USE_CUSTOM_DEFAULTS)
724 static bool cliProcessCustomDefaults(bool quiet
);
727 static void backupAndResetConfigs(const bool useCustomDefaults
)
731 // reset all configs to defaults to do differencing
734 #if defined(USE_CUSTOM_DEFAULTS)
735 if (useCustomDefaults
) {
736 if (!cliProcessCustomDefaults(true)) {
737 cliPrintLine("###WARNING: NO CUSTOM DEFAULTS FOUND###");
741 UNUSED(useCustomDefaults
);
745 static uint8_t getPidProfileIndexToUse(void)
747 return pidProfileIndexToUse
== CURRENT_PROFILE_INDEX
? getCurrentPidProfileIndex() : pidProfileIndexToUse
;
750 static uint8_t getRateProfileIndexToUse(void)
752 return rateProfileIndexToUse
== CURRENT_PROFILE_INDEX
? getCurrentControlRateProfileIndex() : rateProfileIndexToUse
;
756 static uint16_t getValueOffset(const clivalue_t
*value
)
758 switch (value
->type
& VALUE_SECTION_MASK
) {
761 return value
->offset
;
763 return value
->offset
+ sizeof(pidProfile_t
) * getPidProfileIndexToUse();
764 case PROFILE_RATE_VALUE
:
765 return value
->offset
+ sizeof(controlRateConfig_t
) * getRateProfileIndexToUse();
770 STATIC_UNIT_TESTED
void *cliGetValuePointer(const clivalue_t
*value
)
772 const pgRegistry_t
* rec
= pgFind(value
->pgn
);
773 if (isWritingConfigToCopy()) {
774 return CONST_CAST(void *, rec
->copy
+ getValueOffset(value
));
776 return CONST_CAST(void *, rec
->address
+ getValueOffset(value
));
780 static const char *dumpPgValue(const char *cmdName
, const clivalue_t
*value
, dumpFlags_t dumpMask
, const char *headingStr
)
782 const pgRegistry_t
*pg
= pgFind(value
->pgn
);
785 cliPrintLinef("VALUE %s ERROR", value
->name
);
786 return headingStr
; // if it's not found, the pgn shouldn't be in the value table!
790 const char *format
= "set %s = ";
791 const char *defaultFormat
= "#set %s = ";
792 const int valueOffset
= getValueOffset(value
);
793 const bool equalsDefault
= valuePtrEqualsDefault(value
, pg
->copy
+ valueOffset
, pg
->address
+ valueOffset
);
795 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
796 if (((dumpMask
& DO_DIFF
) == 0) || !equalsDefault
) {
797 if (dumpMask
& SHOW_DEFAULTS
&& !equalsDefault
) {
798 cliPrintf(defaultFormat
, value
->name
);
799 printValuePointer(cmdName
, value
, (uint8_t*)pg
->address
+ valueOffset
, false);
802 cliPrintf(format
, value
->name
);
803 printValuePointer(cmdName
, value
, pg
->copy
+ valueOffset
, false);
809 static void dumpAllValues(const char *cmdName
, uint16_t valueSection
, dumpFlags_t dumpMask
, const char *headingStr
)
811 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
813 for (uint32_t i
= 0; i
< valueTableEntryCount
; i
++) {
814 const clivalue_t
*value
= &valueTable
[i
];
816 if ((value
->type
& VALUE_SECTION_MASK
) == valueSection
|| ((valueSection
== MASTER_VALUE
) && (value
->type
& VALUE_SECTION_MASK
) == HARDWARE_VALUE
)) {
817 headingStr
= dumpPgValue(cmdName
, value
, dumpMask
, headingStr
);
822 static void cliPrintVar(const char *cmdName
, const clivalue_t
*var
, bool full
)
824 const void *ptr
= cliGetValuePointer(var
);
826 printValuePointer(cmdName
, var
, ptr
, full
);
829 static void cliPrintVarRange(const clivalue_t
*var
)
831 switch (var
->type
& VALUE_MODE_MASK
) {
832 case (MODE_DIRECT
): {
833 switch (var
->type
& VALUE_TYPE_MASK
) {
835 cliPrintLinef("Allowed range: 0 - %u", var
->config
.u32Max
);
840 cliPrintLinef("Allowed range: %d - %d", var
->config
.minmaxUnsigned
.min
, var
->config
.minmaxUnsigned
.max
);
844 cliPrintLinef("Allowed range: %d - %d", var
->config
.minmax
.min
, var
->config
.minmax
.max
);
850 case (MODE_LOOKUP
): {
851 const lookupTableEntry_t
*tableEntry
= &lookupTables
[var
->config
.lookup
.tableIndex
];
852 cliPrint("Allowed values: ");
853 bool firstEntry
= true;
854 for (unsigned i
= 0; i
< tableEntry
->valueCount
; i
++) {
855 if (tableEntry
->values
[i
]) {
859 cliPrintf("%s", tableEntry
->values
[i
]);
867 cliPrintLinef("Array length: %d", var
->config
.array
.length
);
870 case (MODE_STRING
): {
871 cliPrintLinef("String length: %d - %d", var
->config
.string
.minlength
, var
->config
.string
.maxlength
);
874 case (MODE_BITSET
): {
875 cliPrintLinef("Allowed values: OFF, ON");
881 static void cliSetVar(const clivalue_t
*var
, const uint32_t value
)
883 void *ptr
= cliGetValuePointer(var
);
887 if ((var
->type
& VALUE_MODE_MASK
) == MODE_BITSET
) {
888 switch (var
->type
& VALUE_TYPE_MASK
) {
890 mask
= (1 << var
->config
.bitpos
) & 0xff;
892 workValue
= *(uint8_t *)ptr
| mask
;
894 workValue
= *(uint8_t *)ptr
& ~mask
;
896 *(uint8_t *)ptr
= workValue
;
900 mask
= (1 << var
->config
.bitpos
) & 0xffff;
902 workValue
= *(uint16_t *)ptr
| mask
;
904 workValue
= *(uint16_t *)ptr
& ~mask
;
906 *(uint16_t *)ptr
= workValue
;
910 mask
= 1 << var
->config
.bitpos
;
912 workValue
= *(uint32_t *)ptr
| mask
;
914 workValue
= *(uint32_t *)ptr
& ~mask
;
916 *(uint32_t *)ptr
= workValue
;
920 switch (var
->type
& VALUE_TYPE_MASK
) {
922 *(uint8_t *)ptr
= value
;
926 *(int8_t *)ptr
= value
;
930 *(uint16_t *)ptr
= value
;
934 *(int16_t *)ptr
= value
;
938 *(uint32_t *)ptr
= value
;
944 #if defined(USE_RESOURCE_MGMT) && !defined(MINIMAL_CLI)
945 static void cliRepeat(char ch
, uint8_t len
)
948 for (int i
= 0; i
< len
; i
++) {
949 bufWriterAppend(cliWriter
, ch
);
956 static void cliPrompt(void)
958 #if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS)
959 if (processingCustomDefaults
) {
960 cliPrint("\r\nd: #");
968 static void cliShowParseError(const char *cmdName
)
970 cliPrintErrorLinef(cmdName
, "PARSING FAILED");
973 static void cliShowInvalidArgumentCountError(const char *cmdName
)
975 cliPrintErrorLinef(cmdName
, "INVALID ARGUMENT COUNT", cmdName
);
978 static void cliShowArgumentRangeError(const char *cmdName
, char *name
, int min
, int max
)
981 cliPrintErrorLinef(cmdName
, "%s NOT BETWEEN %d AND %d", name
, min
, max
);
983 cliPrintErrorLinef(cmdName
, "ARGUMENT OUT OF RANGE");
987 static const char *nextArg(const char *currentArg
)
989 const char *ptr
= strchr(currentArg
, ' ');
990 while (ptr
&& *ptr
== ' ') {
997 static const char *processChannelRangeArgs(const char *ptr
, channelRange_t
*range
, uint8_t *validArgumentCount
)
999 for (uint32_t argIndex
= 0; argIndex
< 2; argIndex
++) {
1002 int val
= atoi(ptr
);
1003 val
= CHANNEL_VALUE_TO_STEP(val
);
1004 if (val
>= MIN_MODE_RANGE_STEP
&& val
<= MAX_MODE_RANGE_STEP
) {
1005 if (argIndex
== 0) {
1006 range
->startStep
= val
;
1008 range
->endStep
= val
;
1010 (*validArgumentCount
)++;
1018 // Check if a string's length is zero
1019 static bool isEmpty(const char *string
)
1021 return (string
== NULL
|| *string
== '\0') ? true : false;
1024 static void printRxFailsafe(dumpFlags_t dumpMask
, const rxFailsafeChannelConfig_t
*rxFailsafeChannelConfigs
, const rxFailsafeChannelConfig_t
*defaultRxFailsafeChannelConfigs
, const char *headingStr
)
1026 // print out rxConfig failsafe settings
1027 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1028 for (uint32_t channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
1029 const rxFailsafeChannelConfig_t
*channelFailsafeConfig
= &rxFailsafeChannelConfigs
[channel
];
1030 const rxFailsafeChannelConfig_t
*defaultChannelFailsafeConfig
= &defaultRxFailsafeChannelConfigs
[channel
];
1031 const bool equalsDefault
= !memcmp(channelFailsafeConfig
, defaultChannelFailsafeConfig
, sizeof(*channelFailsafeConfig
));
1032 const bool requireValue
= channelFailsafeConfig
->mode
== RX_FAILSAFE_MODE_SET
;
1033 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1035 const char *format
= "rxfail %u %c %d";
1036 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1038 rxFailsafeModeCharacters
[defaultChannelFailsafeConfig
->mode
],
1039 RXFAIL_STEP_TO_CHANNEL_VALUE(defaultChannelFailsafeConfig
->step
)
1041 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1043 rxFailsafeModeCharacters
[channelFailsafeConfig
->mode
],
1044 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig
->step
)
1047 const char *format
= "rxfail %u %c";
1048 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1050 rxFailsafeModeCharacters
[defaultChannelFailsafeConfig
->mode
]
1052 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1054 rxFailsafeModeCharacters
[channelFailsafeConfig
->mode
]
1060 static void cliRxFailsafe(const char *cmdName
, char *cmdline
)
1065 if (isEmpty(cmdline
)) {
1066 // print out rxConfig failsafe settings
1067 for (channel
= 0; channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
; channel
++) {
1068 cliRxFailsafe(cmdName
, itoa(channel
, buf
, 10));
1071 const char *ptr
= cmdline
;
1072 channel
= atoi(ptr
++);
1073 if ((channel
< MAX_SUPPORTED_RC_CHANNEL_COUNT
)) {
1075 rxFailsafeChannelConfig_t
*channelFailsafeConfig
= rxFailsafeChannelConfigsMutable(channel
);
1077 const rxFailsafeChannelType_e type
= (channel
< NON_AUX_CHANNEL_COUNT
) ? RX_FAILSAFE_TYPE_FLIGHT
: RX_FAILSAFE_TYPE_AUX
;
1078 rxFailsafeChannelMode_e mode
= channelFailsafeConfig
->mode
;
1079 bool requireValue
= channelFailsafeConfig
->mode
== RX_FAILSAFE_MODE_SET
;
1083 const char *p
= strchr(rxFailsafeModeCharacters
, *(ptr
));
1085 const uint8_t requestedMode
= p
- rxFailsafeModeCharacters
;
1086 mode
= rxFailsafeModesTable
[type
][requestedMode
];
1088 mode
= RX_FAILSAFE_MODE_INVALID
;
1090 if (mode
== RX_FAILSAFE_MODE_INVALID
) {
1091 cliShowParseError(cmdName
);
1095 requireValue
= mode
== RX_FAILSAFE_MODE_SET
;
1099 if (!requireValue
) {
1100 cliShowParseError(cmdName
);
1103 uint16_t value
= atoi(ptr
);
1104 value
= CHANNEL_VALUE_TO_RXFAIL_STEP(value
);
1105 if (value
> MAX_RXFAIL_RANGE_STEP
) {
1106 cliPrintErrorLinef(cmdName
, "value out of range: %d", value
);
1110 channelFailsafeConfig
->step
= value
;
1111 } else if (requireValue
) {
1112 cliShowInvalidArgumentCountError(cmdName
);
1115 channelFailsafeConfig
->mode
= mode
;
1118 char modeCharacter
= rxFailsafeModeCharacters
[channelFailsafeConfig
->mode
];
1120 // double use of cliPrintf below
1121 // 1. acknowledge interpretation on command,
1122 // 2. query current setting on single item,
1125 cliPrintLinef("rxfail %u %c %d",
1128 RXFAIL_STEP_TO_CHANNEL_VALUE(channelFailsafeConfig
->step
)
1131 cliPrintLinef("rxfail %u %c",
1137 cliShowArgumentRangeError(cmdName
, "CHANNEL", 0, MAX_SUPPORTED_RC_CHANNEL_COUNT
- 1);
1142 static void printAux(dumpFlags_t dumpMask
, const modeActivationCondition_t
*modeActivationConditions
, const modeActivationCondition_t
*defaultModeActivationConditions
, const char *headingStr
)
1144 const char *format
= "aux %u %u %u %u %u %u %u";
1145 // print out aux channel settings
1146 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1147 for (uint32_t i
= 0; i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
; i
++) {
1148 const modeActivationCondition_t
*mac
= &modeActivationConditions
[i
];
1149 bool equalsDefault
= false;
1150 if (defaultModeActivationConditions
) {
1151 const modeActivationCondition_t
*macDefault
= &defaultModeActivationConditions
[i
];
1152 equalsDefault
= !isModeActivationConditionConfigured(mac
, macDefault
);
1153 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1154 const box_t
*box
= findBoxByBoxId(macDefault
->modeId
);
1155 const box_t
*linkedTo
= findBoxByBoxId(macDefault
->linkedTo
);
1157 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1160 macDefault
->auxChannelIndex
,
1161 MODE_STEP_TO_CHANNEL_VALUE(macDefault
->range
.startStep
),
1162 MODE_STEP_TO_CHANNEL_VALUE(macDefault
->range
.endStep
),
1163 macDefault
->modeLogic
,
1164 linkedTo
? linkedTo
->permanentId
: 0
1168 const box_t
*box
= findBoxByBoxId(mac
->modeId
);
1169 const box_t
*linkedTo
= findBoxByBoxId(mac
->linkedTo
);
1171 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1174 mac
->auxChannelIndex
,
1175 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
1176 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
),
1178 linkedTo
? linkedTo
->permanentId
: 0
1184 static void cliAux(const char *cmdName
, char *cmdline
)
1189 if (isEmpty(cmdline
)) {
1190 printAux(DUMP_MASTER
, modeActivationConditions(0), NULL
, NULL
);
1194 if (i
< MAX_MODE_ACTIVATION_CONDITION_COUNT
) {
1195 modeActivationCondition_t
*mac
= modeActivationConditionsMutable(i
);
1196 uint8_t validArgumentCount
= 0;
1200 const box_t
*box
= findBoxByPermanentId(val
);
1202 mac
->modeId
= box
->boxId
;
1203 validArgumentCount
++;
1209 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1210 mac
->auxChannelIndex
= val
;
1211 validArgumentCount
++;
1214 ptr
= processChannelRangeArgs(ptr
, &mac
->range
, &validArgumentCount
);
1218 if (val
== MODELOGIC_OR
|| val
== MODELOGIC_AND
) {
1219 mac
->modeLogic
= val
;
1220 validArgumentCount
++;
1226 const box_t
*box
= findBoxByPermanentId(val
);
1228 mac
->linkedTo
= box
->boxId
;
1229 validArgumentCount
++;
1232 if (validArgumentCount
== 4) { // for backwards compatibility
1233 mac
->modeLogic
= MODELOGIC_OR
;
1235 } else if (validArgumentCount
== 5) { // for backwards compatibility
1237 } else if (validArgumentCount
!= 6) {
1238 memset(mac
, 0, sizeof(modeActivationCondition_t
));
1240 analyzeModeActivationConditions();
1241 cliPrintLinef( "aux %u %u %u %u %u %u %u",
1243 findBoxByBoxId(mac
->modeId
)->permanentId
,
1244 mac
->auxChannelIndex
,
1245 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.startStep
),
1246 MODE_STEP_TO_CHANNEL_VALUE(mac
->range
.endStep
),
1248 findBoxByBoxId(mac
->linkedTo
)->permanentId
1251 cliShowArgumentRangeError(cmdName
, "INDEX", 0, MAX_MODE_ACTIVATION_CONDITION_COUNT
- 1);
1256 static void printSerial(dumpFlags_t dumpMask
, const serialConfig_t
*serialConfig
, const serialConfig_t
*serialConfigDefault
, const char *headingStr
)
1258 const char *format
= "serial %d %d %ld %ld %ld %ld";
1259 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1260 for (uint32_t i
= 0; i
< SERIAL_PORT_COUNT
; i
++) {
1261 if (!serialIsPortAvailable(serialConfig
->portConfigs
[i
].identifier
)) {
1264 bool equalsDefault
= false;
1265 if (serialConfigDefault
) {
1266 equalsDefault
= !memcmp(&serialConfig
->portConfigs
[i
], &serialConfigDefault
->portConfigs
[i
], sizeof(serialConfig
->portConfigs
[i
]));
1267 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1268 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1269 serialConfigDefault
->portConfigs
[i
].identifier
,
1270 serialConfigDefault
->portConfigs
[i
].functionMask
,
1271 baudRates
[serialConfigDefault
->portConfigs
[i
].msp_baudrateIndex
],
1272 baudRates
[serialConfigDefault
->portConfigs
[i
].gps_baudrateIndex
],
1273 baudRates
[serialConfigDefault
->portConfigs
[i
].telemetry_baudrateIndex
],
1274 baudRates
[serialConfigDefault
->portConfigs
[i
].blackbox_baudrateIndex
]
1277 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1278 serialConfig
->portConfigs
[i
].identifier
,
1279 serialConfig
->portConfigs
[i
].functionMask
,
1280 baudRates
[serialConfig
->portConfigs
[i
].msp_baudrateIndex
],
1281 baudRates
[serialConfig
->portConfigs
[i
].gps_baudrateIndex
],
1282 baudRates
[serialConfig
->portConfigs
[i
].telemetry_baudrateIndex
],
1283 baudRates
[serialConfig
->portConfigs
[i
].blackbox_baudrateIndex
]
1288 static void cliSerial(const char *cmdName
, char *cmdline
)
1290 const char *format
= "serial %d %d %ld %ld %ld %ld";
1291 if (isEmpty(cmdline
)) {
1292 printSerial(DUMP_MASTER
, serialConfig(), NULL
, NULL
);
1295 serialPortConfig_t portConfig
;
1296 memset(&portConfig
, 0 , sizeof(portConfig
));
1299 uint8_t validArgumentCount
= 0;
1301 const char *ptr
= cmdline
;
1303 int val
= atoi(ptr
++);
1304 serialPortConfig_t
*currentConfig
= serialFindPortConfigurationMutable(val
);
1306 if (currentConfig
) {
1307 portConfig
.identifier
= val
;
1308 validArgumentCount
++;
1313 val
= strtoul(ptr
, NULL
, 10);
1314 portConfig
.functionMask
= val
;
1315 validArgumentCount
++;
1318 for (int i
= 0; i
< 4; i
++) {
1326 uint8_t baudRateIndex
= lookupBaudRateIndex(val
);
1327 if (baudRates
[baudRateIndex
] != (uint32_t) val
) {
1333 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_1000000
) {
1336 portConfig
.msp_baudrateIndex
= baudRateIndex
;
1339 if (baudRateIndex
< BAUD_9600
|| baudRateIndex
> BAUD_115200
) {
1342 portConfig
.gps_baudrateIndex
= baudRateIndex
;
1345 if (baudRateIndex
!= BAUD_AUTO
&& baudRateIndex
> BAUD_115200
) {
1348 portConfig
.telemetry_baudrateIndex
= baudRateIndex
;
1351 if (baudRateIndex
< BAUD_19200
|| baudRateIndex
> BAUD_2470000
) {
1354 portConfig
.blackbox_baudrateIndex
= baudRateIndex
;
1358 validArgumentCount
++;
1361 if (validArgumentCount
< 6) {
1362 cliShowInvalidArgumentCountError(cmdName
);
1366 memcpy(currentConfig
, &portConfig
, sizeof(portConfig
));
1368 cliDumpPrintLinef(0, false, format
,
1369 portConfig
.identifier
,
1370 portConfig
.functionMask
,
1371 baudRates
[portConfig
.msp_baudrateIndex
],
1372 baudRates
[portConfig
.gps_baudrateIndex
],
1373 baudRates
[portConfig
.telemetry_baudrateIndex
],
1374 baudRates
[portConfig
.blackbox_baudrateIndex
]
1379 #if defined(USE_SERIAL_PASSTHROUGH)
1380 static void cbCtrlLine(void *context
, uint16_t ctrl
)
1383 int contextValue
= (int)(long)context
;
1385 pinioSet(contextValue
- 1, !(ctrl
& CTRL_LINE_STATE_DTR
));
1387 #endif /* USE_PINIO */
1390 if (!(ctrl
& CTRL_LINE_STATE_DTR
)) {
1395 static int cliParseSerialMode(const char *tok
)
1399 if (strcasestr(tok
, "rx")) {
1402 if (strcasestr(tok
, "tx")) {
1409 static void cliSerialPassthrough(const char *cmdName
, char *cmdline
)
1411 if (isEmpty(cmdline
)) {
1412 cliShowInvalidArgumentCountError(cmdName
);
1416 serialPassthroughPort_t ports
[2] = { {SERIAL_PORT_NONE
, 0, 0, NULL
}, {cliPort
->identifier
, 0, 0, cliPort
} };
1417 bool enableBaudCb
= false;
1418 int port1PinioDtr
= 0;
1419 bool port1ResetOnDtr
= false;
1420 #ifdef USE_PWM_OUTPUT
1421 bool escSensorPassthrough
= false;
1424 char* tok
= strtok_r(cmdline
, " ", &saveptr
);
1427 while (tok
!= NULL
) {
1430 if (strcasestr(tok
, "esc_sensor")) {
1431 #ifdef USE_PWM_OUTPUT
1432 escSensorPassthrough
= true;
1434 const serialPortConfig_t
*portConfig
= findSerialPortConfig(FUNCTION_ESC_SENSOR
);
1435 ports
[0].id
= portConfig
->identifier
;
1437 ports
[0].id
= atoi(tok
);
1441 ports
[0].baud
= atoi(tok
);
1444 ports
[0].mode
= cliParseSerialMode(tok
);
1447 if (strncasecmp(tok
, "reset", strlen(tok
)) == 0) {
1448 port1ResetOnDtr
= true;
1450 } else if (strncasecmp(tok
, "none", strlen(tok
)) == 0) {
1453 port1PinioDtr
= atoi(tok
);
1454 if (port1PinioDtr
< 0 || port1PinioDtr
> PINIO_COUNT
) {
1455 cliPrintLinef("Invalid PinIO number %d", port1PinioDtr
);
1458 #endif /* USE_PINIO */
1462 ports
[1].id
= atoi(tok
);
1463 ports
[1].port
= NULL
;
1466 ports
[1].baud
= atoi(tok
);
1469 ports
[1].mode
= cliParseSerialMode(tok
);
1473 tok
= strtok_r(NULL
, " ", &saveptr
);
1477 if (ports
[0].id
== ports
[1].id
) {
1478 cliPrintLinef("Port1 and port2 are same");
1482 for (int i
= 0; i
< 2; i
++) {
1483 if (findSerialPortIndexByIdentifier(ports
[i
].id
) == -1) {
1484 cliPrintLinef("Invalid port%d %d", i
+ 1, ports
[i
].id
);
1487 cliPrintLinef("Port%d: %d ", i
+ 1, ports
[i
].id
);
1491 if (ports
[0].baud
== 0 && ports
[1].id
== SERIAL_PORT_USB_VCP
) {
1492 enableBaudCb
= true;
1495 for (int i
= 0; i
< 2; i
++) {
1496 serialPort_t
**port
= &(ports
[i
].port
);
1497 if (*port
!= NULL
) {
1501 int portIndex
= i
+ 1;
1502 serialPortUsage_t
*portUsage
= findSerialPortUsageByIdentifier(ports
[i
].id
);
1503 if (!portUsage
|| portUsage
->serialPort
== NULL
) {
1504 bool isUseDefaultBaud
= false;
1505 if (ports
[i
].baud
== 0) {
1507 ports
[i
].baud
= 57600;
1508 isUseDefaultBaud
= true;
1511 if (!ports
[i
].mode
) {
1512 ports
[i
].mode
= MODE_RXTX
;
1515 *port
= openSerialPort(ports
[i
].id
, FUNCTION_NONE
, NULL
, NULL
,
1516 ports
[i
].baud
, ports
[i
].mode
,
1517 SERIAL_NOT_INVERTED
);
1519 cliPrintLinef("Port%d could not be opened.", portIndex
);
1523 if (isUseDefaultBaud
) {
1524 cliPrintf("Port%d opened, default baud = %d.\r\n", portIndex
, ports
[i
].baud
);
1526 cliPrintf("Port%d opened, baud = %d.\r\n", portIndex
, ports
[i
].baud
);
1529 *port
= portUsage
->serialPort
;
1530 // If the user supplied a mode, override the port's mode, otherwise
1531 // leave the mode unchanged. serialPassthrough() handles one-way ports.
1532 // Set the baud rate if specified
1533 if (ports
[i
].baud
) {
1534 cliPrintf("Port%d is already open, setting baud = %d.\r\n", portIndex
, ports
[i
].baud
);
1535 serialSetBaudRate(*port
, ports
[i
].baud
);
1537 cliPrintf("Port%d is already open, baud = %d.\r\n", portIndex
, (*port
)->baudRate
);
1540 if (ports
[i
].mode
&& (*port
)->mode
!= ports
[i
].mode
) {
1541 cliPrintf("Port%d mode changed from %d to %d.\r\n",
1542 portIndex
, (*port
)->mode
, ports
[i
].mode
);
1543 serialSetMode(*port
, ports
[i
].mode
);
1546 // If this port has a rx callback associated we need to remove it now.
1547 // Otherwise no data will be pushed in the serial port buffer!
1548 if ((*port
)->rxCallback
) {
1549 (*port
)->rxCallback
= NULL
;
1554 // If no baud rate is specified allow to be set via USB
1556 cliPrintLine("Port1 baud rate change over USB enabled.");
1557 // Register the right side baud rate setting routine with the left side which allows setting of the UART
1558 // baud rate over USB without setting it using the serialpassthrough command
1559 serialSetBaudRateCb(ports
[1].port
, serialSetBaudRate
, ports
[0].port
);
1562 char *resetMessage
= "";
1563 if (port1ResetOnDtr
&& ports
[1].id
== SERIAL_PORT_USB_VCP
) {
1564 resetMessage
= "or drop DTR ";
1567 cliPrintLinef("Forwarding, power cycle %sto exit.", resetMessage
);
1569 if ((ports
[1].id
== SERIAL_PORT_USB_VCP
) && (port1ResetOnDtr
1572 #endif /* USE_PINIO */
1574 // Register control line state callback
1575 serialSetCtrlLineStateCb(ports
[0].port
, cbCtrlLine
, (void *)(intptr_t)(port1PinioDtr
));
1578 // XXX Review ESC pass through under refactored motor handling
1579 #ifdef USE_PWM_OUTPUT
1580 if (escSensorPassthrough
) {
1581 // pwmDisableMotors();
1584 for (unsigned i
= 0; i
< getMotorCount(); i
++) {
1585 const ioTag_t tag
= motorConfig()->dev
.ioTags
[i
];
1587 const timerHardware_t
*timerHardware
= timerGetConfiguredByTag(tag
);
1588 if (timerHardware
) {
1589 IO_t io
= IOGetByTag(tag
);
1590 IOInit(io
, OWNER_MOTOR
, 0);
1591 IOConfigGPIO(io
, IOCFG_OUT_PP
);
1592 if (timerHardware
->output
& TIMER_OUTPUT_INVERTED
) {
1603 serialPassthrough(ports
[0].port
, ports
[1].port
, NULL
, NULL
);
1607 static void printAdjustmentRange(dumpFlags_t dumpMask
, const adjustmentRange_t
*adjustmentRanges
, const adjustmentRange_t
*defaultAdjustmentRanges
, const char *headingStr
)
1609 const char *format
= "adjrange %u 0 %u %u %u %u %u %u %u";
1610 // print out adjustment ranges channel settings
1611 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1612 for (uint32_t i
= 0; i
< MAX_ADJUSTMENT_RANGE_COUNT
; i
++) {
1613 const adjustmentRange_t
*ar
= &adjustmentRanges
[i
];
1614 bool equalsDefault
= false;
1615 if (defaultAdjustmentRanges
) {
1616 const adjustmentRange_t
*arDefault
= &defaultAdjustmentRanges
[i
];
1617 equalsDefault
= !memcmp(ar
, arDefault
, sizeof(*ar
));
1618 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1619 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1621 arDefault
->auxChannelIndex
,
1622 MODE_STEP_TO_CHANNEL_VALUE(arDefault
->range
.startStep
),
1623 MODE_STEP_TO_CHANNEL_VALUE(arDefault
->range
.endStep
),
1624 arDefault
->adjustmentConfig
,
1625 arDefault
->auxSwitchChannelIndex
,
1626 arDefault
->adjustmentCenter
,
1627 arDefault
->adjustmentScale
1630 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1632 ar
->auxChannelIndex
,
1633 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
1634 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
1635 ar
->adjustmentConfig
,
1636 ar
->auxSwitchChannelIndex
,
1637 ar
->adjustmentCenter
,
1643 static void cliAdjustmentRange(const char *cmdName
, char *cmdline
)
1645 const char *format
= "adjrange %u 0 %u %u %u %u %u %u %u";
1649 if (isEmpty(cmdline
)) {
1650 printAdjustmentRange(DUMP_MASTER
, adjustmentRanges(0), NULL
, NULL
);
1654 if (i
< MAX_ADJUSTMENT_RANGE_COUNT
) {
1655 adjustmentRange_t
*ar
= adjustmentRangesMutable(i
);
1656 uint8_t validArgumentCount
= 0;
1662 // Keeping the parameter to retain backwards compatibility for the command format.
1663 validArgumentCount
++;
1668 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1669 ar
->auxChannelIndex
= val
;
1670 validArgumentCount
++;
1674 ptr
= processChannelRangeArgs(ptr
, &ar
->range
, &validArgumentCount
);
1679 if (val
>= 0 && val
< ADJUSTMENT_FUNCTION_COUNT
) {
1680 ar
->adjustmentConfig
= val
;
1681 validArgumentCount
++;
1687 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
1688 ar
->auxSwitchChannelIndex
= val
;
1689 validArgumentCount
++;
1693 if (validArgumentCount
!= 6) {
1694 memset(ar
, 0, sizeof(adjustmentRange_t
));
1695 cliShowInvalidArgumentCountError(cmdName
);
1699 // Optional arguments
1700 ar
->adjustmentCenter
= 0;
1701 ar
->adjustmentScale
= 0;
1706 ar
->adjustmentCenter
= val
;
1707 validArgumentCount
++;
1712 ar
->adjustmentScale
= val
;
1713 validArgumentCount
++;
1716 activeAdjustmentRangeReset();
1718 cliDumpPrintLinef(0, false, format
,
1720 ar
->auxChannelIndex
,
1721 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.startStep
),
1722 MODE_STEP_TO_CHANNEL_VALUE(ar
->range
.endStep
),
1723 ar
->adjustmentConfig
,
1724 ar
->auxSwitchChannelIndex
,
1725 ar
->adjustmentCenter
,
1730 cliShowArgumentRangeError(cmdName
, "INDEX", 0, MAX_ADJUSTMENT_RANGE_COUNT
- 1);
1735 #ifndef USE_QUAD_MIXER_ONLY
1736 static void printMotorMix(dumpFlags_t dumpMask
, const motorMixer_t
*customMotorMixer
, const motorMixer_t
*defaultCustomMotorMixer
, const char *headingStr
)
1738 const char *format
= "mmix %d %s %s %s %s";
1739 char buf0
[FTOA_BUFFER_LENGTH
];
1740 char buf1
[FTOA_BUFFER_LENGTH
];
1741 char buf2
[FTOA_BUFFER_LENGTH
];
1742 char buf3
[FTOA_BUFFER_LENGTH
];
1743 for (uint32_t i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1744 if (customMotorMixer
[i
].throttle
== 0.0f
)
1746 const float thr
= customMotorMixer
[i
].throttle
;
1747 const float roll
= customMotorMixer
[i
].roll
;
1748 const float pitch
= customMotorMixer
[i
].pitch
;
1749 const float yaw
= customMotorMixer
[i
].yaw
;
1750 bool equalsDefault
= false;
1751 if (defaultCustomMotorMixer
) {
1752 const float thrDefault
= defaultCustomMotorMixer
[i
].throttle
;
1753 const float rollDefault
= defaultCustomMotorMixer
[i
].roll
;
1754 const float pitchDefault
= defaultCustomMotorMixer
[i
].pitch
;
1755 const float yawDefault
= defaultCustomMotorMixer
[i
].yaw
;
1756 const bool equalsDefault
= thr
== thrDefault
&& roll
== rollDefault
&& pitch
== pitchDefault
&& yaw
== yawDefault
;
1758 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1759 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1761 ftoa(thrDefault
, buf0
),
1762 ftoa(rollDefault
, buf1
),
1763 ftoa(pitchDefault
, buf2
),
1764 ftoa(yawDefault
, buf3
));
1766 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1774 #endif // USE_QUAD_MIXER_ONLY
1776 static void cliMotorMix(const char *cmdName
, char *cmdline
)
1778 #ifdef USE_QUAD_MIXER_ONLY
1786 if (isEmpty(cmdline
)) {
1787 printMotorMix(DUMP_MASTER
, customMotorMixer(0), NULL
, NULL
);
1788 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
1789 // erase custom mixer
1790 for (uint32_t i
= 0; i
< MAX_SUPPORTED_MOTORS
; i
++) {
1791 customMotorMixerMutable(i
)->throttle
= 0.0f
;
1793 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
1794 ptr
= nextArg(cmdline
);
1797 for (uint32_t i
= 0; ; i
++) {
1798 if (mixerNames
[i
] == NULL
) {
1799 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
1802 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
1803 mixerLoadMix(i
, customMotorMixerMutable(0));
1804 cliPrintLinef("Loaded %s", mixerNames
[i
]);
1805 cliMotorMix(cmdName
, "");
1812 uint32_t i
= atoi(ptr
); // get motor number
1813 if (i
< MAX_SUPPORTED_MOTORS
) {
1816 customMotorMixerMutable(i
)->throttle
= fastA2F(ptr
);
1821 customMotorMixerMutable(i
)->roll
= fastA2F(ptr
);
1826 customMotorMixerMutable(i
)->pitch
= fastA2F(ptr
);
1831 customMotorMixerMutable(i
)->yaw
= fastA2F(ptr
);
1835 cliShowInvalidArgumentCountError(cmdName
);
1837 printMotorMix(DUMP_MASTER
, customMotorMixer(0), NULL
, NULL
);
1840 cliShowArgumentRangeError(cmdName
, "INDEX", 0, MAX_SUPPORTED_MOTORS
- 1);
1846 static void printRxRange(dumpFlags_t dumpMask
, const rxChannelRangeConfig_t
*channelRangeConfigs
, const rxChannelRangeConfig_t
*defaultChannelRangeConfigs
, const char *headingStr
)
1848 const char *format
= "rxrange %u %u %u";
1849 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1850 for (uint32_t i
= 0; i
< NON_AUX_CHANNEL_COUNT
; i
++) {
1851 bool equalsDefault
= false;
1852 if (defaultChannelRangeConfigs
) {
1853 equalsDefault
= !memcmp(&channelRangeConfigs
[i
], &defaultChannelRangeConfigs
[i
], sizeof(channelRangeConfigs
[i
]));
1854 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1855 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
1857 defaultChannelRangeConfigs
[i
].min
,
1858 defaultChannelRangeConfigs
[i
].max
1861 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
1863 channelRangeConfigs
[i
].min
,
1864 channelRangeConfigs
[i
].max
1869 static void cliRxRange(const char *cmdName
, char *cmdline
)
1871 const char *format
= "rxrange %u %u %u";
1872 int i
, validArgumentCount
= 0;
1875 if (isEmpty(cmdline
)) {
1876 printRxRange(DUMP_MASTER
, rxChannelRangeConfigs(0), NULL
, NULL
);
1877 } else if (strcasecmp(cmdline
, "reset") == 0) {
1878 resetAllRxChannelRangeConfigurations(rxChannelRangeConfigsMutable(0));
1882 if (i
>= 0 && i
< NON_AUX_CHANNEL_COUNT
) {
1883 int rangeMin
= PWM_PULSE_MIN
, rangeMax
= PWM_PULSE_MAX
;
1887 rangeMin
= atoi(ptr
);
1888 validArgumentCount
++;
1893 rangeMax
= atoi(ptr
);
1894 validArgumentCount
++;
1897 if (validArgumentCount
!= 2) {
1898 cliShowInvalidArgumentCountError(cmdName
);
1899 } else if (rangeMin
< PWM_PULSE_MIN
|| rangeMin
> PWM_PULSE_MAX
|| rangeMax
< PWM_PULSE_MIN
|| rangeMax
> PWM_PULSE_MAX
) {
1900 cliShowArgumentRangeError(cmdName
, "range min/max", PWM_PULSE_MIN
, PWM_PULSE_MAX
);
1902 rxChannelRangeConfig_t
*channelRangeConfig
= rxChannelRangeConfigsMutable(i
);
1903 channelRangeConfig
->min
= rangeMin
;
1904 channelRangeConfig
->max
= rangeMax
;
1905 cliDumpPrintLinef(0, false, format
,
1907 channelRangeConfig
->min
,
1908 channelRangeConfig
->max
1913 cliShowArgumentRangeError(cmdName
, "CHANNEL", 0, NON_AUX_CHANNEL_COUNT
- 1);
1918 #ifdef USE_LED_STRIP_STATUS_MODE
1919 static void printLed(dumpFlags_t dumpMask
, const ledConfig_t
*ledConfigs
, const ledConfig_t
*defaultLedConfigs
, const char *headingStr
)
1921 const char *format
= "led %u %s";
1922 char ledConfigBuffer
[20];
1923 char ledConfigDefaultBuffer
[20];
1924 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1925 for (uint32_t i
= 0; i
< LED_MAX_STRIP_LENGTH
; i
++) {
1926 ledConfig_t ledConfig
= ledConfigs
[i
];
1927 generateLedConfig(&ledConfig
, ledConfigBuffer
, sizeof(ledConfigBuffer
));
1928 bool equalsDefault
= false;
1929 if (defaultLedConfigs
) {
1930 ledConfig_t ledConfigDefault
= defaultLedConfigs
[i
];
1931 equalsDefault
= ledConfig
== ledConfigDefault
;
1932 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1933 generateLedConfig(&ledConfigDefault
, ledConfigDefaultBuffer
, sizeof(ledConfigDefaultBuffer
));
1934 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, i
, ledConfigDefaultBuffer
);
1936 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, i
, ledConfigBuffer
);
1940 static void cliLed(const char *cmdName
, char *cmdline
)
1942 const char *format
= "led %u %s";
1943 char ledConfigBuffer
[20];
1947 if (isEmpty(cmdline
)) {
1948 printLed(DUMP_MASTER
, ledStripStatusModeConfig()->ledConfigs
, NULL
, NULL
);
1952 if (i
>= 0 && i
< LED_MAX_STRIP_LENGTH
) {
1953 ptr
= nextArg(cmdline
);
1954 if (parseLedStripConfig(i
, ptr
)) {
1955 generateLedConfig((ledConfig_t
*)&ledStripStatusModeConfig()->ledConfigs
[i
], ledConfigBuffer
, sizeof(ledConfigBuffer
));
1956 cliDumpPrintLinef(0, false, format
, i
, ledConfigBuffer
);
1958 cliShowParseError(cmdName
);
1961 cliShowArgumentRangeError(cmdName
, "INDEX", 0, LED_MAX_STRIP_LENGTH
- 1);
1966 static void printColor(dumpFlags_t dumpMask
, const hsvColor_t
*colors
, const hsvColor_t
*defaultColors
, const char *headingStr
)
1968 const char *format
= "color %u %d,%u,%u";
1969 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
1970 for (uint32_t i
= 0; i
< LED_CONFIGURABLE_COLOR_COUNT
; i
++) {
1971 const hsvColor_t
*color
= &colors
[i
];
1972 bool equalsDefault
= false;
1973 if (defaultColors
) {
1974 const hsvColor_t
*colorDefault
= &defaultColors
[i
];
1975 equalsDefault
= !memcmp(color
, colorDefault
, sizeof(*color
));
1976 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
1977 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, i
,colorDefault
->h
, colorDefault
->s
, colorDefault
->v
);
1979 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, i
, color
->h
, color
->s
, color
->v
);
1983 static void cliColor(const char *cmdName
, char *cmdline
)
1985 const char *format
= "color %u %d,%u,%u";
1986 if (isEmpty(cmdline
)) {
1987 printColor(DUMP_MASTER
, ledStripStatusModeConfig()->colors
, NULL
, NULL
);
1989 const char *ptr
= cmdline
;
1990 const int i
= atoi(ptr
);
1991 if (i
< LED_CONFIGURABLE_COLOR_COUNT
) {
1992 ptr
= nextArg(cmdline
);
1993 if (parseColor(i
, ptr
)) {
1994 const hsvColor_t
*color
= &ledStripStatusModeConfig()->colors
[i
];
1995 cliDumpPrintLinef(0, false, format
, i
, color
->h
, color
->s
, color
->v
);
1997 cliShowParseError(cmdName
);
2000 cliShowArgumentRangeError(cmdName
, "INDEX", 0, LED_CONFIGURABLE_COLOR_COUNT
- 1);
2005 static void printModeColor(dumpFlags_t dumpMask
, const ledStripStatusModeConfig_t
*ledStripStatusModeConfig
, const ledStripStatusModeConfig_t
*defaultLedStripConfig
, const char *headingStr
)
2007 const char *format
= "mode_color %u %u %u";
2008 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
2009 for (uint32_t i
= 0; i
< LED_MODE_COUNT
; i
++) {
2010 for (uint32_t j
= 0; j
< LED_DIRECTION_COUNT
; j
++) {
2011 int colorIndex
= ledStripStatusModeConfig
->modeColors
[i
].color
[j
];
2012 bool equalsDefault
= false;
2013 if (defaultLedStripConfig
) {
2014 int colorIndexDefault
= defaultLedStripConfig
->modeColors
[i
].color
[j
];
2015 equalsDefault
= colorIndex
== colorIndexDefault
;
2016 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2017 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, i
, j
, colorIndexDefault
);
2019 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, i
, j
, colorIndex
);
2023 for (uint32_t j
= 0; j
< LED_SPECIAL_COLOR_COUNT
; j
++) {
2024 const int colorIndex
= ledStripStatusModeConfig
->specialColors
.color
[j
];
2025 bool equalsDefault
= false;
2026 if (defaultLedStripConfig
) {
2027 const int colorIndexDefault
= defaultLedStripConfig
->specialColors
.color
[j
];
2028 equalsDefault
= colorIndex
== colorIndexDefault
;
2029 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2030 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, LED_SPECIAL
, j
, colorIndexDefault
);
2032 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, LED_SPECIAL
, j
, colorIndex
);
2035 const int ledStripAuxChannel
= ledStripStatusModeConfig
->ledstrip_aux_channel
;
2036 bool equalsDefault
= false;
2037 if (defaultLedStripConfig
) {
2038 const int ledStripAuxChannelDefault
= defaultLedStripConfig
->ledstrip_aux_channel
;
2039 equalsDefault
= ledStripAuxChannel
== ledStripAuxChannelDefault
;
2040 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2041 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, LED_AUX_CHANNEL
, 0, ledStripAuxChannelDefault
);
2043 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, LED_AUX_CHANNEL
, 0, ledStripAuxChannel
);
2046 static void cliModeColor(const char *cmdName
, char *cmdline
)
2048 if (isEmpty(cmdline
)) {
2049 printModeColor(DUMP_MASTER
, ledStripStatusModeConfig(), NULL
, NULL
);
2051 enum {MODE
= 0, FUNCTION
, COLOR
, ARGS_COUNT
};
2052 int args
[ARGS_COUNT
];
2055 const char* ptr
= strtok_r(cmdline
, " ", &saveptr
);
2056 while (ptr
&& argNo
< ARGS_COUNT
) {
2057 args
[argNo
++] = atoi(ptr
);
2058 ptr
= strtok_r(NULL
, " ", &saveptr
);
2061 if (ptr
!= NULL
|| argNo
!= ARGS_COUNT
) {
2062 cliShowInvalidArgumentCountError(cmdName
);
2066 int modeIdx
= args
[MODE
];
2067 int funIdx
= args
[FUNCTION
];
2068 int color
= args
[COLOR
];
2069 if (!setModeColor(modeIdx
, funIdx
, color
)) {
2070 cliShowParseError(cmdName
);
2073 // values are validated
2074 cliPrintLinef("mode_color %u %u %u", modeIdx
, funIdx
, color
);
2080 static void printServo(dumpFlags_t dumpMask
, const servoParam_t
*servoParams
, const servoParam_t
*defaultServoParams
, const char *headingStr
)
2082 // print out servo settings
2083 const char *format
= "servo %u %d %d %d %d %d";
2084 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
2085 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2086 const servoParam_t
*servoConf
= &servoParams
[i
];
2087 bool equalsDefault
= false;
2088 if (defaultServoParams
) {
2089 const servoParam_t
*defaultServoConf
= &defaultServoParams
[i
];
2090 equalsDefault
= !memcmp(servoConf
, defaultServoConf
, sizeof(*servoConf
));
2091 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2092 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
2094 defaultServoConf
->min
,
2095 defaultServoConf
->max
,
2096 defaultServoConf
->middle
,
2097 defaultServoConf
->rate
,
2098 defaultServoConf
->forwardFromChannel
2101 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
2107 servoConf
->forwardFromChannel
2110 // print servo directions
2111 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2112 const char *format
= "smix reverse %d %d r";
2113 const servoParam_t
*servoConf
= &servoParams
[i
];
2114 const servoParam_t
*servoConfDefault
= &defaultServoParams
[i
];
2115 if (defaultServoParams
) {
2116 bool equalsDefault
= servoConf
->reversedSources
== servoConfDefault
->reversedSources
;
2117 for (uint32_t channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
2118 equalsDefault
= ~(servoConf
->reversedSources
^ servoConfDefault
->reversedSources
) & (1 << channel
);
2119 if (servoConfDefault
->reversedSources
& (1 << channel
)) {
2120 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, i
, channel
);
2122 if (servoConf
->reversedSources
& (1 << channel
)) {
2123 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, i
, channel
);
2127 for (uint32_t channel
= 0; channel
< INPUT_SOURCE_COUNT
; channel
++) {
2128 if (servoConf
->reversedSources
& (1 << channel
)) {
2129 cliDumpPrintLinef(dumpMask
, true, format
, i
, channel
);
2136 static void cliServo(const char *cmdName
, char *cmdline
)
2138 const char *format
= "servo %u %d %d %d %d %d";
2139 enum { SERVO_ARGUMENT_COUNT
= 6 };
2140 int16_t arguments
[SERVO_ARGUMENT_COUNT
];
2142 servoParam_t
*servo
;
2147 if (isEmpty(cmdline
)) {
2148 printServo(DUMP_MASTER
, servoParams(0), NULL
, NULL
);
2150 int validArgumentCount
= 0;
2154 // Command line is integers (possibly negative) separated by spaces, no other characters allowed.
2156 // If command line doesn't fit the format, don't modify the config
2158 if (*ptr
== '-' || (*ptr
>= '0' && *ptr
<= '9')) {
2159 if (validArgumentCount
>= SERVO_ARGUMENT_COUNT
) {
2160 cliShowInvalidArgumentCountError(cmdName
);
2164 arguments
[validArgumentCount
++] = atoi(ptr
);
2168 } while (*ptr
>= '0' && *ptr
<= '9');
2169 } else if (*ptr
== ' ') {
2172 cliShowParseError(cmdName
);
2177 enum {INDEX
= 0, MIN
, MAX
, MIDDLE
, RATE
, FORWARD
};
2179 i
= arguments
[INDEX
];
2181 // Check we got the right number of args and the servo index is correct (don't validate the other values)
2182 if (validArgumentCount
!= SERVO_ARGUMENT_COUNT
|| i
< 0 || i
>= MAX_SUPPORTED_SERVOS
) {
2183 cliShowInvalidArgumentCountError(cmdName
);
2187 servo
= servoParamsMutable(i
);
2190 arguments
[MIN
] < PWM_PULSE_MIN
|| arguments
[MIN
] > PWM_PULSE_MAX
||
2191 arguments
[MAX
] < PWM_PULSE_MIN
|| arguments
[MAX
] > PWM_PULSE_MAX
||
2192 arguments
[MIDDLE
] < arguments
[MIN
] || arguments
[MIDDLE
] > arguments
[MAX
] ||
2193 arguments
[MIN
] > arguments
[MAX
] ||
2194 arguments
[RATE
] < -100 || arguments
[RATE
] > 100 ||
2195 arguments
[FORWARD
] >= MAX_SUPPORTED_RC_CHANNEL_COUNT
2197 cliShowArgumentRangeError(cmdName
, NULL
, 0, 0);
2201 servo
->min
= arguments
[MIN
];
2202 servo
->max
= arguments
[MAX
];
2203 servo
->middle
= arguments
[MIDDLE
];
2204 servo
->rate
= arguments
[RATE
];
2205 servo
->forwardFromChannel
= arguments
[FORWARD
];
2207 cliDumpPrintLinef(0, false, format
,
2213 servo
->forwardFromChannel
2221 static void printServoMix(dumpFlags_t dumpMask
, const servoMixer_t
*customServoMixers
, const servoMixer_t
*defaultCustomServoMixers
, const char *headingStr
)
2223 const char *format
= "smix %d %d %d %d %d %d %d %d";
2224 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
2225 for (uint32_t i
= 0; i
< MAX_SERVO_RULES
; i
++) {
2226 const servoMixer_t customServoMixer
= customServoMixers
[i
];
2227 if (customServoMixer
.rate
== 0) {
2231 bool equalsDefault
= false;
2232 if (defaultCustomServoMixers
) {
2233 servoMixer_t customServoMixerDefault
= defaultCustomServoMixers
[i
];
2234 equalsDefault
= !memcmp(&customServoMixer
, &customServoMixerDefault
, sizeof(customServoMixer
));
2236 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2237 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
2239 customServoMixerDefault
.targetChannel
,
2240 customServoMixerDefault
.inputSource
,
2241 customServoMixerDefault
.rate
,
2242 customServoMixerDefault
.speed
,
2243 customServoMixerDefault
.min
,
2244 customServoMixerDefault
.max
,
2245 customServoMixerDefault
.box
2248 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
2250 customServoMixer
.targetChannel
,
2251 customServoMixer
.inputSource
,
2252 customServoMixer
.rate
,
2253 customServoMixer
.speed
,
2254 customServoMixer
.min
,
2255 customServoMixer
.max
,
2256 customServoMixer
.box
2261 static void cliServoMix(const char *cmdName
, char *cmdline
)
2263 int args
[8], check
= 0;
2264 int len
= strlen(cmdline
);
2267 printServoMix(DUMP_MASTER
, customServoMixers(0), NULL
, NULL
);
2268 } else if (strncasecmp(cmdline
, "reset", 5) == 0) {
2269 // erase custom mixer
2270 memset(customServoMixers_array(), 0, sizeof(*customServoMixers_array()));
2271 for (uint32_t i
= 0; i
< MAX_SUPPORTED_SERVOS
; i
++) {
2272 servoParamsMutable(i
)->reversedSources
= 0;
2274 } else if (strncasecmp(cmdline
, "load", 4) == 0) {
2275 const char *ptr
= nextArg(cmdline
);
2278 for (uint32_t i
= 0; ; i
++) {
2279 if (mixerNames
[i
] == NULL
) {
2280 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
2283 if (strncasecmp(ptr
, mixerNames
[i
], len
) == 0) {
2284 servoMixerLoadMix(i
);
2285 cliPrintLinef("Loaded %s", mixerNames
[i
]);
2286 cliServoMix(cmdName
, "");
2291 } else if (strncasecmp(cmdline
, "reverse", 7) == 0) {
2292 enum {SERVO
= 0, INPUT
, REVERSE
, ARGS_COUNT
};
2293 char *ptr
= strchr(cmdline
, ' ');
2297 for (uint32_t inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++)
2298 cliPrintf("\ti%d", inputSource
);
2301 for (uint32_t servoIndex
= 0; servoIndex
< MAX_SUPPORTED_SERVOS
; servoIndex
++) {
2302 cliPrintf("%d", servoIndex
);
2303 for (uint32_t inputSource
= 0; inputSource
< INPUT_SOURCE_COUNT
; inputSource
++) {
2304 cliPrintf("\t%s ", (servoParams(servoIndex
)->reversedSources
& (1 << inputSource
)) ? "r" : "n");
2312 ptr
= strtok_r(ptr
, " ", &saveptr
);
2313 while (ptr
!= NULL
&& check
< ARGS_COUNT
- 1) {
2314 args
[check
++] = atoi(ptr
);
2315 ptr
= strtok_r(NULL
, " ", &saveptr
);
2318 if (ptr
== NULL
|| check
!= ARGS_COUNT
- 1) {
2319 cliShowInvalidArgumentCountError(cmdName
);
2323 if (args
[SERVO
] >= 0 && args
[SERVO
] < MAX_SUPPORTED_SERVOS
2324 && args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
2325 && (*ptr
== 'r' || *ptr
== 'n')) {
2327 servoParamsMutable(args
[SERVO
])->reversedSources
|= 1 << args
[INPUT
];
2329 servoParamsMutable(args
[SERVO
])->reversedSources
&= ~(1 << args
[INPUT
]);
2332 cliShowArgumentRangeError(cmdName
, "servo", 0, MAX_SUPPORTED_SERVOS
);
2336 cliServoMix(cmdName
, "reverse");
2338 enum {RULE
= 0, TARGET
, INPUT
, RATE
, SPEED
, MIN
, MAX
, BOX
, ARGS_COUNT
};
2340 char *ptr
= strtok_r(cmdline
, " ", &saveptr
);
2341 while (ptr
!= NULL
&& check
< ARGS_COUNT
) {
2342 args
[check
++] = atoi(ptr
);
2343 ptr
= strtok_r(NULL
, " ", &saveptr
);
2346 if (ptr
!= NULL
|| check
!= ARGS_COUNT
) {
2347 cliShowInvalidArgumentCountError(cmdName
);
2351 int32_t i
= args
[RULE
];
2352 if (i
>= 0 && i
< MAX_SERVO_RULES
&&
2353 args
[TARGET
] >= 0 && args
[TARGET
] < MAX_SUPPORTED_SERVOS
&&
2354 args
[INPUT
] >= 0 && args
[INPUT
] < INPUT_SOURCE_COUNT
&&
2355 args
[RATE
] >= -100 && args
[RATE
] <= 100 &&
2356 args
[SPEED
] >= 0 && args
[SPEED
] <= MAX_SERVO_SPEED
&&
2357 args
[MIN
] >= 0 && args
[MIN
] <= 100 &&
2358 args
[MAX
] >= 0 && args
[MAX
] <= 100 && args
[MIN
] < args
[MAX
] &&
2359 args
[BOX
] >= 0 && args
[BOX
] <= MAX_SERVO_BOXES
) {
2360 customServoMixersMutable(i
)->targetChannel
= args
[TARGET
];
2361 customServoMixersMutable(i
)->inputSource
= args
[INPUT
];
2362 customServoMixersMutable(i
)->rate
= args
[RATE
];
2363 customServoMixersMutable(i
)->speed
= args
[SPEED
];
2364 customServoMixersMutable(i
)->min
= args
[MIN
];
2365 customServoMixersMutable(i
)->max
= args
[MAX
];
2366 customServoMixersMutable(i
)->box
= args
[BOX
];
2367 cliServoMix(cmdName
, "");
2369 cliShowArgumentRangeError(cmdName
, NULL
, 0, 0);
2377 static void cliWriteBytes(const uint8_t *buffer
, int count
)
2386 static void cliSdInfo(const char *cmdName
, char *cmdline
)
2391 cliPrint("SD card: ");
2393 if (sdcardConfig()->mode
== SDCARD_MODE_NONE
) {
2394 cliPrintLine("Not configured");
2399 if (!sdcard_isInserted()) {
2400 cliPrintLine("None inserted");
2404 if (!sdcard_isFunctional() || !sdcard_isInitialized()) {
2405 cliPrintLine("Startup failed");
2409 const sdcardMetadata_t
*metadata
= sdcard_getMetadata();
2411 cliPrintf("Manufacturer 0x%x, %ukB, %02d/%04d, v%d.%d, '",
2412 metadata
->manufacturerID
,
2413 metadata
->numBlocks
/ 2, /* One block is half a kB */
2414 metadata
->productionMonth
,
2415 metadata
->productionYear
,
2416 metadata
->productRevisionMajor
,
2417 metadata
->productRevisionMinor
2420 cliWriteBytes((uint8_t*)metadata
->productName
, sizeof(metadata
->productName
));
2422 cliPrint("'\r\n" "Filesystem: ");
2424 switch (afatfs_getFilesystemState()) {
2425 case AFATFS_FILESYSTEM_STATE_READY
:
2428 case AFATFS_FILESYSTEM_STATE_INITIALIZATION
:
2429 cliPrint("Initializing");
2431 case AFATFS_FILESYSTEM_STATE_UNKNOWN
:
2432 case AFATFS_FILESYSTEM_STATE_FATAL
:
2435 switch (afatfs_getLastError()) {
2436 case AFATFS_ERROR_BAD_MBR
:
2437 cliPrint(" - no FAT MBR partitions");
2439 case AFATFS_ERROR_BAD_FILESYSTEM_HEADER
:
2440 cliPrint(" - bad FAT header");
2442 case AFATFS_ERROR_GENERIC
:
2443 case AFATFS_ERROR_NONE
:
2444 ; // Nothing more detailed to print
2454 #ifdef USE_FLASH_CHIP
2455 static void cliFlashInfo(const char *cmdName
, char *cmdline
)
2460 const flashGeometry_t
*layout
= flashGetGeometry();
2462 cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u JEDEC ID=0x%08x",
2463 layout
->sectors
, layout
->sectorSize
, layout
->pagesPerSector
, layout
->pageSize
, layout
->totalSize
, layout
->jedecId
);
2465 for (uint8_t index
= 0; index
< FLASH_MAX_PARTITIONS
; index
++) {
2466 const flashPartition_t
*partition
;
2468 cliPrintLine("Partitions:");
2470 partition
= flashPartitionFindByIndex(index
);
2474 cliPrintLinef(" %d: %s %u %u", index
, flashPartitionGetTypeName(partition
->type
), partition
->startSector
, partition
->endSector
);
2477 const flashPartition_t
*flashPartition
= flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS
);
2479 cliPrintLinef("FlashFS size=%u, usedSize=%u",
2480 FLASH_PARTITION_SECTOR_COUNT(flashPartition
) * layout
->sectorSize
,
2485 #endif // USE_FLASH_CHIP
2488 static void cliFlashErase(const char *cmdName
, char *cmdline
)
2493 if (!flashfsIsSupported()) {
2499 cliPrintLine("Erasing, please wait ... ");
2501 cliPrintLine("Erasing,");
2505 flashfsEraseCompletely();
2507 while (!flashfsIsReady()) {
2519 beeper(BEEPER_BLACKBOX_ERASE
);
2521 cliPrintLine("Done.");
2524 #ifdef USE_FLASH_TOOLS
2525 static void cliFlashVerify(const char *cmdName
, char *cmdline
)
2529 cliPrintLine("Verifying");
2530 if (flashfsVerifyEntireFlash()) {
2531 cliPrintLine("Success");
2533 cliPrintErrorLinef(cmdName
, "Failed");
2537 static void cliFlashWrite(const char *cmdName
, char *cmdline
)
2539 const uint32_t address
= atoi(cmdline
);
2540 const char *text
= strchr(cmdline
, ' ');
2543 cliShowInvalidArgumentCountError(cmdName
);
2545 flashfsSeekAbs(address
);
2546 flashfsWrite((uint8_t*)text
, strlen(text
), true);
2549 cliPrintLinef("Wrote %u bytes at %u.", strlen(text
), address
);
2553 static void cliFlashRead(const char *cmdName
, char *cmdline
)
2555 uint32_t address
= atoi(cmdline
);
2557 const char *nextArg
= strchr(cmdline
, ' ');
2560 cliShowInvalidArgumentCountError(cmdName
);
2562 uint32_t length
= atoi(nextArg
);
2564 cliPrintLinef("Reading %u bytes at %u:", length
, address
);
2567 while (length
> 0) {
2568 int bytesRead
= flashfsReadAbs(address
, buffer
, length
< sizeof(buffer
) ? length
: sizeof(buffer
));
2570 for (int i
= 0; i
< bytesRead
; i
++) {
2571 cliWrite(buffer
[i
]);
2574 length
-= bytesRead
;
2575 address
+= bytesRead
;
2577 if (bytesRead
== 0) {
2578 //Assume we reached the end of the volume or something fatal happened
2585 #endif // USE_FLASH_TOOLS
2586 #endif // USE_FLASHFS
2588 #ifdef USE_VTX_CONTROL
2589 static void printVtx(dumpFlags_t dumpMask
, const vtxConfig_t
*vtxConfig
, const vtxConfig_t
*vtxConfigDefault
, const char *headingStr
)
2591 // print out vtx channel settings
2592 const char *format
= "vtx %u %u %u %u %u %u %u";
2593 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
2594 bool equalsDefault
= false;
2595 for (uint32_t i
= 0; i
< MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
; i
++) {
2596 const vtxChannelActivationCondition_t
*cac
= &vtxConfig
->vtxChannelActivationConditions
[i
];
2597 if (vtxConfigDefault
) {
2598 const vtxChannelActivationCondition_t
*cacDefault
= &vtxConfigDefault
->vtxChannelActivationConditions
[i
];
2599 equalsDefault
= !memcmp(cac
, cacDefault
, sizeof(*cac
));
2600 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2601 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
,
2603 cacDefault
->auxChannelIndex
,
2605 cacDefault
->channel
,
2607 MODE_STEP_TO_CHANNEL_VALUE(cacDefault
->range
.startStep
),
2608 MODE_STEP_TO_CHANNEL_VALUE(cacDefault
->range
.endStep
)
2611 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
,
2613 cac
->auxChannelIndex
,
2617 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.startStep
),
2618 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.endStep
)
2623 static void cliVtx(const char *cmdName
, char *cmdline
)
2625 const char *format
= "vtx %u %u %u %u %u %u %u";
2629 if (isEmpty(cmdline
)) {
2630 printVtx(DUMP_MASTER
, vtxConfig(), NULL
, NULL
);
2632 #ifdef USE_VTX_TABLE
2633 const uint8_t maxBandIndex
= vtxTableConfig()->bands
;
2634 const uint8_t maxChannelIndex
= vtxTableConfig()->channels
;
2635 const uint8_t maxPowerIndex
= vtxTableConfig()->powerLevels
;
2637 const uint8_t maxBandIndex
= VTX_TABLE_MAX_BANDS
;
2638 const uint8_t maxChannelIndex
= VTX_TABLE_MAX_CHANNELS
;
2639 const uint8_t maxPowerIndex
= VTX_TABLE_MAX_POWER_LEVELS
;
2643 if (i
< MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
) {
2644 vtxChannelActivationCondition_t
*cac
= &vtxConfigMutable()->vtxChannelActivationConditions
[i
];
2645 uint8_t validArgumentCount
= 0;
2649 if (val
>= 0 && val
< MAX_AUX_CHANNEL_COUNT
) {
2650 cac
->auxChannelIndex
= val
;
2651 validArgumentCount
++;
2657 if (val
>= 0 && val
<= maxBandIndex
) {
2659 validArgumentCount
++;
2665 if (val
>= 0 && val
<= maxChannelIndex
) {
2667 validArgumentCount
++;
2673 if (val
>= 0 && val
<= maxPowerIndex
) {
2675 validArgumentCount
++;
2678 ptr
= processChannelRangeArgs(ptr
, &cac
->range
, &validArgumentCount
);
2680 if (validArgumentCount
!= 6) {
2681 memset(cac
, 0, sizeof(vtxChannelActivationCondition_t
));
2682 cliShowInvalidArgumentCountError(cmdName
);
2684 cliDumpPrintLinef(0, false, format
,
2686 cac
->auxChannelIndex
,
2690 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.startStep
),
2691 MODE_STEP_TO_CHANNEL_VALUE(cac
->range
.endStep
)
2695 cliShowArgumentRangeError(cmdName
, "INDEX", 0, MAX_CHANNEL_ACTIVATION_CONDITION_COUNT
- 1);
2700 #endif // VTX_CONTROL
2702 #ifdef USE_VTX_TABLE
2704 static char *formatVtxTableBandFrequency(const bool isFactory
, const uint16_t *frequency
, int channels
)
2706 static char freqbuf
[5 * VTX_TABLE_MAX_CHANNELS
+ 8 + 1];
2707 char freqtmp
[5 + 1];
2709 strcat(freqbuf
, isFactory
? " FACTORY" : " CUSTOM ");
2710 for (int channel
= 0; channel
< channels
; channel
++) {
2711 tfp_sprintf(freqtmp
, " %4d", frequency
[channel
]);
2712 strcat(freqbuf
, freqtmp
);
2717 static const char *printVtxTableBand(dumpFlags_t dumpMask
, int band
, const vtxTableConfig_t
*currentConfig
, const vtxTableConfig_t
*defaultConfig
, const char *headingStr
)
2719 char *fmt
= "vtxtable band %d %s %c%s";
2720 bool equalsDefault
= false;
2722 if (defaultConfig
) {
2723 equalsDefault
= true;
2724 if (strcasecmp(currentConfig
->bandNames
[band
], defaultConfig
->bandNames
[band
])) {
2725 equalsDefault
= false;
2727 if (currentConfig
->bandLetters
[band
] != defaultConfig
->bandLetters
[band
]) {
2728 equalsDefault
= false;
2730 for (int channel
= 0; channel
< VTX_TABLE_MAX_CHANNELS
; channel
++) {
2731 if (currentConfig
->frequency
[band
][channel
] != defaultConfig
->frequency
[band
][channel
]) {
2732 equalsDefault
= false;
2735 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2736 char *freqbuf
= formatVtxTableBandFrequency(defaultConfig
->isFactoryBand
[band
], defaultConfig
->frequency
[band
], defaultConfig
->channels
);
2737 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, band
+ 1, defaultConfig
->bandNames
[band
], defaultConfig
->bandLetters
[band
], freqbuf
);
2740 char *freqbuf
= formatVtxTableBandFrequency(currentConfig
->isFactoryBand
[band
], currentConfig
->frequency
[band
], currentConfig
->channels
);
2741 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, band
+ 1, currentConfig
->bandNames
[band
], currentConfig
->bandLetters
[band
], freqbuf
);
2745 static char *formatVtxTablePowerValues(const uint16_t *levels
, int count
)
2747 // (max 4 digit + 1 space) per level
2748 static char pwrbuf
[5 * VTX_TABLE_MAX_POWER_LEVELS
+ 1];
2751 for (int pwrindex
= 0; pwrindex
< count
; pwrindex
++) {
2752 tfp_sprintf(pwrtmp
, " %d", levels
[pwrindex
]);
2753 strcat(pwrbuf
, pwrtmp
);
2758 static const char *printVtxTablePowerValues(dumpFlags_t dumpMask
, const vtxTableConfig_t
*currentConfig
, const vtxTableConfig_t
*defaultConfig
, const char *headingStr
)
2760 char *fmt
= "vtxtable powervalues%s";
2761 bool equalsDefault
= false;
2762 if (defaultConfig
) {
2763 equalsDefault
= true;
2764 for (int pwrindex
= 0; pwrindex
< VTX_TABLE_MAX_POWER_LEVELS
; pwrindex
++) {
2765 if (defaultConfig
->powerValues
[pwrindex
] != currentConfig
->powerValues
[pwrindex
]) {
2766 equalsDefault
= false;
2769 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2770 char *pwrbuf
= formatVtxTablePowerValues(defaultConfig
->powerValues
, VTX_TABLE_MAX_POWER_LEVELS
);
2771 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, pwrbuf
);
2774 char *pwrbuf
= formatVtxTablePowerValues(currentConfig
->powerValues
, currentConfig
->powerLevels
);
2775 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, pwrbuf
);
2779 static char *formatVtxTablePowerLabels(const char labels
[VTX_TABLE_MAX_POWER_LEVELS
][VTX_TABLE_POWER_LABEL_LENGTH
+ 1], int count
)
2781 static char pwrbuf
[(VTX_TABLE_POWER_LABEL_LENGTH
+ 1) * VTX_TABLE_MAX_POWER_LEVELS
+ 1];
2782 char pwrtmp
[(VTX_TABLE_POWER_LABEL_LENGTH
+ 1) + 1];
2784 for (int pwrindex
= 0; pwrindex
< count
; pwrindex
++) {
2785 strcat(pwrbuf
, " ");
2786 strcpy(pwrtmp
, labels
[pwrindex
]);
2787 // trim trailing space
2789 while ((sp
= strchr(pwrtmp
, ' '))) {
2792 strcat(pwrbuf
, pwrtmp
);
2797 static const char *printVtxTablePowerLabels(dumpFlags_t dumpMask
, const vtxTableConfig_t
*currentConfig
, const vtxTableConfig_t
*defaultConfig
, const char *headingStr
)
2799 char *fmt
= "vtxtable powerlabels%s";
2800 bool equalsDefault
= false;
2801 if (defaultConfig
) {
2802 equalsDefault
= true;
2803 for (int pwrindex
= 0; pwrindex
< VTX_TABLE_MAX_POWER_LEVELS
; pwrindex
++) {
2804 if (strcasecmp(defaultConfig
->powerLabels
[pwrindex
], currentConfig
->powerLabels
[pwrindex
])) {
2805 equalsDefault
= false;
2808 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2809 char *pwrbuf
= formatVtxTablePowerLabels(defaultConfig
->powerLabels
, VTX_TABLE_MAX_POWER_LEVELS
);
2810 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, pwrbuf
);
2813 char *pwrbuf
= formatVtxTablePowerLabels(currentConfig
->powerLabels
, currentConfig
->powerLevels
);
2814 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, pwrbuf
);
2818 static void printVtxTable(dumpFlags_t dumpMask
, const vtxTableConfig_t
*currentConfig
, const vtxTableConfig_t
*defaultConfig
, const char *headingStr
)
2823 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
2826 equalsDefault
= false;
2827 fmt
= "vtxtable bands %d";
2828 if (defaultConfig
) {
2829 equalsDefault
= (defaultConfig
->bands
== currentConfig
->bands
);
2830 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2831 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, defaultConfig
->bands
);
2833 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, currentConfig
->bands
);
2836 equalsDefault
= false;
2837 fmt
= "vtxtable channels %d";
2838 if (defaultConfig
) {
2839 equalsDefault
= (defaultConfig
->channels
== currentConfig
->channels
);
2840 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2841 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, defaultConfig
->channels
);
2843 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, currentConfig
->channels
);
2847 for (int band
= 0; band
< currentConfig
->bands
; band
++) {
2848 headingStr
= printVtxTableBand(dumpMask
, band
, currentConfig
, defaultConfig
, headingStr
);
2853 equalsDefault
= false;
2854 fmt
= "vtxtable powerlevels %d";
2855 if (defaultConfig
) {
2856 equalsDefault
= (defaultConfig
->powerLevels
== currentConfig
->powerLevels
);
2857 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
2858 cliDefaultPrintLinef(dumpMask
, equalsDefault
, fmt
, defaultConfig
->powerLevels
);
2860 cliDumpPrintLinef(dumpMask
, equalsDefault
, fmt
, currentConfig
->powerLevels
);
2865 headingStr
= printVtxTablePowerValues(dumpMask
, currentConfig
, defaultConfig
, headingStr
);
2866 headingStr
= printVtxTablePowerLabels(dumpMask
, currentConfig
, defaultConfig
, headingStr
);
2869 static void cliVtxTable(const char *cmdName
, char *cmdline
)
2874 // Band number or nothing
2875 tok
= strtok_r(cmdline
, " ", &saveptr
);
2878 printVtxTable(DUMP_MASTER
| HIDE_UNUSED
, vtxTableConfigMutable(), NULL
, NULL
);
2882 if (strcasecmp(tok
, "bands") == 0) {
2883 tok
= strtok_r(NULL
, " ", &saveptr
);
2884 int bands
= atoi(tok
);
2885 if (bands
< 0 || bands
> VTX_TABLE_MAX_BANDS
) {
2886 cliShowArgumentRangeError(cmdName
, "BAND COUNT", 0, VTX_TABLE_MAX_BANDS
);
2889 if (bands
< vtxTableConfigMutable()->bands
) {
2890 for (int i
= bands
; i
< vtxTableConfigMutable()->bands
; i
++) {
2891 vtxTableConfigClearBand(vtxTableConfigMutable(), i
);
2894 vtxTableConfigMutable()->bands
= bands
;
2896 } else if (strcasecmp(tok
, "channels") == 0) {
2897 tok
= strtok_r(NULL
, " ", &saveptr
);
2899 int channels
= atoi(tok
);
2900 if (channels
< 0 || channels
> VTX_TABLE_MAX_CHANNELS
) {
2901 cliShowArgumentRangeError(cmdName
, "CHANNEL COUNT", 0, VTX_TABLE_MAX_CHANNELS
);
2904 if (channels
< vtxTableConfigMutable()->channels
) {
2905 for (int i
= 0; i
< VTX_TABLE_MAX_BANDS
; i
++) {
2906 vtxTableConfigClearChannels(vtxTableConfigMutable(), i
, channels
);
2909 vtxTableConfigMutable()->channels
= channels
;
2911 } else if (strcasecmp(tok
, "powerlevels") == 0) {
2912 // Number of power levels
2913 tok
= strtok_r(NULL
, " ", &saveptr
);
2915 int levels
= atoi(tok
);
2916 if (levels
< 0 || levels
> VTX_TABLE_MAX_POWER_LEVELS
) {
2917 cliShowArgumentRangeError(cmdName
, "POWER LEVEL COUNT", 0, VTX_TABLE_MAX_POWER_LEVELS
);
2919 if (levels
< vtxTableConfigMutable()->powerLevels
) {
2920 vtxTableConfigClearPowerValues(vtxTableConfigMutable(), levels
);
2921 vtxTableConfigClearPowerLabels(vtxTableConfigMutable(), levels
);
2923 vtxTableConfigMutable()->powerLevels
= levels
;
2926 // XXX Show current level count?
2930 } else if (strcasecmp(tok
, "powervalues") == 0) {
2932 uint16_t power
[VTX_TABLE_MAX_POWER_LEVELS
];
2934 int levels
= vtxTableConfigMutable()->powerLevels
;
2936 memset(power
, 0, sizeof(power
));
2938 for (count
= 0; count
< levels
&& (tok
= strtok_r(NULL
, " ", &saveptr
)); count
++) {
2939 int value
= atoi(tok
);
2940 power
[count
] = value
;
2943 // Check remaining tokens
2945 if (count
< levels
) {
2946 cliPrintErrorLinef(cmdName
, "NOT ENOUGH VALUES (EXPECTED %d)", levels
);
2948 } else if ((tok
= strtok_r(NULL
, " ", &saveptr
))) {
2949 cliPrintErrorLinef(cmdName
, "TOO MANY VALUES (EXPECTED %d)", levels
);
2953 for (int i
= 0; i
< VTX_TABLE_MAX_POWER_LEVELS
; i
++) {
2954 vtxTableConfigMutable()->powerValues
[i
] = power
[i
];
2957 } else if (strcasecmp(tok
, "powerlabels") == 0) {
2959 char label
[VTX_TABLE_MAX_POWER_LEVELS
][VTX_TABLE_POWER_LABEL_LENGTH
+ 1];
2960 int levels
= vtxTableConfigMutable()->powerLevels
;
2962 for (count
= 0; count
< levels
&& (tok
= strtok_r(NULL
, " ", &saveptr
)); count
++) {
2963 strncpy(label
[count
], tok
, VTX_TABLE_POWER_LABEL_LENGTH
);
2964 for (unsigned i
= 0; i
< strlen(label
[count
]); i
++) {
2965 label
[count
][i
] = toupper(label
[count
][i
]);
2969 // Check remaining tokens
2971 if (count
< levels
) {
2972 cliPrintErrorLinef(cmdName
, "NOT ENOUGH LABELS (EXPECTED %d)", levels
);
2974 } else if ((tok
= strtok_r(NULL
, " ", &saveptr
))) {
2975 cliPrintErrorLinef(cmdName
, "TOO MANY LABELS (EXPECTED %d)", levels
);
2979 for (int i
= 0; i
< count
; i
++) {
2980 vtxTableStrncpyWithPad(vtxTableConfigMutable()->powerLabels
[i
], label
[i
], VTX_TABLE_POWER_LABEL_LENGTH
);
2982 } else if (strcasecmp(tok
, "band") == 0) {
2984 int bands
= vtxTableConfigMutable()->bands
;
2986 tok
= strtok_r(NULL
, " ", &saveptr
);
2991 int band
= atoi(tok
);
2994 if (band
< 0 || band
>= bands
) {
2995 cliShowArgumentRangeError(cmdName
, "BAND NUMBER", 1, bands
);
3000 tok
= strtok_r(NULL
, " ", &saveptr
);
3006 char bandname
[VTX_TABLE_BAND_NAME_LENGTH
+ 1];
3007 memset(bandname
, 0, VTX_TABLE_BAND_NAME_LENGTH
+ 1);
3008 strncpy(bandname
, tok
, VTX_TABLE_BAND_NAME_LENGTH
);
3009 for (unsigned i
= 0; i
< strlen(bandname
); i
++) {
3010 bandname
[i
] = toupper(bandname
[i
]);
3014 tok
= strtok_r(NULL
, " ", &saveptr
);
3020 char bandletter
= toupper(tok
[0]);
3022 uint16_t bandfreq
[VTX_TABLE_MAX_CHANNELS
];
3024 int channels
= vtxTableConfigMutable()->channels
;
3025 bool isFactory
= false;
3027 for (channel
= 0; channel
< channels
&& (tok
= strtok_r(NULL
, " ", &saveptr
)); channel
++) {
3028 if (channel
== 0 && !isdigit(tok
[0])) {
3030 if (strcasecmp(tok
, "FACTORY") == 0) {
3032 } else if (strcasecmp(tok
, "CUSTOM") == 0) {
3035 cliPrintErrorLinef(cmdName
, "INVALID FACTORY FLAG %s (EXPECTED FACTORY OR CUSTOM)", tok
);
3039 int freq
= atoi(tok
);
3041 cliPrintErrorLinef(cmdName
, "INVALID FREQUENCY %s", tok
);
3044 bandfreq
[channel
] = freq
;
3047 if (channel
< channels
) {
3048 cliPrintErrorLinef(cmdName
, "NOT ENOUGH FREQUENCIES (EXPECTED %d)", channels
);
3050 } else if ((tok
= strtok_r(NULL
, " ", &saveptr
))) {
3051 cliPrintErrorLinef(cmdName
, "TOO MANY FREQUENCIES (EXPECTED %d)", channels
);
3055 vtxTableStrncpyWithPad(vtxTableConfigMutable()->bandNames
[band
], bandname
, VTX_TABLE_BAND_NAME_LENGTH
);
3056 vtxTableConfigMutable()->bandLetters
[band
] = bandletter
;
3058 for (int i
= 0; i
< channel
; i
++) {
3059 vtxTableConfigMutable()->frequency
[band
][i
] = bandfreq
[i
];
3061 vtxTableConfigMutable()->isFactoryBand
[band
] = isFactory
;
3064 cliPrintErrorLinef(cmdName
, "INVALID SUBCOMMAND %s", tok
);
3068 static void cliVtxInfo(const char *cmdName
, char *cmdline
)
3072 // Display the available power levels
3073 uint16_t levels
[VTX_TABLE_MAX_POWER_LEVELS
];
3074 uint16_t powers
[VTX_TABLE_MAX_POWER_LEVELS
];
3075 vtxDevice_t
*vtxDevice
= vtxCommonDevice();
3077 uint8_t level_count
= vtxCommonGetVTXPowerLevels(vtxDevice
, levels
, powers
);
3080 for (int i
= 0; i
< level_count
; i
++) {
3081 cliPrintLinef("level %d dBm, power %d mW", levels
[i
], powers
[i
]);
3084 cliPrintErrorLinef(cmdName
, "NO POWER VALUES DEFINED");
3087 cliPrintErrorLinef(cmdName
, "NO VTX");
3090 #endif // USE_VTX_TABLE
3092 #if defined(USE_SIMPLIFIED_TUNING)
3093 static void applySimplifiedTuningAllProfiles(void)
3095 for (unsigned pidProfileIndex
= 0; pidProfileIndex
< PID_PROFILE_COUNT
; pidProfileIndex
++) {
3096 applySimplifiedTuning(pidProfilesMutable(pidProfileIndex
), gyroConfigMutable());
3100 static void cliSimplifiedTuning(const char *cmdName
, char *cmdline
)
3102 if (strcasecmp(cmdline
, "apply") == 0) {
3103 applySimplifiedTuningAllProfiles();
3105 cliPrintLine("Applied simplified tuning.");
3106 } else if (strcasecmp(cmdline
, "disable") == 0) {
3107 for (unsigned pidProfileIndex
= 0; pidProfileIndex
< PID_PROFILE_COUNT
; pidProfileIndex
++) {
3108 disableSimplifiedTuning(pidProfilesMutable(pidProfileIndex
), gyroConfigMutable());
3111 cliPrintLine("Disabled simplified tuning.");
3113 cliShowParseError(cmdName
);
3118 static void printCraftName(dumpFlags_t dumpMask
, const pilotConfig_t
*pilotConfig
)
3120 const bool equalsDefault
= strlen(pilotConfig
->craftName
) == 0;
3121 cliDumpPrintLinef(dumpMask
, equalsDefault
, "\r\n# name: %s", equalsDefault
? emptyName
: pilotConfig
->craftName
);
3124 #if defined(USE_BOARD_INFO)
3126 static void printBoardName(dumpFlags_t dumpMask
)
3128 if (!(dumpMask
& DO_DIFF
) || strlen(getBoardName())) {
3129 cliPrintLinef("board_name %s", getBoardName());
3133 static void cliBoardName(const char *cmdName
, char *cmdline
)
3135 const unsigned int len
= strlen(cmdline
);
3136 const char *boardName
= getBoardName();
3137 if (len
> 0 && strlen(boardName
) != 0 && boardInformationIsSet() && (len
!= strlen(boardName
) || strncmp(boardName
, cmdline
, len
))) {
3138 cliPrintErrorLinef(cmdName
, ERROR_MESSAGE
, "BOARD_NAME", boardName
);
3140 if (len
> 0 && !configIsInCopy
&& setBoardName(cmdline
)) {
3141 boardInformationUpdated
= true;
3143 cliPrintHashLine("Set board_name.");
3145 printBoardName(DUMP_ALL
);
3149 static void printManufacturerId(dumpFlags_t dumpMask
)
3151 if (!(dumpMask
& DO_DIFF
) || strlen(getManufacturerId())) {
3152 cliPrintLinef("manufacturer_id %s", getManufacturerId());
3156 static void cliManufacturerId(const char *cmdName
, char *cmdline
)
3158 const unsigned int len
= strlen(cmdline
);
3159 const char *manufacturerId
= getManufacturerId();
3160 if (len
> 0 && boardInformationIsSet() && strlen(manufacturerId
) != 0 && (len
!= strlen(manufacturerId
) || strncmp(manufacturerId
, cmdline
, len
))) {
3161 cliPrintErrorLinef(cmdName
, ERROR_MESSAGE
, "MANUFACTURER_ID", manufacturerId
);
3163 if (len
> 0 && !configIsInCopy
&& setManufacturerId(cmdline
)) {
3164 boardInformationUpdated
= true;
3166 cliPrintHashLine("Set manufacturer_id.");
3168 printManufacturerId(DUMP_ALL
);
3172 #if defined(USE_SIGNATURE)
3173 static void writeSignature(char *signatureStr
, uint8_t *signature
)
3175 for (unsigned i
= 0; i
< SIGNATURE_LENGTH
; i
++) {
3176 tfp_sprintf(&signatureStr
[2 * i
], "%02x", signature
[i
]);
3180 static void cliSignature(const char *cmdName
, char *cmdline
)
3182 const int len
= strlen(cmdline
);
3184 uint8_t signature
[SIGNATURE_LENGTH
] = {0};
3186 if (len
!= 2 * SIGNATURE_LENGTH
) {
3187 cliPrintErrorLinef(cmdName
, "INVALID LENGTH: %d (EXPECTED: %d)", len
, 2 * SIGNATURE_LENGTH
);
3192 #define BLOCK_SIZE 2
3193 for (unsigned i
= 0; i
< SIGNATURE_LENGTH
; i
++) {
3194 char temp
[BLOCK_SIZE
+ 1];
3195 strncpy(temp
, &cmdline
[i
* BLOCK_SIZE
], BLOCK_SIZE
);
3196 temp
[BLOCK_SIZE
] = '\0';
3198 unsigned result
= strtoul(temp
, &end
, 16);
3199 if (end
== &temp
[BLOCK_SIZE
]) {
3200 signature
[i
] = result
;
3202 cliPrintErrorLinef(cmdName
, "INVALID CHARACTER FOUND: %c", end
[0]);
3210 char signatureStr
[SIGNATURE_LENGTH
* 2 + 1] = {0};
3211 if (len
> 0 && signatureIsSet() && memcmp(signature
, getSignature(), SIGNATURE_LENGTH
)) {
3212 writeSignature(signatureStr
, getSignature());
3213 cliPrintErrorLinef(cmdName
, ERROR_MESSAGE
, "SIGNATURE", signatureStr
);
3215 if (len
> 0 && !configIsInCopy
&& setSignature(signature
)) {
3216 signatureUpdated
= true;
3218 writeSignature(signatureStr
, getSignature());
3220 cliPrintHashLine("Set signature.");
3221 } else if (signatureUpdated
|| signatureIsSet()) {
3222 writeSignature(signatureStr
, getSignature());
3225 cliPrintLinef("signature %s", signatureStr
);
3230 #undef ERROR_MESSAGE
3232 #endif // USE_BOARD_INFO
3234 static void cliMcuId(const char *cmdName
, char *cmdline
)
3239 cliPrintLinef("mcu_id %08x%08x%08x", U_ID_0
, U_ID_1
, U_ID_2
);
3242 static void printFeature(dumpFlags_t dumpMask
, const uint32_t mask
, const uint32_t defaultMask
, const char *headingStr
)
3244 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
3245 for (uint32_t i
= 0; featureNames
[i
]; i
++) { // disabled features first
3246 if (strcmp(featureNames
[i
], emptyString
) != 0) { //Skip unused
3247 const char *format
= "feature -%s";
3248 const bool equalsDefault
= (~defaultMask
| mask
) & (1 << i
);
3249 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
3250 cliDefaultPrintLinef(dumpMask
, (defaultMask
| ~mask
) & (1 << i
), format
, featureNames
[i
]);
3251 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, featureNames
[i
]);
3254 for (uint32_t i
= 0; featureNames
[i
]; i
++) { // enabled features
3255 if (strcmp(featureNames
[i
], emptyString
) != 0) { //Skip unused
3256 const char *format
= "feature %s";
3257 if (defaultMask
& (1 << i
)) {
3258 cliDefaultPrintLinef(dumpMask
, (~defaultMask
| mask
) & (1 << i
), format
, featureNames
[i
]);
3260 if (mask
& (1 << i
)) {
3261 const bool equalsDefault
= (defaultMask
| ~mask
) & (1 << i
);
3262 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
3263 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, featureNames
[i
]);
3269 static void cliFeature(const char *cmdName
, char *cmdline
)
3271 uint32_t len
= strlen(cmdline
);
3272 const uint32_t mask
= featureConfig()->enabledFeatures
;
3274 cliPrint("Enabled: ");
3275 for (uint32_t i
= 0; ; i
++) {
3276 if (featureNames
[i
] == NULL
) {
3279 if (mask
& (1 << i
)) {
3280 cliPrintf("%s ", featureNames
[i
]);
3284 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
3285 cliPrint("Available:");
3286 for (uint32_t i
= 0; ; i
++) {
3287 if (featureNames
[i
] == NULL
)
3289 if (strcmp(featureNames
[i
], emptyString
) != 0) //Skip unused
3290 cliPrintf(" %s", featureNames
[i
]);
3297 bool remove
= false;
3298 if (cmdline
[0] == '-') {
3301 cmdline
++; // skip over -
3305 for (uint32_t i
= 0; ; i
++) {
3306 if (featureNames
[i
] == NULL
) {
3307 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
3311 if (strncasecmp(cmdline
, featureNames
[i
], len
) == 0) {
3314 if (feature
& FEATURE_GPS
) {
3315 cliPrintLine("unavailable");
3319 #ifndef USE_RANGEFINDER
3320 if (feature
& FEATURE_RANGEFINDER
) {
3321 cliPrintLine("unavailable");
3326 featureConfigClear(feature
);
3327 cliPrint("Disabled");
3329 featureConfigSet(feature
);
3330 cliPrint("Enabled");
3332 cliPrintLinef(" %s", featureNames
[i
]);
3339 #if defined(USE_BEEPER)
3340 static void printBeeper(dumpFlags_t dumpMask
, const uint32_t offFlags
, const uint32_t offFlagsDefault
, const char *name
, const uint32_t allowedFlags
, const char *headingStr
)
3342 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
3343 const uint8_t beeperCount
= beeperTableEntryCount();
3344 for (int32_t i
= 0; i
< beeperCount
- 1; i
++) {
3345 if (beeperModeMaskForTableIndex(i
) & allowedFlags
) {
3346 const char *formatOff
= "%s -%s";
3347 const char *formatOn
= "%s %s";
3348 const uint32_t beeperModeMask
= beeperModeMaskForTableIndex(i
);
3349 cliDefaultPrintLinef(dumpMask
, ~(offFlags
^ offFlagsDefault
) & beeperModeMask
, offFlags
& beeperModeMask
? formatOn
: formatOff
, name
, beeperNameForTableIndex(i
));
3350 const bool equalsDefault
= ~(offFlags
^ offFlagsDefault
) & beeperModeMask
;
3351 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
3352 cliDumpPrintLinef(dumpMask
, equalsDefault
, offFlags
& beeperModeMask
? formatOff
: formatOn
, name
, beeperNameForTableIndex(i
));
3357 static void processBeeperCommand(const char *cmdName
, char *cmdline
, uint32_t *offFlags
, const uint32_t allowedFlags
)
3359 uint32_t len
= strlen(cmdline
);
3360 uint8_t beeperCount
= beeperTableEntryCount();
3363 cliPrintf("Disabled:");
3364 for (int32_t i
= 0; ; i
++) {
3365 if (i
== beeperCount
- 1) {
3371 if (beeperModeMaskForTableIndex(i
) & *offFlags
)
3372 cliPrintf(" %s", beeperNameForTableIndex(i
));
3375 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
3376 cliPrint("Available:");
3377 for (uint32_t i
= 0; i
< beeperCount
; i
++) {
3378 if (beeperModeMaskForTableIndex(i
) & allowedFlags
) {
3379 cliPrintf(" %s", beeperNameForTableIndex(i
));
3384 bool remove
= false;
3385 if (cmdline
[0] == '-') {
3386 remove
= true; // this is for beeper OFF condition
3391 for (uint32_t i
= 0; ; i
++) {
3392 if (i
== beeperCount
) {
3393 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
3396 if (strncasecmp(cmdline
, beeperNameForTableIndex(i
), len
) == 0 && beeperModeMaskForTableIndex(i
) & (allowedFlags
| BEEPER_GET_FLAG(BEEPER_ALL
))) {
3397 if (remove
) { // beeper off
3398 if (i
== BEEPER_ALL
- 1) {
3399 *offFlags
= allowedFlags
;
3401 *offFlags
|= beeperModeMaskForTableIndex(i
);
3403 cliPrint("Disabled");
3406 if (i
== BEEPER_ALL
- 1) {
3409 *offFlags
&= ~beeperModeMaskForTableIndex(i
);
3411 cliPrint("Enabled");
3413 cliPrintLinef(" %s", beeperNameForTableIndex(i
));
3420 #if defined(USE_DSHOT)
3421 static void cliBeacon(const char *cmdName
, char *cmdline
)
3423 processBeeperCommand(cmdName
, cmdline
, &(beeperConfigMutable()->dshotBeaconOffFlags
), DSHOT_BEACON_ALLOWED_MODES
);
3427 static void cliBeeper(const char *cmdName
, char *cmdline
)
3429 processBeeperCommand(cmdName
, cmdline
, &(beeperConfigMutable()->beeper_off_flags
), BEEPER_ALLOWED_MODES
);
3433 #if defined(USE_RX_BIND)
3434 static void cliRxBind(const char *cmdName
, char *cmdline
)
3437 if (!startRxBind()) {
3438 cliPrintErrorLinef(cmdName
, "Not supported.");
3440 cliPrintLinef("Binding...");
3445 static void printMap(dumpFlags_t dumpMask
, const rxConfig_t
*rxConfig
, const rxConfig_t
*defaultRxConfig
, const char *headingStr
)
3447 bool equalsDefault
= true;
3449 char bufDefault
[16];
3452 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
3453 for (i
= 0; i
< RX_MAPPABLE_CHANNEL_COUNT
; i
++) {
3454 buf
[rxConfig
->rcmap
[i
]] = rcChannelLetters
[i
];
3455 if (defaultRxConfig
) {
3456 bufDefault
[defaultRxConfig
->rcmap
[i
]] = rcChannelLetters
[i
];
3457 equalsDefault
= equalsDefault
&& (rxConfig
->rcmap
[i
] == defaultRxConfig
->rcmap
[i
]);
3462 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
3463 const char *formatMap
= "map %s";
3464 if (defaultRxConfig
) {
3465 bufDefault
[i
] = '\0';
3466 cliDefaultPrintLinef(dumpMask
, equalsDefault
, formatMap
, bufDefault
);
3468 cliDumpPrintLinef(dumpMask
, equalsDefault
, formatMap
, buf
);
3472 static void cliMap(const char *cmdName
, char *cmdline
)
3475 char buf
[RX_MAPPABLE_CHANNEL_COUNT
+ 1];
3477 uint32_t len
= strlen(cmdline
);
3478 if (len
== RX_MAPPABLE_CHANNEL_COUNT
) {
3480 for (i
= 0; i
< RX_MAPPABLE_CHANNEL_COUNT
; i
++) {
3481 buf
[i
] = toupper((unsigned char)cmdline
[i
]);
3485 for (i
= 0; i
< RX_MAPPABLE_CHANNEL_COUNT
; i
++) {
3486 buf
[i
] = toupper((unsigned char)cmdline
[i
]);
3488 if (strchr(rcChannelLetters
, buf
[i
]) && !strchr(buf
+ i
+ 1, buf
[i
]))
3491 cliShowParseError(cmdName
);
3494 parseRcChannels(buf
, rxConfigMutable());
3495 } else if (len
> 0) {
3496 cliShowInvalidArgumentCountError(cmdName
);
3500 for (i
= 0; i
< RX_MAPPABLE_CHANNEL_COUNT
; i
++) {
3501 buf
[rxConfig()->rcmap
[i
]] = rcChannelLetters
[i
];
3505 cliPrintLinef("map %s", buf
);
3508 static char *skipSpace(char *buffer
)
3510 while (*(buffer
) == ' ') {
3517 static char *checkCommand(char *cmdline
, const char *command
)
3519 if (!strncasecmp(cmdline
, command
, strlen(command
)) // command names match
3520 && (isspace((unsigned)cmdline
[strlen(command
)]) || cmdline
[strlen(command
)] == 0)) {
3521 return skipSpace(cmdline
+ strlen(command
) + 1);
3527 static void cliRebootEx(rebootTarget_e rebootTarget
)
3529 cliPrint("\r\nRebooting");
3531 waitForSerialPortToFinishTransmitting(cliPort
);
3534 switch (rebootTarget
) {
3535 case REBOOT_TARGET_BOOTLOADER_ROM
:
3536 systemResetToBootloader(BOOTLOADER_REQUEST_ROM
);
3539 #if defined(USE_FLASH_BOOT_LOADER)
3540 case REBOOT_TARGET_BOOTLOADER_FLASH
:
3541 systemResetToBootloader(BOOTLOADER_REQUEST_FLASH
);
3545 case REBOOT_TARGET_FIRMWARE
:
3553 static void cliReboot(void)
3555 cliRebootEx(REBOOT_TARGET_FIRMWARE
);
3558 static void cliBootloader(const char *cmdName
, char *cmdline
)
3560 rebootTarget_e rebootTarget
;
3562 #if !defined(USE_FLASH_BOOT_LOADER)
3565 strncasecmp(cmdline
, "rom", 3) == 0) {
3566 rebootTarget
= REBOOT_TARGET_BOOTLOADER_ROM
;
3568 cliPrintHashLine("restarting in ROM bootloader mode");
3569 #if defined(USE_FLASH_BOOT_LOADER)
3570 } else if (isEmpty(cmdline
) || strncasecmp(cmdline
, "flash", 5) == 0) {
3571 rebootTarget
= REBOOT_TARGET_BOOTLOADER_FLASH
;
3573 cliPrintHashLine("restarting in flash bootloader mode");
3576 cliPrintErrorLinef(cmdName
, "Invalid option");
3581 cliRebootEx(rebootTarget
);
3584 static void cliExit(const char *cmdName
, char *cmdline
)
3589 cliPrintHashLine("leaving CLI mode, unsaved changes lost");
3595 // incase a motor was left running during motortest, clear it here
3596 mixerResetDisarmedMotors();
3601 static void cliGpsPassthrough(const char *cmdName
, char *cmdline
)
3606 gpsEnablePassthrough(cliPort
);
3610 #if defined(USE_GYRO_REGISTER_DUMP) && !defined(SIMULATOR_BUILD)
3611 static void cliPrintGyroRegisters(uint8_t whichSensor
)
3613 cliPrintLinef("# WHO_AM_I 0x%X", gyroReadRegister(whichSensor
, MPU_RA_WHO_AM_I
));
3614 cliPrintLinef("# CONFIG 0x%X", gyroReadRegister(whichSensor
, MPU_RA_CONFIG
));
3615 cliPrintLinef("# GYRO_CONFIG 0x%X", gyroReadRegister(whichSensor
, MPU_RA_GYRO_CONFIG
));
3618 static void cliDumpGyroRegisters(const char *cmdName
, char *cmdline
)
3623 #ifdef USE_MULTI_GYRO
3624 if ((gyroConfig()->gyro_to_use
== GYRO_CONFIG_USE_GYRO_1
) || (gyroConfig()->gyro_to_use
== GYRO_CONFIG_USE_GYRO_BOTH
)) {
3625 cliPrintLinef("\r\n# Gyro 1");
3626 cliPrintGyroRegisters(GYRO_CONFIG_USE_GYRO_1
);
3628 if ((gyroConfig()->gyro_to_use
== GYRO_CONFIG_USE_GYRO_2
) || (gyroConfig()->gyro_to_use
== GYRO_CONFIG_USE_GYRO_BOTH
)) {
3629 cliPrintLinef("\r\n# Gyro 2");
3630 cliPrintGyroRegisters(GYRO_CONFIG_USE_GYRO_2
);
3633 cliPrintGyroRegisters(GYRO_CONFIG_USE_GYRO_1
);
3639 static int parseOutputIndex(const char *cmdName
, char *pch
, bool allowAllEscs
)
3641 int outputIndex
= atoi(pch
);
3642 if ((outputIndex
>= 0) && (outputIndex
< getMotorCount())) {
3643 cliPrintLinef("Using output %d.", outputIndex
);
3644 } else if (allowAllEscs
&& outputIndex
== ALL_MOTORS
) {
3645 cliPrintLinef("Using all outputs.");
3647 cliPrintErrorLinef(cmdName
, "INVALID OUTPUT NUMBER. RANGE: 0 - %d.", getMotorCount() - 1);
3655 #if defined(USE_DSHOT)
3656 #if defined(USE_ESC_SENSOR) && defined(USE_ESC_SENSOR_INFO)
3658 #define ESC_INFO_KISS_V1_EXPECTED_FRAME_SIZE 15
3659 #define ESC_INFO_KISS_V2_EXPECTED_FRAME_SIZE 21
3660 #define ESC_INFO_BLHELI32_EXPECTED_FRAME_SIZE 64
3668 #define ESC_INFO_VERSION_POSITION 12
3670 static void printEscInfo(const char *cmdName
, const uint8_t *escInfoBuffer
, uint8_t bytesRead
)
3672 bool escInfoReceived
= false;
3673 if (bytesRead
> ESC_INFO_VERSION_POSITION
) {
3674 uint8_t escInfoVersion
;
3675 uint8_t frameLength
;
3676 if (escInfoBuffer
[ESC_INFO_VERSION_POSITION
] == 254) {
3677 escInfoVersion
= ESC_INFO_BLHELI32
;
3678 frameLength
= ESC_INFO_BLHELI32_EXPECTED_FRAME_SIZE
;
3679 } else if (escInfoBuffer
[ESC_INFO_VERSION_POSITION
] == 255) {
3680 escInfoVersion
= ESC_INFO_KISS_V2
;
3681 frameLength
= ESC_INFO_KISS_V2_EXPECTED_FRAME_SIZE
;
3683 escInfoVersion
= ESC_INFO_KISS_V1
;
3684 frameLength
= ESC_INFO_KISS_V1_EXPECTED_FRAME_SIZE
;
3687 if (bytesRead
== frameLength
) {
3688 escInfoReceived
= true;
3690 if (calculateCrc8(escInfoBuffer
, frameLength
- 1) == escInfoBuffer
[frameLength
- 1]) {
3691 uint8_t firmwareVersion
= 0;
3692 uint8_t firmwareSubVersion
= 0;
3693 uint8_t escType
= 0;
3694 switch (escInfoVersion
) {
3695 case ESC_INFO_KISS_V1
:
3696 firmwareVersion
= escInfoBuffer
[12];
3697 firmwareSubVersion
= (escInfoBuffer
[13] & 0x1f) + 97;
3698 escType
= (escInfoBuffer
[13] & 0xe0) >> 5;
3701 case ESC_INFO_KISS_V2
:
3702 firmwareVersion
= escInfoBuffer
[13];
3703 firmwareSubVersion
= escInfoBuffer
[14];
3704 escType
= escInfoBuffer
[15];
3707 case ESC_INFO_BLHELI32
:
3708 firmwareVersion
= escInfoBuffer
[13];
3709 firmwareSubVersion
= escInfoBuffer
[14];
3710 escType
= escInfoBuffer
[15];
3715 cliPrint("ESC Type: ");
3716 switch (escInfoVersion
) {
3717 case ESC_INFO_KISS_V1
:
3718 case ESC_INFO_KISS_V2
:
3721 cliPrintLine("KISS8A");
3725 cliPrintLine("KISS16A");
3729 cliPrintLine("KISS24A");
3733 cliPrintLine("KISS Ultralite");
3737 cliPrintLine("unknown");
3743 case ESC_INFO_BLHELI32
:
3745 char *escType
= (char *)(escInfoBuffer
+ 31);
3747 cliPrintLine(escType
);
3753 cliPrint("MCU Serial No: 0x");
3754 for (int i
= 0; i
< 12; i
++) {
3755 if (i
&& (i
% 3 == 0)) {
3758 cliPrintf("%02x", escInfoBuffer
[i
]);
3762 switch (escInfoVersion
) {
3763 case ESC_INFO_KISS_V1
:
3764 case ESC_INFO_KISS_V2
:
3765 cliPrintLinef("Firmware Version: %d.%02d%c", firmwareVersion
/ 100, firmwareVersion
% 100, (char)firmwareSubVersion
);
3768 case ESC_INFO_BLHELI32
:
3769 cliPrintLinef("Firmware Version: %d.%02d%", firmwareVersion
, firmwareSubVersion
);
3773 if (escInfoVersion
== ESC_INFO_KISS_V2
|| escInfoVersion
== ESC_INFO_BLHELI32
) {
3774 cliPrintLinef("Rotation Direction: %s", escInfoBuffer
[16] ? "reversed" : "normal");
3775 cliPrintLinef("3D: %s", escInfoBuffer
[17] ? "on" : "off");
3776 if (escInfoVersion
== ESC_INFO_BLHELI32
) {
3777 uint8_t setting
= escInfoBuffer
[18];
3778 cliPrint("Low voltage Limit: ");
3781 cliPrintLine("off");
3785 cliPrintLine("unsupported");
3789 cliPrintLinef("%d.%01d", setting
/ 10, setting
% 10);
3794 setting
= escInfoBuffer
[19];
3795 cliPrint("Current Limit: ");
3798 cliPrintLine("off");
3802 cliPrintLine("unsupported");
3806 cliPrintLinef("%d", setting
);
3811 for (int i
= 0; i
< 4; i
++) {
3812 setting
= escInfoBuffer
[i
+ 20];
3813 cliPrintLinef("LED %d: %s", i
, setting
? (setting
== 255) ? "unsupported" : "on" : "off");
3818 cliPrintErrorLinef(cmdName
, "CHECKSUM ERROR.");
3823 if (!escInfoReceived
) {
3824 cliPrintLine("No Info.");
3828 static void executeEscInfoCommand(const char *cmdName
, uint8_t escIndex
)
3830 cliPrintLinef("Info for ESC %d:", escIndex
);
3832 uint8_t escInfoBuffer
[ESC_INFO_BLHELI32_EXPECTED_FRAME_SIZE
];
3834 startEscDataRead(escInfoBuffer
, ESC_INFO_BLHELI32_EXPECTED_FRAME_SIZE
);
3836 dshotCommandWrite(escIndex
, getMotorCount(), DSHOT_CMD_ESC_INFO
, DSHOT_CMD_TYPE_BLOCKING
);
3840 printEscInfo(cmdName
, escInfoBuffer
, getNumberEscBytesRead());
3842 #endif // USE_ESC_SENSOR && USE_ESC_SENSOR_INFO
3844 static void cliDshotProg(const char *cmdName
, char *cmdline
)
3846 if (isEmpty(cmdline
) || !isMotorProtocolDshot()) {
3847 cliShowParseError(cmdName
);
3853 char *pch
= strtok_r(cmdline
, " ", &saveptr
);
3856 bool firstCommand
= true;
3857 while (pch
!= NULL
) {
3860 escIndex
= parseOutputIndex(cmdName
, pch
, true);
3861 if (escIndex
== -1) {
3868 int command
= atoi(pch
);
3869 if (command
>= 0 && command
< DSHOT_MIN_THROTTLE
) {
3871 // pwmDisableMotors();
3874 firstCommand
= false;
3877 if (command
!= DSHOT_CMD_ESC_INFO
) {
3878 dshotCommandWrite(escIndex
, getMotorCount(), command
, DSHOT_CMD_TYPE_BLOCKING
);
3880 #if defined(USE_ESC_SENSOR) && defined(USE_ESC_SENSOR_INFO)
3881 if (featureIsEnabled(FEATURE_ESC_SENSOR
)) {
3882 if (escIndex
!= ALL_MOTORS
) {
3883 executeEscInfoCommand(cmdName
, escIndex
);
3885 for (uint8_t i
= 0; i
< getMotorCount(); i
++) {
3886 executeEscInfoCommand(cmdName
, i
);
3892 cliPrintLine("Not supported.");
3896 cliPrintLinef("Command Sent: %d", command
);
3899 cliPrintErrorLinef(cmdName
, "INVALID COMMAND. RANGE: 1 - %d.", DSHOT_MIN_THROTTLE
- 1);
3907 pch
= strtok_r(NULL
, " ", &saveptr
);
3914 #ifdef USE_ESCSERIAL
3915 static void cliEscPassthrough(const char *cmdName
, char *cmdline
)
3917 if (isEmpty(cmdline
)) {
3918 cliShowInvalidArgumentCountError(cmdName
);
3924 char *pch
= strtok_r(cmdline
, " ", &saveptr
);
3928 while (pch
!= NULL
) {
3931 if (strncasecmp(pch
, "sk", strlen(pch
)) == 0) {
3932 mode
= PROTOCOL_SIMONK
;
3933 } else if (strncasecmp(pch
, "bl", strlen(pch
)) == 0) {
3934 mode
= PROTOCOL_BLHELI
;
3935 } else if (strncasecmp(pch
, "ki", strlen(pch
)) == 0) {
3936 mode
= PROTOCOL_KISS
;
3937 } else if (strncasecmp(pch
, "cc", strlen(pch
)) == 0) {
3938 mode
= PROTOCOL_KISSALL
;
3940 cliShowParseError(cmdName
);
3946 escIndex
= parseOutputIndex(cmdName
, pch
, mode
== PROTOCOL_KISS
);
3947 if (escIndex
== -1) {
3953 cliShowInvalidArgumentCountError(cmdName
);
3961 pch
= strtok_r(NULL
, " ", &saveptr
);
3964 if (!escEnablePassthrough(cliPort
, &motorConfig()->dev
, escIndex
, mode
)) {
3965 cliPrintErrorLinef(cmdName
, "Error starting ESC connection");
3970 #ifndef USE_QUAD_MIXER_ONLY
3971 static void cliMixer(const char *cmdName
, char *cmdline
)
3975 len
= strlen(cmdline
);
3978 cliPrintLinef("Mixer: %s", mixerNames
[mixerConfig()->mixerMode
- 1]);
3980 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
3981 cliPrint("Available:");
3982 for (uint32_t i
= 0; ; i
++) {
3983 if (mixerNames
[i
] == NULL
)
3985 cliPrintf(" %s", mixerNames
[i
]);
3991 for (uint32_t i
= 0; ; i
++) {
3992 if (mixerNames
[i
] == NULL
) {
3993 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
3996 if (strncasecmp(cmdline
, mixerNames
[i
], len
) == 0) {
3997 mixerConfigMutable()->mixerMode
= i
+ 1;
4002 cliMixer(cmdName
, "");
4006 static void cliMotor(const char *cmdName
, char *cmdline
)
4008 if (isEmpty(cmdline
)) {
4009 cliShowInvalidArgumentCountError(cmdName
);
4018 char *pch
= strtok_r(cmdline
, " ", &saveptr
);
4020 while (pch
!= NULL
) {
4023 motorIndex
= parseOutputIndex(cmdName
, pch
, true);
4024 if (motorIndex
== -1) {
4030 motorValue
= atoi(pch
);
4035 pch
= strtok_r(NULL
, " ", &saveptr
);
4039 if (motorValue
< PWM_RANGE_MIN
|| motorValue
> PWM_RANGE_MAX
) {
4040 cliShowArgumentRangeError(cmdName
, "VALUE", 1000, 2000);
4042 uint32_t motorOutputValue
= motorConvertFromExternal(motorValue
);
4044 if (motorIndex
!= ALL_MOTORS
) {
4045 motor_disarmed
[motorIndex
] = motorOutputValue
;
4047 cliPrintLinef("motor %d: %d", motorIndex
, motorOutputValue
);
4049 for (int i
= 0; i
< getMotorCount(); i
++) {
4050 motor_disarmed
[i
] = motorOutputValue
;
4053 cliPrintLinef("all motors: %d", motorOutputValue
);
4057 cliShowInvalidArgumentCountError(cmdName
);
4062 static void cliPlaySound(const char *cmdName
, char *cmdline
)
4066 static int lastSoundIdx
= -1;
4068 if (isEmpty(cmdline
)) {
4069 i
= lastSoundIdx
+ 1; //next sound index
4070 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
4071 while (true) { //no name for index; try next one
4072 if (++i
>= beeperTableEntryCount())
4073 i
= 0; //if end then wrap around to first entry
4074 if ((name
=beeperNameForTableIndex(i
)) != NULL
)
4075 break; //if name OK then play sound below
4076 if (i
== lastSoundIdx
+ 1) { //prevent infinite loop
4077 cliPrintErrorLinef(cmdName
, "ERROR PLAYING SOUND");
4082 } else { //index value was given
4084 if ((name
=beeperNameForTableIndex(i
)) == NULL
) {
4085 cliPrintLinef("No sound for index %d", i
);
4091 cliPrintLinef("Playing sound %d: %s", i
, name
);
4092 beeper(beeperModeForTableIndex(i
));
4096 static void cliProfile(const char *cmdName
, char *cmdline
)
4098 if (isEmpty(cmdline
)) {
4099 cliPrintLinef("profile %d", getPidProfileIndexToUse());
4102 const int i
= atoi(cmdline
);
4103 if (i
>= 0 && i
< PID_PROFILE_COUNT
) {
4104 changePidProfile(i
);
4105 cliProfile(cmdName
, "");
4107 cliPrintErrorLinef(cmdName
, "PROFILE OUTSIDE OF [0..%d]", PID_PROFILE_COUNT
- 1);
4112 static void cliRateProfile(const char *cmdName
, char *cmdline
)
4114 if (isEmpty(cmdline
)) {
4115 cliPrintLinef("rateprofile %d", getRateProfileIndexToUse());
4118 const int i
= atoi(cmdline
);
4119 if (i
>= 0 && i
< CONTROL_RATE_PROFILE_COUNT
) {
4120 changeControlRateProfile(i
);
4121 cliRateProfile(cmdName
, "");
4123 cliPrintErrorLinef(cmdName
, "RATE PROFILE OUTSIDE OF [0..%d]", CONTROL_RATE_PROFILE_COUNT
- 1);
4128 static void cliDumpPidProfile(const char *cmdName
, uint8_t pidProfileIndex
, dumpFlags_t dumpMask
)
4130 if (pidProfileIndex
>= PID_PROFILE_COUNT
) {
4135 pidProfileIndexToUse
= pidProfileIndex
;
4138 cliProfile(cmdName
, "");
4140 char profileStr
[10];
4141 tfp_sprintf(profileStr
, "profile %d", pidProfileIndex
);
4142 dumpAllValues(cmdName
, PROFILE_VALUE
, dumpMask
, profileStr
);
4144 pidProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
4147 static void cliDumpRateProfile(const char *cmdName
, uint8_t rateProfileIndex
, dumpFlags_t dumpMask
)
4149 if (rateProfileIndex
>= CONTROL_RATE_PROFILE_COUNT
) {
4154 rateProfileIndexToUse
= rateProfileIndex
;
4157 cliRateProfile(cmdName
, "");
4159 char rateProfileStr
[14];
4160 tfp_sprintf(rateProfileStr
, "rateprofile %d", rateProfileIndex
);
4161 dumpAllValues(cmdName
, PROFILE_RATE_VALUE
, dumpMask
, rateProfileStr
);
4163 rateProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
4166 #ifdef USE_CLI_BATCH
4167 static void cliPrintCommandBatchWarning(const char *cmdName
, const char *warning
)
4169 cliPrintErrorLinef(cmdName
, "ERRORS WERE DETECTED - PLEASE REVIEW BEFORE CONTINUING");
4171 cliPrintErrorLinef(cmdName
, warning
);
4175 static void resetCommandBatch(void)
4177 commandBatchActive
= false;
4178 commandBatchError
= false;
4181 static void cliBatch(const char *cmdName
, char *cmdline
)
4183 if (strncasecmp(cmdline
, "start", 5) == 0) {
4184 if (!commandBatchActive
) {
4185 commandBatchActive
= true;
4186 commandBatchError
= false;
4188 cliPrintLine("Command batch started");
4189 } else if (strncasecmp(cmdline
, "end", 3) == 0) {
4190 if (commandBatchActive
&& commandBatchError
) {
4191 cliPrintCommandBatchWarning(cmdName
, NULL
);
4193 cliPrintLine("Command batch ended");
4195 resetCommandBatch();
4197 cliPrintErrorLinef(cmdName
, "Invalid option");
4202 static bool prepareSave(void)
4204 #if defined(USE_CUSTOM_DEFAULTS)
4205 if (processingCustomDefaults
) {
4210 #ifdef USE_CLI_BATCH
4211 if (commandBatchActive
&& commandBatchError
) {
4216 #if defined(USE_BOARD_INFO)
4217 if (boardInformationUpdated
) {
4218 persistBoardInformation();
4220 #if defined(USE_SIGNATURE)
4221 if (signatureUpdated
) {
4225 #endif // USE_BOARD_INFO
4230 bool tryPrepareSave(const char *cmdName
)
4232 bool success
= prepareSave();
4233 #if defined(USE_CLI_BATCH)
4235 cliPrintCommandBatchWarning(cmdName
, "PLEASE FIX ERRORS THEN 'SAVE'");
4236 resetCommandBatch();
4248 static void cliSave(const char *cmdName
, char *cmdline
)
4252 if (tryPrepareSave(cmdName
)) {
4254 cliPrintHashLine("saving");
4260 #if defined(USE_CUSTOM_DEFAULTS)
4261 bool resetConfigToCustomDefaults(void)
4265 #ifdef USE_CLI_BATCH
4266 commandBatchError
= false;
4269 cliProcessCustomDefaults(true);
4271 #if defined(USE_SIMPLIFIED_TUNING)
4272 applySimplifiedTuningAllProfiles();
4275 return prepareSave();
4278 static bool customDefaultsHasNext(const char *customDefaultsPtr
)
4280 return *customDefaultsPtr
&& *customDefaultsPtr
!= 0xFF && customDefaultsPtr
< customDefaultsEnd
;
4283 static void parseCustomDefaultsHeader(void)
4285 const char *customDefaultsPtr
= customDefaultsStart
;
4286 if (strncmp(customDefaultsPtr
, CUSTOM_DEFAULTS_START_PREFIX
, strlen(CUSTOM_DEFAULTS_START_PREFIX
)) == 0) {
4287 customDefaultsFound
= true;
4289 customDefaultsPtr
= strchr(customDefaultsPtr
, '\n');
4290 if (customDefaultsPtr
&& customDefaultsHasNext(customDefaultsPtr
)) {
4291 customDefaultsPtr
++;
4295 customDefaultsHeaderParsed
= true;
4298 bool hasCustomDefaults(void)
4300 if (!customDefaultsHeaderParsed
) {
4301 parseCustomDefaultsHeader();
4304 return customDefaultsFound
;
4308 static void cliDefaults(const char *cmdName
, char *cmdline
)
4310 bool saveConfigs
= true;
4311 uint16_t parameterGroupId
= 0;
4312 #if defined(USE_CUSTOM_DEFAULTS)
4313 bool useCustomDefaults
= true;
4314 #elif defined(USE_CUSTOM_DEFAULTS_ADDRESS)
4315 // Required to keep the linker from eliminating these
4316 if (customDefaultsStart
!= customDefaultsEnd
) {
4322 char* tok
= strtok_r(cmdline
, " ", &saveptr
);
4324 bool expectParameterGroupId
= false;
4325 while (tok
!= NULL
) {
4326 if (expectParameterGroupId
) {
4327 parameterGroupId
= atoi(tok
);
4328 expectParameterGroupId
= false;
4330 if (!parameterGroupId
) {
4331 cliShowParseError(cmdName
);
4335 } else if (strcasestr(tok
, "group_id")) {
4336 expectParameterGroupId
= true;
4337 } else if (strcasestr(tok
, "nosave")) {
4338 saveConfigs
= false;
4339 #if defined(USE_CUSTOM_DEFAULTS)
4340 } else if (strcasestr(tok
, "bare")) {
4341 useCustomDefaults
= false;
4342 } else if (strcasestr(tok
, "show")) {
4344 cliShowParseError(cmdName
);
4345 } else if (hasCustomDefaults()) {
4346 char *customDefaultsPtr
= customDefaultsStart
;
4347 while (customDefaultsHasNext(customDefaultsPtr
)) {
4348 if (*customDefaultsPtr
!= '\n') {
4349 cliPrintf("%c", *customDefaultsPtr
++);
4352 customDefaultsPtr
++;
4356 cliPrintError(cmdName
, "NO CUSTOM DEFAULTS FOUND");
4362 cliShowParseError(cmdName
);
4368 tok
= strtok_r(NULL
, " ", &saveptr
);
4371 if (expectParameterGroupId
) {
4372 cliShowParseError(cmdName
);
4377 if (parameterGroupId
) {
4378 cliPrintLinef("\r\n# resetting group %d to defaults", parameterGroupId
);
4381 cliPrintHashLine("resetting to defaults");
4386 #ifdef USE_CLI_BATCH
4387 // Reset only the error state and allow the batch active state to remain.
4388 // This way if a "defaults nosave" was issued after the "batch on" we'll
4389 // only reset the current error state but the batch will still be active
4390 // for subsequent commands.
4391 commandBatchError
= false;
4394 #if defined(USE_CUSTOM_DEFAULTS)
4395 if (useCustomDefaults
) {
4396 cliProcessCustomDefaults(false);
4400 #if defined(USE_SIMPLIFIED_TUNING)
4401 applySimplifiedTuningAllProfiles();
4404 if (parameterGroupId
) {
4405 restoreConfigs(parameterGroupId
);
4408 if (saveConfigs
&& tryPrepareSave(cmdName
)) {
4409 writeUnmodifiedConfigToEEPROM();
4415 static void cliPrintVarDefault(const char *cmdName
, const clivalue_t
*value
)
4417 const pgRegistry_t
*pg
= pgFind(value
->pgn
);
4419 const char *defaultFormat
= "Default value: ";
4420 const int valueOffset
= getValueOffset(value
);
4421 const bool equalsDefault
= valuePtrEqualsDefault(value
, pg
->copy
+ valueOffset
, pg
->address
+ valueOffset
);
4422 if (!equalsDefault
) {
4423 cliPrintf(defaultFormat
, value
->name
);
4424 printValuePointer(cmdName
, value
, (uint8_t*)pg
->address
+ valueOffset
, false);
4430 STATIC_UNIT_TESTED
void cliGet(const char *cmdName
, char *cmdline
)
4432 const clivalue_t
*val
;
4433 int matchedCommands
= 0;
4435 pidProfileIndexToUse
= getCurrentPidProfileIndex();
4436 rateProfileIndexToUse
= getCurrentControlRateProfileIndex();
4438 backupAndResetConfigs(true);
4440 for (uint32_t i
= 0; i
< valueTableEntryCount
; i
++) {
4441 if (strcasestr(valueTable
[i
].name
, cmdline
)) {
4442 val
= &valueTable
[i
];
4443 if (matchedCommands
> 0) {
4446 cliPrintf("%s = ", valueTable
[i
].name
);
4447 cliPrintVar(cmdName
, val
, 0);
4449 switch (val
->type
& VALUE_SECTION_MASK
) {
4451 cliProfile(cmdName
, "");
4454 case PROFILE_RATE_VALUE
:
4455 cliRateProfile(cmdName
, "");
4462 cliPrintVarRange(val
);
4463 cliPrintVarDefault(cmdName
, val
);
4471 pidProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
4472 rateProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
4474 if (!matchedCommands
) {
4475 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
4479 static uint8_t getWordLength(char *bufBegin
, char *bufEnd
)
4481 while (*(bufEnd
- 1) == ' ') {
4485 return bufEnd
- bufBegin
;
4488 uint16_t cliGetSettingIndex(char *name
, uint8_t length
)
4490 for (uint32_t i
= 0; i
< valueTableEntryCount
; i
++) {
4491 const char *settingName
= valueTable
[i
].name
;
4493 // ensure exact match when setting to prevent setting variables with shorter names
4494 if (strncasecmp(name
, settingName
, strlen(settingName
)) == 0 && length
== strlen(settingName
)) {
4498 return valueTableEntryCount
;
4501 STATIC_UNIT_TESTED
void cliSet(const char *cmdName
, char *cmdline
)
4503 const uint32_t len
= strlen(cmdline
);
4506 if (len
== 0 || (len
== 1 && cmdline
[0] == '*')) {
4507 cliPrintLine("Current settings: ");
4509 for (uint32_t i
= 0; i
< valueTableEntryCount
; i
++) {
4510 const clivalue_t
*val
= &valueTable
[i
];
4511 cliPrintf("%s = ", valueTable
[i
].name
);
4512 cliPrintVar(cmdName
, val
, len
); // when len is 1 (when * is passed as argument), it will print min/max values as well, for gui
4515 } else if ((eqptr
= strstr(cmdline
, "=")) != NULL
) {
4518 uint8_t variableNameLength
= getWordLength(cmdline
, eqptr
);
4520 // skip the '=' and any ' ' characters
4522 eqptr
= skipSpace(eqptr
);
4524 const uint16_t index
= cliGetSettingIndex(cmdline
, variableNameLength
);
4525 if (index
>= valueTableEntryCount
) {
4526 cliPrintErrorLinef(cmdName
, ERROR_INVALID_NAME
, cmdline
);
4529 const clivalue_t
*val
= &valueTable
[index
];
4531 bool valueChanged
= false;
4533 switch (val
->type
& VALUE_MODE_MASK
) {
4535 if ((val
->type
& VALUE_TYPE_MASK
) == VAR_UINT32
) {
4536 uint32_t value
= strtoul(eqptr
, NULL
, 10);
4538 if (value
<= val
->config
.u32Max
) {
4539 cliSetVar(val
, value
);
4540 valueChanged
= true;
4543 int value
= atoi(eqptr
);
4547 getMinMax(val
, &min
, &max
);
4549 if (value
>= min
&& value
<= max
) {
4550 cliSetVar(val
, value
);
4551 valueChanged
= true;
4560 if ((val
->type
& VALUE_MODE_MASK
) == MODE_BITSET
) {
4561 tableIndex
= TABLE_OFF_ON
;
4563 tableIndex
= val
->config
.lookup
.tableIndex
;
4565 const lookupTableEntry_t
*tableEntry
= &lookupTables
[tableIndex
];
4566 bool matched
= false;
4567 for (uint32_t tableValueIndex
= 0; tableValueIndex
< tableEntry
->valueCount
&& !matched
; tableValueIndex
++) {
4568 matched
= tableEntry
->values
[tableValueIndex
] && strcasecmp(tableEntry
->values
[tableValueIndex
], eqptr
) == 0;
4571 value
= tableValueIndex
;
4573 cliSetVar(val
, value
);
4574 valueChanged
= true;
4582 const uint8_t arrayLength
= val
->config
.array
.length
;
4583 char *valPtr
= eqptr
;
4586 while (i
< arrayLength
&& valPtr
!= NULL
) {
4588 valPtr
= skipSpace(valPtr
);
4590 // process substring starting at valPtr
4591 // note: no need to copy substrings for atoi()
4592 // it stops at the first character that cannot be converted...
4593 switch (val
->type
& VALUE_TYPE_MASK
) {
4597 // fetch data pointer
4598 uint8_t *data
= (uint8_t *)cliGetValuePointer(val
) + i
;
4600 *data
= (uint8_t)atoi((const char*) valPtr
);
4606 // fetch data pointer
4607 int8_t *data
= (int8_t *)cliGetValuePointer(val
) + i
;
4609 *data
= (int8_t)atoi((const char*) valPtr
);
4615 // fetch data pointer
4616 uint16_t *data
= (uint16_t *)cliGetValuePointer(val
) + i
;
4618 *data
= (uint16_t)atoi((const char*) valPtr
);
4624 // fetch data pointer
4625 int16_t *data
= (int16_t *)cliGetValuePointer(val
) + i
;
4627 *data
= (int16_t)atoi((const char*) valPtr
);
4633 // fetch data pointer
4634 uint32_t *data
= (uint32_t *)cliGetValuePointer(val
) + i
;
4636 *data
= (uint32_t)strtoul((const char*) valPtr
, NULL
, 10);
4642 // find next comma (or end of string)
4643 valPtr
= strchr(valPtr
, ',') + 1;
4650 valueChanged
= true;
4654 char *valPtr
= eqptr
;
4655 valPtr
= skipSpace(valPtr
);
4657 const unsigned int len
= strlen(valPtr
);
4658 const uint8_t min
= val
->config
.string
.minlength
;
4659 const uint8_t max
= val
->config
.string
.maxlength
;
4660 const bool updatable
= ((val
->config
.string
.flags
& STRING_FLAGS_WRITEONCE
) == 0 ||
4661 strlen((char *)cliGetValuePointer(val
)) == 0 ||
4662 strncmp(valPtr
, (char *)cliGetValuePointer(val
), len
) == 0);
4664 if (updatable
&& len
> 0 && len
<= max
) {
4665 memset((char *)cliGetValuePointer(val
), 0, max
);
4666 if (len
>= min
&& strncmp(valPtr
, emptyName
, len
)) {
4667 strncpy((char *)cliGetValuePointer(val
), valPtr
, len
);
4669 valueChanged
= true;
4671 cliPrintErrorLinef(cmdName
, "STRING MUST BE 1-%d CHARACTERS OR '-' FOR EMPTY", max
);
4678 cliPrintf("%s set to ", val
->name
);
4679 cliPrintVar(cmdName
, val
, 0);
4681 cliPrintErrorLinef(cmdName
, "INVALID VALUE");
4682 cliPrintVarRange(val
);
4687 // no equals, check for matching variables.
4688 cliGet(cmdName
, cmdline
);
4692 static const char *getMcuTypeById(mcuTypeId_e id
)
4694 if (id
< ARRAYLEN(mcuTypeNames
)) {
4695 return mcuTypeNames
[id
];
4701 static void cliStatus(const char *cmdName
, char *cmdline
)
4706 // MCU type, clock, vrefint, core temperature
4708 cliPrintf("MCU %s Clock=%dMHz", getMcuTypeById(getMcuTypeId()), (SystemCoreClock
/ 1000000));
4710 #if defined(STM32F4) || defined(STM32G4)
4711 // Only F4 and G4 is capable of switching between HSE/HSI (for now)
4712 int sysclkSource
= SystemSYSCLKSource();
4714 const char *SYSCLKSource
[] = { "HSI", "HSE", "PLLP", "PLLR" };
4715 const char *PLLSource
[] = { "-HSI", "-HSE" };
4719 if (sysclkSource
>= 2) {
4720 pllSource
= SystemPLLSource();
4723 cliPrintf(" (%s%s)", SYSCLKSource
[sysclkSource
], (sysclkSource
< 2) ? "" : PLLSource
[pllSource
]);
4726 #ifdef USE_ADC_INTERNAL
4727 uint16_t vrefintMv
= getVrefMv();
4728 int16_t coretemp
= getCoreTemperatureCelsius();
4729 cliPrintLinef(", Vref=%d.%2dV, Core temp=%ddegC", vrefintMv
/ 1000, (vrefintMv
% 1000) / 10, coretemp
);
4734 // Stack and config sizes and usages
4736 cliPrintf("Stack size: %d, Stack address: 0x%x", stackTotalSize(), stackHighMem());
4737 #ifdef USE_STACK_CHECK
4738 cliPrintf(", Stack used: %d", stackUsedSize());
4742 cliPrintLinef("Configuration: %s, size: %d, max available: %d", configurationStates
[systemConfigMutable()->configurationState
], getEEPROMConfigSize(), getEEPROMStorageSize());
4745 #if defined(USE_SPI) || defined(USE_I2C)
4746 cliPrint("Devices detected:");
4747 #if defined(USE_SPI)
4748 cliPrintf(" SPI:%d", spiGetRegisteredDeviceCount());
4749 #if defined(USE_I2C)
4753 #if defined(USE_I2C)
4754 cliPrintf(" I2C:%d", i2cGetRegisteredDeviceCount());
4760 cliPrint("Gyros detected:");
4762 for (unsigned pos
= 0; pos
< 7; pos
++) {
4763 if (gyroConfig()->gyrosDetected
& BIT(pos
)) {
4769 cliPrintf(" gyro %d", pos
+ 1);
4773 if (gyroActiveDev()->gyroModeSPI
!= GYRO_EXTI_NO_INT
) {
4774 cliPrintf(" locked");
4776 if (gyroActiveDev()->gyroModeSPI
== GYRO_EXTI_INT_DMA
) {
4779 if (spiGetExtDeviceCount(&gyroActiveDev()->dev
) > 1) {
4780 cliPrintf(" shared");
4785 #if defined(USE_SENSOR_NAMES)
4786 const uint32_t detectedSensorsMask
= sensorsMask();
4787 for (uint32_t i
= 0; ; i
++) {
4788 if (sensorTypeNames
[i
] == NULL
) {
4791 const uint32_t mask
= (1 << i
);
4792 if ((detectedSensorsMask
& mask
) && (mask
& SENSOR_NAMES_MASK
)) {
4793 const uint8_t sensorHardwareIndex
= detectedSensors
[i
];
4794 const char *sensorHardware
= sensorHardwareNames
[i
][sensorHardwareIndex
];
4798 cliPrintf("%s=%s", sensorTypeNames
[i
], sensorHardware
);
4799 #if defined(USE_ACC)
4800 if (mask
== SENSOR_ACC
&& acc
.dev
.revisionCode
) {
4801 cliPrintf(".%c", acc
.dev
.revisionCode
);
4807 #endif /* USE_SENSOR_NAMES */
4809 #if defined(USE_OSD)
4810 osdDisplayPortDevice_e displayPortDeviceType
;
4811 displayPort_t
*osdDisplayPort
= osdGetDisplayPort(&displayPortDeviceType
);
4813 cliPrintLinef("OSD: %s (%u x %u)", lookupTableOsdDisplayPortDevice
[displayPortDeviceType
], osdDisplayPort
->cols
, osdDisplayPort
->rows
);
4817 cliPrintf("BUILD KEY: %s", STR(BUILD_KEY
));
4819 cliPrintf(" (%s)", STR(RELEASE_NAME
));
4824 // Uptime and wall clock
4826 cliPrintf("System Uptime: %d seconds", millis() / 1000);
4829 char buf
[FORMATTED_DATE_TIME_BUFSIZE
];
4831 if (rtcGetDateTime(&dt
)) {
4832 dateTimeFormatLocal(buf
, &dt
);
4833 cliPrintf(", Current Time: %s", buf
);
4840 const int gyroRate
= getTaskDeltaTimeUs(TASK_GYRO
) == 0 ? 0 : (int)(1000000.0f
/ ((float)getTaskDeltaTimeUs(TASK_GYRO
)));
4841 int rxRate
= getCurrentRxRefreshRate();
4843 rxRate
= (int)(1000000.0f
/ ((float)rxRate
));
4845 const int systemRate
= getTaskDeltaTimeUs(TASK_SYSTEM
) == 0 ? 0 : (int)(1000000.0f
/ ((float)getTaskDeltaTimeUs(TASK_SYSTEM
)));
4846 cliPrintLinef("CPU:%d%%, cycle time: %d, GYRO rate: %d, RX rate: %d, System rate: %d",
4847 constrain(getAverageSystemLoadPercent(), 0, LOAD_PERCENTAGE_ONE
), getTaskDeltaTimeUs(TASK_GYRO
), gyroRate
, rxRate
, systemRate
);
4851 cliPrintLinef("Voltage: %d * 0.01V (%dS battery - %s)", getBatteryVoltage(), getBatteryCellCount(), getBatteryStateString());
4853 // Other devices and status
4856 const uint16_t i2cErrorCounter
= i2cGetErrorCounter();
4858 const uint16_t i2cErrorCounter
= 0;
4860 cliPrintLinef("I2C Errors: %d", i2cErrorCounter
);
4863 cliSdInfo(cmdName
, "");
4866 #ifdef USE_FLASH_CHIP
4867 const flashGeometry_t
*layout
= flashGetGeometry();
4868 if (layout
->jedecId
!= 0) {
4869 cliPrintLinef("FLASH: JEDEC ID=0x%08x %uM", layout
->jedecId
, layout
->totalSize
>> 20);
4873 cliPrint("Arming disable flags:");
4874 armingDisableFlags_e flags
= getArmingDisableFlags();
4876 const int bitpos
= ffs(flags
) - 1;
4877 flags
&= ~(1 << bitpos
);
4878 cliPrintf(" %s", armingDisableFlagNames
[bitpos
]);
4883 static void cliTasks(const char *cmdName
, char *cmdline
)
4887 int averageLoadSum
= 0;
4890 if (systemConfig()->task_statistics
) {
4891 #if defined(USE_LATE_TASK_STATISTICS)
4892 cliPrintLine("Task list rate/hz max/us avg/us maxload avgload total/ms late run reqd/us");
4894 cliPrintLine("Task list rate/hz max/us avg/us maxload avgload total/ms");
4897 cliPrintLine("Task list");
4900 for (taskId_e taskId
= 0; taskId
< TASK_COUNT
; taskId
++) {
4901 taskInfo_t taskInfo
;
4902 getTaskInfo(taskId
, &taskInfo
);
4903 if (taskInfo
.isEnabled
) {
4904 int taskFrequency
= taskInfo
.averageDeltaTime10thUs
== 0 ? 0 : lrintf(1e7f
/ taskInfo
.averageDeltaTime10thUs
);
4905 cliPrintf("%02d - (%15s) ", taskId
, taskInfo
.taskName
);
4906 const int maxLoad
= taskInfo
.maxExecutionTimeUs
== 0 ? 0 : (taskInfo
.maxExecutionTimeUs
* taskFrequency
) / 1000;
4907 const int averageLoad
= taskInfo
.averageExecutionTime10thUs
== 0 ? 0 : (taskInfo
.averageExecutionTime10thUs
* taskFrequency
) / 10000;
4908 if (taskId
!= TASK_SERIAL
) {
4909 averageLoadSum
+= averageLoad
;
4911 if (systemConfig()->task_statistics
) {
4912 #if defined(USE_LATE_TASK_STATISTICS)
4913 cliPrintLinef("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d %6d %6d %7d",
4914 taskFrequency
, taskInfo
.maxExecutionTimeUs
, taskInfo
.averageExecutionTime10thUs
/ 10,
4915 maxLoad
/10, maxLoad
%10, averageLoad
/10, averageLoad
%10,
4916 taskInfo
.totalExecutionTimeUs
/ 1000,
4917 taskInfo
.lateCount
, taskInfo
.runCount
, taskInfo
.execTime
);
4919 cliPrintLinef("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d",
4920 taskFrequency
, taskInfo
.maxExecutionTimeUs
, taskInfo
.averageExecutionTime10thUs
/ 10,
4921 maxLoad
/10, maxLoad
%10, averageLoad
/10, averageLoad
%10,
4922 taskInfo
.totalExecutionTimeUs
/ 1000);
4925 cliPrintLinef("%6d", taskFrequency
);
4928 schedulerResetTaskMaxExecutionTime(taskId
);
4931 if (systemConfig()->task_statistics
) {
4932 cfCheckFuncInfo_t checkFuncInfo
;
4933 getCheckFuncInfo(&checkFuncInfo
);
4934 cliPrintLinef("RX Check Function %19d %7d %25d", checkFuncInfo
.maxExecutionTimeUs
, checkFuncInfo
.averageExecutionTimeUs
, checkFuncInfo
.totalExecutionTimeUs
/ 1000);
4935 cliPrintLinef("Total (excluding SERIAL) %33d.%1d%%", averageLoadSum
/10, averageLoadSum
%10);
4936 if (debugMode
== DEBUG_SCHEDULER_DETERMINISM
) {
4937 extern int32_t schedLoopStartCycles
, taskGuardCycles
;
4939 cliPrintLinef("Scheduler start cycles %d guard cycles %d", schedLoopStartCycles
, taskGuardCycles
);
4941 schedulerResetCheckFunctionMaxExecutionTime();
4945 static void printVersion(const char *cmdName
, bool printBoardInfo
)
4947 #if !(defined(USE_CUSTOM_DEFAULTS))
4949 UNUSED(printBoardInfo
);
4952 cliPrintf("# %s / %s (%s) %s %s / %s (%s) MSP API: %s",
4955 systemConfig()->boardIdentifier
,
4960 MSP_API_VERSION_STRING
4965 #if defined(USE_CUSTOM_DEFAULTS)
4966 if (hasCustomDefaults()) {
4967 cliPrintHashLine("config: YES");
4969 cliPrintError(cmdName
, "NO CONFIG FOUND");
4971 #endif // USE_CUSTOM_DEFAULTS
4973 #if defined(USE_BOARD_INFO)
4974 if (printBoardInfo
&& strlen(getManufacturerId()) && strlen(getBoardName())) {
4975 cliPrintLinef("# board: manufacturer_id: %s, board_name: %s", getManufacturerId(), getBoardName());
4980 static void cliVersion(const char *cmdName
, char *cmdline
)
4984 printVersion(cmdName
, true);
4987 #ifdef USE_RC_SMOOTHING_FILTER
4988 static void cliRcSmoothing(const char *cmdName
, char *cmdline
)
4992 rcSmoothingFilter_t
*rcSmoothingData
= getRcSmoothingData();
4993 cliPrint("# RC Smoothing Type: ");
4994 if (rxConfig()->rc_smoothing_mode
) {
4995 cliPrintLine("FILTER");
4996 if (rcSmoothingAutoCalculate()) {
4997 const uint16_t avgRxFrameUs
= rcSmoothingData
->averageFrameTimeUs
;
4998 cliPrint("# Detected RX frame rate: ");
4999 if (avgRxFrameUs
== 0) {
5000 cliPrintLine("NO SIGNAL");
5002 cliPrintLinef("%d.%03dms", avgRxFrameUs
/ 1000, avgRxFrameUs
% 1000);
5005 cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData
->setpointCutoffFrequency
);
5006 if (rcSmoothingData
->setpointCutoffSetting
) {
5007 cliPrintLine("(manual)");
5009 cliPrintLine("(auto)");
5011 cliPrintf("# Active FF cutoff: %dhz ", rcSmoothingData
->feedforwardCutoffFrequency
);
5012 if (rcSmoothingData
->ffCutoffSetting
) {
5013 cliPrintLine("(manual)");
5015 cliPrintLine("(auto)");
5017 cliPrintf("# Active throttle cutoff: %dhz ", rcSmoothingData
->throttleCutoffFrequency
);
5018 if (rcSmoothingData
->throttleCutoffSetting
) {
5019 cliPrintLine("(manual)");
5021 cliPrintLine("(auto)");
5024 cliPrintLine("OFF");
5027 #endif // USE_RC_SMOOTHING_FILTER
5029 #if defined(USE_RESOURCE_MGMT)
5031 #define RESOURCE_VALUE_MAX_INDEX(x) ((x) == 0 ? 1 : (x))
5034 const uint8_t owner
;
5038 const uint8_t maxIndex
;
5039 } cliResourceValue_t
;
5041 // Handy macros for keeping the table tidy.
5042 // DEFS : Single entry
5043 // DEFA : Array of uint8_t (stride = 1)
5044 // DEFW : Wider stride case; array of structs.
5046 #define DEFS(owner, pgn, type, member) \
5047 { owner, pgn, 0, offsetof(type, member), 0 }
5049 #define DEFA(owner, pgn, type, member, max) \
5050 { owner, pgn, sizeof(ioTag_t), offsetof(type, member), max }
5052 #define DEFW(owner, pgn, type, member, max) \
5053 { owner, pgn, sizeof(type), offsetof(type, member), max }
5055 const cliResourceValue_t resourceTable
[] = {
5056 #if defined(USE_BEEPER)
5057 DEFS( OWNER_BEEPER
, PG_BEEPER_DEV_CONFIG
, beeperDevConfig_t
, ioTag
) ,
5059 DEFA( OWNER_MOTOR
, PG_MOTOR_CONFIG
, motorConfig_t
, dev
.ioTags
[0], MAX_SUPPORTED_MOTORS
),
5060 #if defined(USE_SERVOS)
5061 DEFA( OWNER_SERVO
, PG_SERVO_CONFIG
, servoConfig_t
, dev
.ioTags
[0], MAX_SUPPORTED_SERVOS
),
5063 #if defined(USE_RX_PPM)
5064 DEFS( OWNER_PPMINPUT
, PG_PPM_CONFIG
, ppmConfig_t
, ioTag
),
5066 #if defined(USE_RX_PWM)
5067 DEFA( OWNER_PWMINPUT
, PG_PWM_CONFIG
, pwmConfig_t
, ioTags
[0], PWM_INPUT_PORT_COUNT
),
5069 #if defined(USE_RANGEFINDER_HCSR04)
5070 DEFS( OWNER_SONAR_TRIGGER
, PG_SONAR_CONFIG
, sonarConfig_t
, triggerTag
),
5071 DEFS( OWNER_SONAR_ECHO
, PG_SONAR_CONFIG
, sonarConfig_t
, echoTag
),
5073 #if defined(USE_LED_STRIP)
5074 DEFS( OWNER_LED_STRIP
, PG_LED_STRIP_CONFIG
, ledStripConfig_t
, ioTag
),
5077 DEFA( OWNER_SERIAL_TX
, PG_SERIAL_PIN_CONFIG
, serialPinConfig_t
, ioTagTx
[0], SERIAL_PORT_MAX_INDEX
),
5078 DEFA( OWNER_SERIAL_RX
, PG_SERIAL_PIN_CONFIG
, serialPinConfig_t
, ioTagRx
[0], SERIAL_PORT_MAX_INDEX
),
5081 DEFA( OWNER_INVERTER
, PG_SERIAL_PIN_CONFIG
, serialPinConfig_t
, ioTagInverter
[0], SERIAL_PORT_MAX_INDEX
),
5084 DEFW( OWNER_I2C_SCL
, PG_I2C_CONFIG
, i2cConfig_t
, ioTagScl
, I2CDEV_COUNT
),
5085 DEFW( OWNER_I2C_SDA
, PG_I2C_CONFIG
, i2cConfig_t
, ioTagSda
, I2CDEV_COUNT
),
5087 DEFA( OWNER_LED
, PG_STATUS_LED_CONFIG
, statusLedConfig_t
, ioTags
[0], STATUS_LED_NUMBER
),
5088 #ifdef USE_SPEKTRUM_BIND
5089 DEFS( OWNER_RX_BIND
, PG_RX_CONFIG
, rxConfig_t
, spektrum_bind_pin_override_ioTag
),
5090 DEFS( OWNER_RX_BIND_PLUG
, PG_RX_CONFIG
, rxConfig_t
, spektrum_bind_plug_ioTag
),
5092 #ifdef USE_TRANSPONDER
5093 DEFS( OWNER_TRANSPONDER
, PG_TRANSPONDER_CONFIG
, transponderConfig_t
, ioTag
),
5096 DEFW( OWNER_SPI_SCK
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, ioTagSck
, SPIDEV_COUNT
),
5097 DEFW( OWNER_SPI_MISO
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, ioTagMiso
, SPIDEV_COUNT
),
5098 DEFW( OWNER_SPI_MOSI
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, ioTagMosi
, SPIDEV_COUNT
),
5100 #ifdef USE_ESCSERIAL
5101 DEFS( OWNER_ESCSERIAL
, PG_ESCSERIAL_CONFIG
, escSerialConfig_t
, ioTag
),
5103 #ifdef USE_CAMERA_CONTROL
5104 DEFS( OWNER_CAMERA_CONTROL
, PG_CAMERA_CONTROL_CONFIG
, cameraControlConfig_t
, ioTag
),
5107 DEFS( OWNER_ADC_BATT
, PG_ADC_CONFIG
, adcConfig_t
, vbat
.ioTag
),
5108 DEFS( OWNER_ADC_RSSI
, PG_ADC_CONFIG
, adcConfig_t
, rssi
.ioTag
),
5109 DEFS( OWNER_ADC_CURR
, PG_ADC_CONFIG
, adcConfig_t
, current
.ioTag
),
5110 DEFS( OWNER_ADC_EXT
, PG_ADC_CONFIG
, adcConfig_t
, external1
.ioTag
),
5113 DEFS( OWNER_BARO_CS
, PG_BAROMETER_CONFIG
, barometerConfig_t
, baro_spi_csn
),
5114 DEFS( OWNER_BARO_EOC
, PG_BAROMETER_CONFIG
, barometerConfig_t
, baro_eoc_tag
),
5115 DEFS( OWNER_BARO_XCLR
, PG_BAROMETER_CONFIG
, barometerConfig_t
, baro_xclr_tag
),
5118 DEFS( OWNER_COMPASS_CS
, PG_COMPASS_CONFIG
, compassConfig_t
, mag_spi_csn
),
5119 #ifdef USE_MAG_DATA_READY_SIGNAL
5120 DEFS( OWNER_COMPASS_EXTI
, PG_COMPASS_CONFIG
, compassConfig_t
, interruptTag
),
5123 #ifdef USE_SDCARD_SPI
5124 DEFS( OWNER_SDCARD_CS
, PG_SDCARD_CONFIG
, sdcardConfig_t
, chipSelectTag
),
5127 DEFS( OWNER_SDCARD_DETECT
, PG_SDCARD_CONFIG
, sdcardConfig_t
, cardDetectTag
),
5129 #if defined(STM32H7) && defined(USE_SDCARD_SDIO)
5130 DEFS( OWNER_SDIO_CK
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, CKPin
),
5131 DEFS( OWNER_SDIO_CMD
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, CMDPin
),
5132 DEFS( OWNER_SDIO_D0
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, D0Pin
),
5133 DEFS( OWNER_SDIO_D1
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, D1Pin
),
5134 DEFS( OWNER_SDIO_D2
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, D2Pin
),
5135 DEFS( OWNER_SDIO_D3
, PG_SDIO_PIN_CONFIG
, sdioPinConfig_t
, D3Pin
),
5138 DEFA( OWNER_PINIO
, PG_PINIO_CONFIG
, pinioConfig_t
, ioTag
, PINIO_COUNT
),
5140 #if defined(USE_USB_MSC)
5141 DEFS( OWNER_USB_MSC_PIN
, PG_USB_CONFIG
, usbDev_t
, mscButtonPin
),
5143 #ifdef USE_FLASH_CHIP
5144 DEFS( OWNER_FLASH_CS
, PG_FLASH_CONFIG
, flashConfig_t
, csTag
),
5147 DEFS( OWNER_OSD_CS
, PG_MAX7456_CONFIG
, max7456Config_t
, csTag
),
5150 DEFS( OWNER_RX_SPI_CS
, PG_RX_SPI_CONFIG
, rxSpiConfig_t
, csnTag
),
5151 DEFS( OWNER_RX_SPI_EXTI
, PG_RX_SPI_CONFIG
, rxSpiConfig_t
, extiIoTag
),
5152 DEFS( OWNER_RX_SPI_BIND
, PG_RX_SPI_CONFIG
, rxSpiConfig_t
, bindIoTag
),
5153 DEFS( OWNER_RX_SPI_LED
, PG_RX_SPI_CONFIG
, rxSpiConfig_t
, ledIoTag
),
5154 #if defined(USE_RX_CC2500) && defined(USE_RX_CC2500_SPI_PA_LNA)
5155 DEFS( OWNER_RX_SPI_CC2500_TX_EN
, PG_RX_CC2500_SPI_CONFIG
, rxCc2500SpiConfig_t
, txEnIoTag
),
5156 DEFS( OWNER_RX_SPI_CC2500_LNA_EN
, PG_RX_CC2500_SPI_CONFIG
, rxCc2500SpiConfig_t
, lnaEnIoTag
),
5157 #if defined(USE_RX_CC2500_SPI_DIVERSITY)
5158 DEFS( OWNER_RX_SPI_CC2500_ANT_SEL
, PG_RX_CC2500_SPI_CONFIG
, rxCc2500SpiConfig_t
, antSelIoTag
),
5161 #if defined(USE_RX_EXPRESSLRS)
5162 DEFS( OWNER_RX_SPI_EXPRESSLRS_RESET
, PG_RX_EXPRESSLRS_SPI_CONFIG
, rxExpressLrsSpiConfig_t
, resetIoTag
),
5163 DEFS( OWNER_RX_SPI_EXPRESSLRS_BUSY
, PG_RX_EXPRESSLRS_SPI_CONFIG
, rxExpressLrsSpiConfig_t
, busyIoTag
),
5166 DEFW( OWNER_GYRO_EXTI
, PG_GYRO_DEVICE_CONFIG
, gyroDeviceConfig_t
, extiTag
, MAX_GYRODEV_COUNT
),
5167 DEFW( OWNER_GYRO_CS
, PG_GYRO_DEVICE_CONFIG
, gyroDeviceConfig_t
, csnTag
, MAX_GYRODEV_COUNT
),
5168 #ifdef USE_USB_DETECT
5169 DEFS( OWNER_USB_DETECT
, PG_USB_CONFIG
, usbDev_t
, detectPin
),
5171 #ifdef USE_VTX_RTC6705
5172 DEFS( OWNER_VTX_POWER
, PG_VTX_IO_CONFIG
, vtxIOConfig_t
, powerTag
),
5173 DEFS( OWNER_VTX_CS
, PG_VTX_IO_CONFIG
, vtxIOConfig_t
, csTag
),
5174 DEFS( OWNER_VTX_DATA
, PG_VTX_IO_CONFIG
, vtxIOConfig_t
, dataTag
),
5175 DEFS( OWNER_VTX_CLK
, PG_VTX_IO_CONFIG
, vtxIOConfig_t
, clockTag
),
5177 #ifdef USE_PIN_PULL_UP_DOWN
5178 DEFA( OWNER_PULLUP
, PG_PULLUP_CONFIG
, pinPullUpDownConfig_t
, ioTag
, PIN_PULL_UP_DOWN_COUNT
),
5179 DEFA( OWNER_PULLDOWN
, PG_PULLDOWN_CONFIG
, pinPullUpDownConfig_t
, ioTag
, PIN_PULL_UP_DOWN_COUNT
),
5187 static ioTag_t
*getIoTag(const cliResourceValue_t value
, uint8_t index
)
5189 const pgRegistry_t
* rec
= pgFind(value
.pgn
);
5190 return CONST_CAST(ioTag_t
*, rec
->address
+ value
.stride
* index
+ value
.offset
);
5193 static void printResource(dumpFlags_t dumpMask
, const char *headingStr
)
5195 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
5196 for (unsigned int i
= 0; i
< ARRAYLEN(resourceTable
); i
++) {
5197 const char* owner
= ownerNames
[resourceTable
[i
].owner
];
5198 const pgRegistry_t
* pg
= pgFind(resourceTable
[i
].pgn
);
5199 const void *currentConfig
;
5200 const void *defaultConfig
;
5201 if (isReadingConfigFromCopy()) {
5202 currentConfig
= pg
->copy
;
5203 defaultConfig
= pg
->address
;
5205 currentConfig
= pg
->address
;
5206 defaultConfig
= NULL
;
5209 for (int index
= 0; index
< RESOURCE_VALUE_MAX_INDEX(resourceTable
[i
].maxIndex
); index
++) {
5210 const ioTag_t ioTag
= *(ioTag_t
*)((const uint8_t *)currentConfig
+ resourceTable
[i
].stride
* index
+ resourceTable
[i
].offset
);
5211 ioTag_t ioTagDefault
= 0;
5212 if (defaultConfig
) {
5213 ioTagDefault
= *(ioTag_t
*)((const uint8_t *)defaultConfig
+ resourceTable
[i
].stride
* index
+ resourceTable
[i
].offset
);
5216 const bool equalsDefault
= ioTag
== ioTagDefault
;
5217 const char *format
= "resource %s %d %c%02d";
5218 const char *formatUnassigned
= "resource %s %d NONE";
5219 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
5221 cliDefaultPrintLinef(dumpMask
, equalsDefault
, format
, owner
, RESOURCE_INDEX(index
), IO_GPIOPortIdxByTag(ioTagDefault
) + 'A', IO_GPIOPinIdxByTag(ioTagDefault
));
5222 } else if (defaultConfig
) {
5223 cliDefaultPrintLinef(dumpMask
, equalsDefault
, formatUnassigned
, owner
, RESOURCE_INDEX(index
));
5226 cliDumpPrintLinef(dumpMask
, equalsDefault
, format
, owner
, RESOURCE_INDEX(index
), IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
));
5227 } else if (!(dumpMask
& HIDE_UNUSED
)) {
5228 cliDumpPrintLinef(dumpMask
, equalsDefault
, formatUnassigned
, owner
, RESOURCE_INDEX(index
));
5234 static void printResourceOwner(uint8_t owner
, uint8_t index
)
5236 cliPrintf("%s", ownerNames
[resourceTable
[owner
].owner
]);
5238 if (resourceTable
[owner
].maxIndex
> 0) {
5239 cliPrintf(" %d", RESOURCE_INDEX(index
));
5243 static void resourceCheck(uint8_t resourceIndex
, uint8_t index
, ioTag_t newTag
)
5249 const char * format
= "\r\nNOTE: %c%02d already assigned to ";
5250 for (int r
= 0; r
< (int)ARRAYLEN(resourceTable
); r
++) {
5251 for (int i
= 0; i
< RESOURCE_VALUE_MAX_INDEX(resourceTable
[r
].maxIndex
); i
++) {
5252 ioTag_t
*tag
= getIoTag(resourceTable
[r
], i
);
5253 if (*tag
== newTag
) {
5254 bool cleared
= false;
5255 if (r
== resourceIndex
) {
5263 cliPrintf(format
, DEFIO_TAG_GPIOID(newTag
) + 'A', DEFIO_TAG_PIN(newTag
));
5265 printResourceOwner(r
, i
);
5269 printResourceOwner(r
, i
);
5270 cliPrintf(" disabled");
5279 static bool strToPin(char *ptr
, ioTag_t
*tag
)
5281 if (strcasecmp(ptr
, "NONE") == 0) {
5286 const unsigned port
= (*ptr
>= 'a') ? *ptr
- 'a' : *ptr
- 'A';
5291 const long pin
= strtol(ptr
, &end
, 10);
5292 if (end
!= ptr
&& pin
>= 0 && pin
< 16) {
5293 *tag
= DEFIO_TAG_MAKE(port
, pin
);
5304 static void showDma(void)
5309 cliPrintLine("DMA:");
5311 cliPrintLine("Currently active DMA:");
5314 for (int i
= 1; i
<= DMA_LAST_HANDLER
; i
++) {
5315 const resourceOwner_t
*owner
= dmaGetOwner(i
);
5317 cliPrintf(DMA_OUTPUT_STRING
, DMA_DEVICE_NO(i
), DMA_DEVICE_INDEX(i
));
5318 if (owner
->resourceIndex
> 0) {
5319 cliPrintLinef(" %s %d", ownerNames
[owner
->owner
], owner
->resourceIndex
);
5321 cliPrintLinef(" %s", ownerNames
[owner
->owner
]);
5329 typedef struct dmaoptEntry_s
{
5331 dmaPeripheral_e peripheral
;
5336 uint32_t presenceMask
;
5339 #define MASK_IGNORED (0)
5341 // Handy macros for keeping the table tidy.
5342 // DEFS : Single entry
5343 // DEFA : Array of uint8_t (stride = 1)
5344 // DEFW : Wider stride case; array of structs.
5346 #define DEFS(device, peripheral, pgn, type, member) \
5347 { device, peripheral, pgn, 0, offsetof(type, member), 0, MASK_IGNORED }
5349 #define DEFA(device, peripheral, pgn, type, member, max, mask) \
5350 { device, peripheral, pgn, sizeof(uint8_t), offsetof(type, member), max, mask }
5352 #define DEFW(device, peripheral, pgn, type, member, max, mask) \
5353 { device, peripheral, pgn, sizeof(type), offsetof(type, member), max, mask }
5355 dmaoptEntry_t dmaoptEntryTable
[] = {
5356 DEFW("SPI_MOSI", DMA_PERIPH_SPI_MOSI
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, txDmaopt
, SPIDEV_COUNT
, MASK_IGNORED
),
5357 DEFW("SPI_MISO", DMA_PERIPH_SPI_MISO
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, rxDmaopt
, SPIDEV_COUNT
, MASK_IGNORED
),
5358 // SPI_TX/SPI_RX for backwards compatibility with unified configs defined for 4.2.x
5359 DEFW("SPI_TX", DMA_PERIPH_SPI_MOSI
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, txDmaopt
, SPIDEV_COUNT
, MASK_IGNORED
),
5360 DEFW("SPI_RX", DMA_PERIPH_SPI_MISO
, PG_SPI_PIN_CONFIG
, spiPinConfig_t
, rxDmaopt
, SPIDEV_COUNT
, MASK_IGNORED
),
5361 DEFA("ADC", DMA_PERIPH_ADC
, PG_ADC_CONFIG
, adcConfig_t
, dmaopt
, ADCDEV_COUNT
, MASK_IGNORED
),
5362 DEFS("SDIO", DMA_PERIPH_SDIO
, PG_SDIO_CONFIG
, sdioConfig_t
, dmaopt
),
5363 DEFW("UART_TX", DMA_PERIPH_UART_TX
, PG_SERIAL_UART_CONFIG
, serialUartConfig_t
, txDmaopt
, UARTDEV_CONFIG_MAX
, MASK_IGNORED
),
5364 DEFW("UART_RX", DMA_PERIPH_UART_RX
, PG_SERIAL_UART_CONFIG
, serialUartConfig_t
, rxDmaopt
, UARTDEV_CONFIG_MAX
, MASK_IGNORED
),
5365 #if defined(STM32H7) || defined(STM32G4)
5366 DEFW("TIMUP", DMA_PERIPH_TIMUP
, PG_TIMER_UP_CONFIG
, timerUpConfig_t
, dmaopt
, HARDWARE_TIMER_DEFINITION_COUNT
, TIMUP_TIMERS
),
5374 #define DMA_OPT_UI_INDEX(i) ((i) + 1)
5375 #define DMA_OPT_STRING_BUFSIZE 5
5377 #if defined(STM32H7) || defined(STM32G4)
5378 #define DMA_CHANREQ_STRING "Request"
5380 #define DMA_CHANREQ_STRING "Channel"
5383 #if defined(STM32F4) || defined(STM32F7) || defined(STM32H7)
5384 #define DMA_STCH_STRING "Stream"
5386 #define DMA_STCH_STRING "Channel"
5389 #define DMASPEC_FORMAT_STRING "DMA%d " DMA_STCH_STRING " %d " DMA_CHANREQ_STRING " %d"
5391 static void optToString(int optval
, char *buf
)
5393 if (optval
== DMA_OPT_UNUSED
) {
5394 memcpy(buf
, "NONE", DMA_OPT_STRING_BUFSIZE
);
5396 tfp_sprintf(buf
, "%d", optval
);
5400 static void printPeripheralDmaoptDetails(dmaoptEntry_t
*entry
, int index
, const dmaoptValue_t dmaopt
, const bool equalsDefault
, const dumpFlags_t dumpMask
, printFn
*printValue
)
5402 // We compute number to display for different peripherals in advance.
5403 // This is done to deal with TIMUP which numbered non-contiguously.
5404 // Note that using timerGetNumberByIndex is not a generic solution,
5405 // but we are lucky that TIMUP is the only peripheral with non-contiguous numbering.
5409 if (entry
->presenceMask
) {
5410 uiIndex
= timerGetNumberByIndex(index
);
5412 uiIndex
= DMA_OPT_UI_INDEX(index
);
5415 if (dmaopt
!= DMA_OPT_UNUSED
) {
5416 printValue(dumpMask
, equalsDefault
,
5418 entry
->device
, uiIndex
, dmaopt
);
5420 const dmaChannelSpec_t
*dmaChannelSpec
= dmaGetChannelSpecByPeripheral(entry
->peripheral
, index
, dmaopt
);
5421 dmaCode_t dmaCode
= 0;
5422 if (dmaChannelSpec
) {
5423 dmaCode
= dmaChannelSpec
->code
;
5425 printValue(dumpMask
, equalsDefault
,
5426 "# %s %d: " DMASPEC_FORMAT_STRING
,
5427 entry
->device
, uiIndex
, DMA_CODE_CONTROLLER(dmaCode
), DMA_CODE_STREAM(dmaCode
), DMA_CODE_CHANNEL(dmaCode
));
5428 } else if (!(dumpMask
& HIDE_UNUSED
)) {
5429 printValue(dumpMask
, equalsDefault
,
5431 entry
->device
, uiIndex
);
5435 static const char *printPeripheralDmaopt(dmaoptEntry_t
*entry
, int index
, dumpFlags_t dumpMask
, const char *headingStr
)
5437 const pgRegistry_t
* pg
= pgFind(entry
->pgn
);
5438 const void *currentConfig
;
5439 const void *defaultConfig
;
5441 if (isReadingConfigFromCopy()) {
5442 currentConfig
= pg
->copy
;
5443 defaultConfig
= pg
->address
;
5445 currentConfig
= pg
->address
;
5446 defaultConfig
= NULL
;
5449 dmaoptValue_t currentOpt
= *(dmaoptValue_t
*)((uint8_t *)currentConfig
+ entry
->stride
* index
+ entry
->offset
);
5450 dmaoptValue_t defaultOpt
;
5452 if (defaultConfig
) {
5453 defaultOpt
= *(dmaoptValue_t
*)((uint8_t *)defaultConfig
+ entry
->stride
* index
+ entry
->offset
);
5455 defaultOpt
= DMA_OPT_UNUSED
;
5458 bool equalsDefault
= currentOpt
== defaultOpt
;
5459 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
5461 if (defaultConfig
) {
5462 printPeripheralDmaoptDetails(entry
, index
, defaultOpt
, equalsDefault
, dumpMask
, cliDefaultPrintLinef
);
5465 printPeripheralDmaoptDetails(entry
, index
, currentOpt
, equalsDefault
, dumpMask
, cliDumpPrintLinef
);
5469 #if defined(USE_TIMER_MGMT)
5470 static void printTimerDmaoptDetails(const ioTag_t ioTag
, const timerHardware_t
*timer
, const dmaoptValue_t dmaopt
, const bool equalsDefault
, const dumpFlags_t dumpMask
, printFn
*printValue
)
5472 const char *format
= "dma pin %c%02d %d";
5474 if (dmaopt
!= DMA_OPT_UNUSED
) {
5475 const bool printDetails
= printValue(dumpMask
, equalsDefault
, format
,
5476 IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
),
5481 const dmaChannelSpec_t
*dmaChannelSpec
= dmaGetChannelSpecByTimerValue(timer
->tim
, timer
->channel
, dmaopt
);
5482 dmaCode_t dmaCode
= 0;
5483 if (dmaChannelSpec
) {
5484 dmaCode
= dmaChannelSpec
->code
;
5485 printValue(dumpMask
, false,
5486 "# pin %c%02d: " DMASPEC_FORMAT_STRING
,
5487 IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
),
5488 DMA_CODE_CONTROLLER(dmaCode
), DMA_CODE_STREAM(dmaCode
), DMA_CODE_CHANNEL(dmaCode
)
5492 } else if (!(dumpMask
& HIDE_UNUSED
)) {
5493 printValue(dumpMask
, equalsDefault
,
5494 "dma pin %c%02d NONE",
5495 IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
)
5500 static const char *printTimerDmaopt(const timerIOConfig_t
*currentConfig
, const timerIOConfig_t
*defaultConfig
, unsigned index
, dumpFlags_t dumpMask
, bool tagsInUse
[], const char *headingStr
)
5502 const ioTag_t ioTag
= currentConfig
[index
].ioTag
;
5508 const timerHardware_t
*timer
= timerGetByTagAndIndex(ioTag
, currentConfig
[index
].index
);
5509 const dmaoptValue_t dmaopt
= currentConfig
[index
].dmaopt
;
5511 dmaoptValue_t defaultDmaopt
= DMA_OPT_UNUSED
;
5512 bool equalsDefault
= defaultDmaopt
== dmaopt
;
5513 if (defaultConfig
) {
5514 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5515 if (defaultConfig
[i
].ioTag
== ioTag
) {
5516 defaultDmaopt
= defaultConfig
[i
].dmaopt
;
5518 // We need to check timer as well here to get 'default' DMA options for non-default timers printed, because setting the timer resets the DMA option.
5519 equalsDefault
= (defaultDmaopt
== dmaopt
) && (defaultConfig
[i
].index
== currentConfig
[index
].index
|| dmaopt
== DMA_OPT_UNUSED
);
5521 tagsInUse
[index
] = true;
5528 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
5530 if (defaultConfig
) {
5531 printTimerDmaoptDetails(ioTag
, timer
, defaultDmaopt
, equalsDefault
, dumpMask
, cliDefaultPrintLinef
);
5534 printTimerDmaoptDetails(ioTag
, timer
, dmaopt
, equalsDefault
, dumpMask
, cliDumpPrintLinef
);
5539 static void printDmaopt(dumpFlags_t dumpMask
, const char *headingStr
)
5541 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
5542 for (size_t i
= 0; i
< ARRAYLEN(dmaoptEntryTable
); i
++) {
5543 dmaoptEntry_t
*entry
= &dmaoptEntryTable
[i
];
5544 for (int index
= 0; index
< entry
->maxIndex
; index
++) {
5545 headingStr
= printPeripheralDmaopt(entry
, index
, dumpMask
, headingStr
);
5549 #if defined(USE_TIMER_MGMT)
5550 const pgRegistry_t
* pg
= pgFind(PG_TIMER_IO_CONFIG
);
5551 const timerIOConfig_t
*currentConfig
;
5552 const timerIOConfig_t
*defaultConfig
;
5554 if (isReadingConfigFromCopy()) {
5555 currentConfig
= (timerIOConfig_t
*)pg
->copy
;
5556 defaultConfig
= (timerIOConfig_t
*)pg
->address
;
5558 currentConfig
= (timerIOConfig_t
*)pg
->address
;
5559 defaultConfig
= NULL
;
5562 bool tagsInUse
[MAX_TIMER_PINMAP_COUNT
] = { false };
5563 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5564 headingStr
= printTimerDmaopt(currentConfig
, defaultConfig
, i
, dumpMask
, tagsInUse
, headingStr
);
5567 if (defaultConfig
) {
5568 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5569 if (!tagsInUse
[i
] && defaultConfig
[i
].ioTag
&& defaultConfig
[i
].dmaopt
!= DMA_OPT_UNUSED
) {
5570 const timerHardware_t
*timer
= timerGetByTagAndIndex(defaultConfig
[i
].ioTag
, defaultConfig
[i
].index
);
5571 headingStr
= cliPrintSectionHeading(dumpMask
, true, headingStr
);
5572 printTimerDmaoptDetails(defaultConfig
[i
].ioTag
, timer
, defaultConfig
[i
].dmaopt
, false, dumpMask
, cliDefaultPrintLinef
);
5574 printTimerDmaoptDetails(defaultConfig
[i
].ioTag
, timer
, DMA_OPT_UNUSED
, false, dumpMask
, cliDumpPrintLinef
);
5581 static void cliDmaopt(const char *cmdName
, char *cmdline
)
5586 // Peripheral name or command option
5587 pch
= strtok_r(cmdline
, " ", &saveptr
);
5589 printDmaopt(DUMP_MASTER
| HIDE_UNUSED
, NULL
);
5592 } else if (strcasecmp(pch
, "list") == 0) {
5593 cliPrintErrorLinef(cmdName
, "NOT IMPLEMENTED YET");
5598 dmaoptEntry_t
*entry
= NULL
;
5599 for (unsigned i
= 0; i
< ARRAYLEN(dmaoptEntryTable
); i
++) {
5600 if (strcasecmp(pch
, dmaoptEntryTable
[i
].device
) == 0) {
5601 entry
= &dmaoptEntryTable
[i
];
5605 if (!entry
&& strcasecmp(pch
, "pin") != 0) {
5606 cliPrintErrorLinef(cmdName
, "BAD DEVICE: %s", pch
);
5611 dmaoptValue_t orgval
= DMA_OPT_UNUSED
;
5614 dmaoptValue_t
*optaddr
= NULL
;
5616 ioTag_t ioTag
= IO_TAG_NONE
;
5617 #if defined(USE_TIMER_MGMT)
5618 timerIOConfig_t
*timerIoConfig
= NULL
;
5620 const timerHardware_t
*timer
= NULL
;
5621 pch
= strtok_r(NULL
, " ", &saveptr
);
5623 index
= pch
? (atoi(pch
) - 1) : -1;
5624 if (index
< 0 || index
>= entry
->maxIndex
|| (entry
->presenceMask
!= MASK_IGNORED
&& !(entry
->presenceMask
& BIT(index
+ 1)))) {
5625 cliPrintErrorLinef(cmdName
, "BAD INDEX: '%s'", pch
? pch
: "");
5629 const pgRegistry_t
* pg
= pgFind(entry
->pgn
);
5630 const void *currentConfig
;
5631 if (isWritingConfigToCopy()) {
5632 currentConfig
= pg
->copy
;
5634 currentConfig
= pg
->address
;
5636 optaddr
= (dmaoptValue_t
*)((uint8_t *)currentConfig
+ entry
->stride
* index
+ entry
->offset
);
5640 if (!pch
|| !(strToPin(pch
, &ioTag
) && IOGetByTag(ioTag
))) {
5641 cliPrintErrorLinef(cmdName
, "INVALID PIN: '%s'", pch
? pch
: "");
5646 orgval
= dmaoptByTag(ioTag
);
5647 #if defined(USE_TIMER_MGMT)
5648 timerIoConfig
= timerIoConfigByTag(ioTag
);
5650 timer
= timerGetConfiguredByTag(ioTag
);
5654 pch
= strtok_r(NULL
, " ", &saveptr
);
5657 printPeripheralDmaoptDetails(entry
, index
, *optaddr
, true, DUMP_MASTER
, cliDumpPrintLinef
);
5659 #if defined(USE_TIMER_MGMT)
5661 printTimerDmaoptDetails(ioTag
, timer
, orgval
, true, DUMP_MASTER
, cliDumpPrintLinef
);
5666 } else if (strcasecmp(pch
, "list") == 0) {
5667 // Show possible opts
5668 const dmaChannelSpec_t
*dmaChannelSpec
;
5670 for (int opt
= 0; (dmaChannelSpec
= dmaGetChannelSpecByPeripheral(entry
->peripheral
, index
, opt
)); opt
++) {
5671 cliPrintLinef("# %d: " DMASPEC_FORMAT_STRING
, opt
, DMA_CODE_CONTROLLER(dmaChannelSpec
->code
), DMA_CODE_STREAM(dmaChannelSpec
->code
), DMA_CODE_CHANNEL(dmaChannelSpec
->code
));
5674 for (int opt
= 0; (dmaChannelSpec
= dmaGetChannelSpecByTimerValue(timer
->tim
, timer
->channel
, opt
)); opt
++) {
5675 cliPrintLinef("# %d: " DMASPEC_FORMAT_STRING
, opt
, DMA_CODE_CONTROLLER(dmaChannelSpec
->code
), DMA_CODE_STREAM(dmaChannelSpec
->code
), DMA_CODE_CHANNEL(dmaChannelSpec
->code
));
5682 if (strcasecmp(pch
, "none") == 0) {
5683 optval
= DMA_OPT_UNUSED
;
5688 if (!dmaGetChannelSpecByPeripheral(entry
->peripheral
, index
, optval
)) {
5689 cliPrintErrorLinef(cmdName
, "INVALID DMA OPTION FOR %s %d: '%s'", entry
->device
, DMA_OPT_UI_INDEX(index
), pch
);
5694 if (!dmaGetChannelSpecByTimerValue(timer
->tim
, timer
->channel
, optval
)) {
5695 cliPrintErrorLinef(cmdName
, "INVALID DMA OPTION FOR PIN %c%02d: '%s'", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), pch
);
5702 char optvalString
[DMA_OPT_STRING_BUFSIZE
];
5703 optToString(optval
, optvalString
);
5705 char orgvalString
[DMA_OPT_STRING_BUFSIZE
];
5706 optToString(orgval
, orgvalString
);
5708 if (optval
!= orgval
) {
5712 cliPrintLinef("# dma %s %d: changed from %s to %s", entry
->device
, DMA_OPT_UI_INDEX(index
), orgvalString
, optvalString
);
5714 #if defined(USE_TIMER_MGMT)
5715 timerIoConfig
->dmaopt
= optval
;
5718 cliPrintLinef("# dma pin %c%02d: changed from %s to %s", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), orgvalString
, optvalString
);
5722 cliPrintLinef("# dma %s %d: no change: %s", entry
->device
, DMA_OPT_UI_INDEX(index
), orgvalString
);
5724 cliPrintLinef("# dma %c%02d: no change: %s", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
),orgvalString
);
5729 #endif // USE_DMA_SPEC
5732 static void cliDma(const char *cmdName
, char* cmdline
)
5734 int len
= strlen(cmdline
);
5735 if (len
&& strncasecmp(cmdline
, "show", len
) == 0) {
5741 #if defined(USE_DMA_SPEC)
5742 cliDmaopt(cmdName
, cmdline
);
5744 cliShowParseError(cmdName
);
5748 #endif // USE_RESOURCE_MGMT
5750 #ifdef USE_TIMER_MGMT
5751 static void printTimerDetails(const ioTag_t ioTag
, const unsigned timerIndex
, const bool equalsDefault
, const dumpFlags_t dumpMask
, printFn
*printValue
)
5753 const char *format
= "timer %c%02d AF%d";
5754 const char *emptyFormat
= "timer %c%02d NONE";
5756 if (timerIndex
> 0) {
5757 const timerHardware_t
*timer
= timerGetByTagAndIndex(ioTag
, timerIndex
);
5758 const bool printDetails
= printValue(dumpMask
, equalsDefault
, format
,
5759 IO_GPIOPortIdxByTag(ioTag
) + 'A',
5760 IO_GPIOPinIdxByTag(ioTag
),
5761 timer
->alternateFunction
5764 printValue(dumpMask
, false,
5765 "# pin %c%02d: TIM%d CH%d%s (AF%d)",
5766 IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
),
5767 timerGetTIMNumber(timer
->tim
),
5768 CC_INDEX_FROM_CHANNEL(timer
->channel
) + 1,
5769 timer
->output
& TIMER_OUTPUT_N_CHANNEL
? "N" : "",
5770 timer
->alternateFunction
5774 printValue(dumpMask
, equalsDefault
, emptyFormat
,
5775 IO_GPIOPortIdxByTag(ioTag
) + 'A',
5776 IO_GPIOPinIdxByTag(ioTag
)
5781 static void printTimer(dumpFlags_t dumpMask
, const char *headingStr
)
5783 const pgRegistry_t
* pg
= pgFind(PG_TIMER_IO_CONFIG
);
5784 const timerIOConfig_t
*currentConfig
;
5785 const timerIOConfig_t
*defaultConfig
;
5787 headingStr
= cliPrintSectionHeading(dumpMask
, false, headingStr
);
5788 if (isReadingConfigFromCopy()) {
5789 currentConfig
= (timerIOConfig_t
*)pg
->copy
;
5790 defaultConfig
= (timerIOConfig_t
*)pg
->address
;
5792 currentConfig
= (timerIOConfig_t
*)pg
->address
;
5793 defaultConfig
= NULL
;
5796 bool tagsInUse
[MAX_TIMER_PINMAP_COUNT
] = { false };
5797 for (unsigned int i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5798 const ioTag_t ioTag
= currentConfig
[i
].ioTag
;
5804 const uint8_t timerIndex
= currentConfig
[i
].index
;
5806 uint8_t defaultTimerIndex
= 0;
5807 if (defaultConfig
) {
5808 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5809 if (defaultConfig
[i
].ioTag
== ioTag
) {
5810 defaultTimerIndex
= defaultConfig
[i
].index
;
5811 tagsInUse
[i
] = true;
5818 const bool equalsDefault
= defaultTimerIndex
== timerIndex
;
5819 headingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, headingStr
);
5820 if (defaultConfig
&& defaultTimerIndex
) {
5821 printTimerDetails(ioTag
, defaultTimerIndex
, equalsDefault
, dumpMask
, cliDefaultPrintLinef
);
5824 printTimerDetails(ioTag
, timerIndex
, equalsDefault
, dumpMask
, cliDumpPrintLinef
);
5827 if (defaultConfig
) {
5828 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5829 if (!tagsInUse
[i
] && defaultConfig
[i
].ioTag
) {
5830 headingStr
= cliPrintSectionHeading(DO_DIFF
, true, headingStr
);
5831 printTimerDetails(defaultConfig
[i
].ioTag
, defaultConfig
[i
].index
, false, dumpMask
, cliDefaultPrintLinef
);
5833 printTimerDetails(defaultConfig
[i
].ioTag
, 0, false, dumpMask
, cliDumpPrintLinef
);
5839 #define TIMER_INDEX_UNDEFINED -1
5840 #define TIMER_AF_STRING_BUFSIZE 5
5842 static void alternateFunctionToString(const ioTag_t ioTag
, const int index
, char *buf
)
5844 const timerHardware_t
*timer
= timerGetByTagAndIndex(ioTag
, index
+ 1);
5846 memcpy(buf
, "NONE", TIMER_AF_STRING_BUFSIZE
);
5848 tfp_sprintf(buf
, "AF%d", timer
->alternateFunction
);
5852 static void showTimers(void)
5857 cliPrintLine("Timers:");
5859 cliPrintLine("Currently active Timers:");
5864 for (int i
= 0; (timerNumber
= timerGetNumberByIndex(i
)); i
++) {
5865 cliPrintf("TIM%d:", timerNumber
);
5866 bool timerUsed
= false;
5867 for (unsigned timerIndex
= 0; timerIndex
< CC_CHANNELS_PER_TIMER
; timerIndex
++) {
5868 const timerHardware_t
*timer
= timerGetAllocatedByNumberAndChannel(timerNumber
, CC_CHANNEL_FROM_INDEX(timerIndex
));
5869 const resourceOwner_t
*timerOwner
= timerGetOwner(timer
);
5870 if (timerOwner
->owner
) {
5877 if (timerOwner
->resourceIndex
> 0) {
5878 cliPrintLinef(" CH%d%s: %s %d", timerIndex
+ 1, timer
->output
& TIMER_OUTPUT_N_CHANNEL
? "N" : " ", ownerNames
[timerOwner
->owner
], timerOwner
->resourceIndex
);
5880 cliPrintLinef(" CH%d%s: %s", timerIndex
+ 1, timer
->output
& TIMER_OUTPUT_N_CHANNEL
? "N" : " ", ownerNames
[timerOwner
->owner
]);
5886 cliPrintLine(" FREE");
5891 static void cliTimer(const char *cmdName
, char *cmdline
)
5893 int len
= strlen(cmdline
);
5896 printTimer(DUMP_MASTER
, NULL
);
5899 } else if (strncasecmp(cmdline
, "list", len
) == 0) {
5900 cliPrintErrorLinef(cmdName
, "NOT IMPLEMENTED YET");
5903 } else if (strncasecmp(cmdline
, "show", len
) == 0) {
5912 ioTag_t ioTag
= IO_TAG_NONE
;
5913 pch
= strtok_r(cmdline
, " ", &saveptr
);
5914 if (!pch
|| !strToPin(pch
, &ioTag
)) {
5915 cliShowParseError(cmdName
);
5918 } else if (!IOGetByTag(ioTag
)) {
5919 cliPrintErrorLinef(cmdName
, "PIN NOT USED ON BOARD.");
5924 int timerIOIndex
= TIMER_INDEX_UNDEFINED
;
5925 bool isExistingTimerOpt
= false;
5926 /* find existing entry, or go for next available */
5927 for (unsigned i
= 0; i
< MAX_TIMER_PINMAP_COUNT
; i
++) {
5928 if (timerIOConfig(i
)->ioTag
== ioTag
) {
5930 isExistingTimerOpt
= true;
5935 /* first available empty slot */
5936 if (timerIOIndex
< 0 && timerIOConfig(i
)->ioTag
== IO_TAG_NONE
) {
5941 if (timerIOIndex
< 0) {
5942 cliPrintErrorLinef(cmdName
, "PIN TIMER MAP FULL.");
5947 pch
= strtok_r(NULL
, " ", &saveptr
);
5949 int timerIndex
= TIMER_INDEX_UNDEFINED
;
5950 if (strcasecmp(pch
, "list") == 0) {
5951 /* output the list of available options */
5952 const timerHardware_t
*timer
;
5953 for (unsigned index
= 0; (timer
= timerGetByTagAndIndex(ioTag
, index
+ 1)); index
++) {
5954 cliPrintLinef("# AF%d: TIM%d CH%d%s",
5955 timer
->alternateFunction
,
5956 timerGetTIMNumber(timer
->tim
),
5957 CC_INDEX_FROM_CHANNEL(timer
->channel
) + 1,
5958 timer
->output
& TIMER_OUTPUT_N_CHANNEL
? "N" : ""
5963 } else if (strncasecmp(pch
, "af", 2) == 0) {
5964 unsigned alternateFunction
= atoi(&pch
[2]);
5966 const timerHardware_t
*timer
;
5967 for (unsigned index
= 0; (timer
= timerGetByTagAndIndex(ioTag
, index
+ 1)); index
++) {
5968 if (timer
->alternateFunction
== alternateFunction
) {
5976 cliPrintErrorLinef(cmdName
, "INVALID ALTERNATE FUNCTION FOR %c%02d: '%s'", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), pch
);
5980 } else if (strcasecmp(pch
, "none") != 0) {
5981 cliPrintErrorLinef(cmdName
, "INVALID TIMER OPTION FOR %c%02d: '%s'", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), pch
);
5986 int oldTimerIndex
= isExistingTimerOpt
? timerIOConfig(timerIOIndex
)->index
- 1 : -1;
5987 timerIOConfigMutable(timerIOIndex
)->ioTag
= timerIndex
== TIMER_INDEX_UNDEFINED
? IO_TAG_NONE
: ioTag
;
5988 timerIOConfigMutable(timerIOIndex
)->index
= timerIndex
+ 1;
5989 timerIOConfigMutable(timerIOIndex
)->dmaopt
= DMA_OPT_UNUSED
;
5991 char optvalString
[DMA_OPT_STRING_BUFSIZE
];
5992 alternateFunctionToString(ioTag
, timerIndex
, optvalString
);
5994 char orgvalString
[DMA_OPT_STRING_BUFSIZE
];
5995 alternateFunctionToString(ioTag
, oldTimerIndex
, orgvalString
);
5997 if (timerIndex
== oldTimerIndex
) {
5998 cliPrintLinef("# timer %c%02d: no change: %s", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), orgvalString
);
6000 cliPrintLinef("# timer %c%02d: changed from %s to %s", IO_GPIOPortIdxByTag(ioTag
) + 'A', IO_GPIOPinIdxByTag(ioTag
), orgvalString
, optvalString
);
6005 printTimerDetails(ioTag
, timerIOConfig(timerIOIndex
)->index
, false, DUMP_MASTER
, cliDumpPrintLinef
);
6012 #if defined(USE_RESOURCE_MGMT)
6013 static void cliResource(const char *cmdName
, char *cmdline
)
6018 pch
= strtok_r(cmdline
, " ", &saveptr
);
6020 printResource(DUMP_MASTER
| HIDE_UNUSED
, NULL
);
6023 } else if (strcasecmp(pch
, "show") == 0) {
6027 cliPrintLine("Currently active IO resource assignments:\r\n(reboot to update)");
6030 for (int i
= 0; i
< DEFIO_IO_USED_COUNT
; i
++) {
6032 owner
= ownerNames
[ioRecs
[i
].owner
];
6034 cliPrintf("%c%02d: %s", IO_GPIOPortIdx(ioRecs
+ i
) + 'A', IO_GPIOPinIdx(ioRecs
+ i
), owner
);
6035 if (ioRecs
[i
].index
> 0) {
6036 cliPrintf(" %d", ioRecs
[i
].index
);
6041 pch
= strtok_r(NULL
, " ", &saveptr
);
6042 if (strcasecmp(pch
, "all") == 0) {
6043 #if defined(USE_TIMER_MGMT)
6044 cliTimer(cmdName
, "show");
6046 #if defined(USE_DMA)
6047 cliDma(cmdName
, "show");
6054 unsigned resourceIndex
= 0;
6055 for (; ; resourceIndex
++) {
6056 if (resourceIndex
>= ARRAYLEN(resourceTable
)) {
6057 cliPrintErrorLinef(cmdName
, "INVALID RESOURCE NAME: '%s'", pch
);
6061 const char *resourceName
= ownerNames
[resourceTable
[resourceIndex
].owner
];
6062 if (strncasecmp(pch
, resourceName
, strlen(resourceName
)) == 0) {
6067 pch
= strtok_r(NULL
, " ", &saveptr
);
6068 int index
= atoi(pch
);
6070 if (resourceTable
[resourceIndex
].maxIndex
> 0 || index
> 0) {
6071 if (index
<= 0 || index
> RESOURCE_VALUE_MAX_INDEX(resourceTable
[resourceIndex
].maxIndex
)) {
6072 cliShowArgumentRangeError(cmdName
, "INDEX", 1, RESOURCE_VALUE_MAX_INDEX(resourceTable
[resourceIndex
].maxIndex
));
6077 pch
= strtok_r(NULL
, " ", &saveptr
);
6080 ioTag_t
*tag
= getIoTag(resourceTable
[resourceIndex
], index
);
6082 if (strlen(pch
) > 0) {
6083 if (strToPin(pch
, tag
)) {
6084 if (*tag
== IO_TAG_NONE
) {
6086 cliPrintLine("Freed");
6088 cliPrintLine("Resource is freed");
6092 ioRec_t
*rec
= IO_Rec(IOGetByTag(*tag
));
6094 resourceCheck(resourceIndex
, index
, *tag
);
6096 cliPrintLinef(" %c%02d set", IO_GPIOPortIdx(rec
) + 'A', IO_GPIOPinIdx(rec
));
6098 cliPrintLinef("\r\nResource is set to %c%02d", IO_GPIOPortIdx(rec
) + 'A', IO_GPIOPinIdx(rec
));
6101 cliShowParseError(cmdName
);
6108 cliShowParseError(cmdName
);
6112 #ifdef USE_DSHOT_TELEMETRY
6115 static void cliDshotTelemetryInfo(const char *cmdName
, char *cmdline
)
6120 if (useDshotTelemetry
) {
6121 cliPrintLinef("Dshot reads: %u", dshotTelemetryState
.readCount
);
6122 cliPrintLinef("Dshot invalid pkts: %u", dshotTelemetryState
.invalidPacketCount
);
6123 int32_t directionChangeCycles
= cmp32(dshotDMAHandlerCycleCounters
.changeDirectionCompletedAt
, dshotDMAHandlerCycleCounters
.irqAt
);
6124 int32_t directionChangeDurationUs
= clockCyclesToMicros(directionChangeCycles
);
6125 cliPrintLinef("Dshot directionChange cycles: %u, micros: %u", directionChangeCycles
, directionChangeDurationUs
);
6128 #ifdef USE_DSHOT_TELEMETRY_STATS
6129 cliPrintLine("Motor Type eRPM RPM Hz Invalid TEMP VCC CURR ST/EV DBG1 DBG2 DBG3");
6130 cliPrintLine("===== ====== ====== ====== ====== ======= ====== ====== ====== ====== ====== ====== ======");
6132 cliPrintLine("Motor Type eRPM RPM Hz TEMP VCC CURR ST/EV DBG1 DBG2 DBG3");
6133 cliPrintLine("===== ====== ====== ====== ====== ====== ====== ====== ====== ====== ====== ======");
6136 for (uint8_t i
= 0; i
< getMotorCount(); i
++) {
6137 const uint16_t erpm
= getDshotTelemetry(i
);
6138 const uint16_t rpm
= erpmToRpm(erpm
);
6140 cliPrintf("%5d %c%c%c%c%c %6d %6d %6d",
6142 ((dshotTelemetryState
.motorState
[i
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_eRPM
)) ? 'R' : '-'),
6143 ((dshotTelemetryState
.motorState
[i
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_TEMPERATURE
)) ? 'T' : '-'),
6144 ((dshotTelemetryState
.motorState
[i
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_VOLTAGE
)) ? 'V' : '-'),
6145 ((dshotTelemetryState
.motorState
[i
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_CURRENT
)) ? 'C' : '-'),
6146 ((dshotTelemetryState
.motorState
[i
].telemetryTypes
& (1 << DSHOT_TELEMETRY_TYPE_STATE_EVENTS
)) ? 'S' : '-'),
6147 erpm
* 100, rpm
, rpm
/ 60);
6149 #ifdef USE_DSHOT_TELEMETRY_STATS
6150 if (isDshotMotorTelemetryActive(i
)) {
6151 int32_t calcPercent
= getDshotTelemetryMotorInvalidPercent(i
);
6152 cliPrintf(" %3d.%02d%%", calcPercent
/ 100, calcPercent
% 100);
6154 cliPrint(" NO DATA");
6158 cliPrintLinef(" %6d %3d.%02d %6d %6d %6d %6d %6d",
6159 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_TEMPERATURE
],
6160 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_VOLTAGE
] / 4,
6161 25 * (dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_VOLTAGE
] % 4),
6162 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_CURRENT
],
6163 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_STATE_EVENTS
],
6164 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_DEBUG1
],
6165 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_DEBUG2
],
6166 dshotTelemetryState
.motorState
[i
].telemetryData
[DSHOT_TELEMETRY_TYPE_DEBUG3
]
6171 const int len
= MAX_GCR_EDGES
;
6172 #ifdef DEBUG_BBDECODE
6173 extern uint16_t bbBuffer
[134];
6174 for (int i
= 0; i
< 134; i
++) {
6175 cliPrintf("%u ", (int)bbBuffer
[i
]);
6179 for (int i
= 0; i
< len
; i
++) {
6180 cliPrintf("%u ", (int)dshotTelemetryState
.inputBuffer
[i
]);
6183 for (int i
= 1; i
< len
; i
++) {
6184 cliPrintf("%u ", (int)(dshotTelemetryState
.inputBuffer
[i
] - dshotTelemetryState
.inputBuffer
[i
-1]));
6188 cliPrintLine("Dshot telemetry not enabled");
6194 static void printConfig(const char *cmdName
, char *cmdline
, bool doDiff
)
6196 dumpFlags_t dumpMask
= DUMP_MASTER
;
6198 if ((options
= checkCommand(cmdline
, "master"))) {
6199 dumpMask
= DUMP_MASTER
; // only
6200 } else if ((options
= checkCommand(cmdline
, "profile"))) {
6201 dumpMask
= DUMP_PROFILE
; // only
6202 } else if ((options
= checkCommand(cmdline
, "rates"))) {
6203 dumpMask
= DUMP_RATES
; // only
6204 } else if ((options
= checkCommand(cmdline
, "hardware"))) {
6205 dumpMask
= DUMP_MASTER
| HARDWARE_ONLY
; // Show only hardware related settings (useful to generate unified target configs).
6206 } else if ((options
= checkCommand(cmdline
, "all"))) {
6207 dumpMask
= DUMP_ALL
; // all profiles and rates
6213 dumpMask
= dumpMask
| DO_DIFF
;
6216 if (checkCommand(options
, "defaults")) {
6217 dumpMask
= dumpMask
| SHOW_DEFAULTS
; // add default values as comments for changed values
6218 } else if (checkCommand(options
, "bare")) {
6219 dumpMask
= dumpMask
| BARE
; // show the diff / dump without extra commands and board specific data
6222 backupAndResetConfigs((dumpMask
& BARE
) == 0);
6224 #ifdef USE_CLI_BATCH
6225 bool batchModeEnabled
= false;
6227 if ((dumpMask
& DUMP_MASTER
) || (dumpMask
& DUMP_ALL
)) {
6228 cliPrintHashLine("version");
6229 printVersion(cmdName
, false);
6231 if (!(dumpMask
& BARE
)) {
6232 #ifdef USE_CLI_BATCH
6233 cliPrintHashLine("start the command batch");
6234 cliPrintLine("batch start");
6235 batchModeEnabled
= true;
6238 if ((dumpMask
& (DUMP_ALL
| DO_DIFF
)) == (DUMP_ALL
| DO_DIFF
)) {
6239 cliPrintHashLine("reset configuration to default settings");
6240 cliPrintLine("defaults nosave");
6244 #if defined(USE_BOARD_INFO)
6246 printBoardName(dumpMask
);
6247 printManufacturerId(dumpMask
);
6250 if ((dumpMask
& DUMP_ALL
) && !(dumpMask
& BARE
)) {
6251 cliMcuId(cmdName
, "");
6252 #if defined(USE_SIGNATURE)
6253 cliSignature(cmdName
, "");
6257 if (!(dumpMask
& HARDWARE_ONLY
)) {
6258 printCraftName(dumpMask
, &pilotConfig_Copy
);
6261 #ifdef USE_RESOURCE_MGMT
6262 printResource(dumpMask
, "resources");
6263 #if defined(USE_TIMER_MGMT)
6264 printTimer(dumpMask
, "timer");
6267 printDmaopt(dumpMask
, "dma");
6271 printFeature(dumpMask
, featureConfig_Copy
.enabledFeatures
, featureConfig()->enabledFeatures
, "feature");
6273 printSerial(dumpMask
, &serialConfig_Copy
, serialConfig(), "serial");
6275 if (!(dumpMask
& HARDWARE_ONLY
)) {
6276 #ifndef USE_QUAD_MIXER_ONLY
6277 const char *mixerHeadingStr
= "mixer";
6278 const bool equalsDefault
= mixerConfig_Copy
.mixerMode
== mixerConfig()->mixerMode
;
6279 mixerHeadingStr
= cliPrintSectionHeading(dumpMask
, !equalsDefault
, mixerHeadingStr
);
6280 const char *formatMixer
= "mixer %s";
6281 cliDefaultPrintLinef(dumpMask
, equalsDefault
, formatMixer
, mixerNames
[mixerConfig()->mixerMode
- 1]);
6282 cliDumpPrintLinef(dumpMask
, equalsDefault
, formatMixer
, mixerNames
[mixerConfig_Copy
.mixerMode
- 1]);
6284 cliDumpPrintLinef(dumpMask
, customMotorMixer(0)->throttle
== 0.0f
, "\r\nmmix reset\r\n");
6286 printMotorMix(dumpMask
, customMotorMixer_CopyArray
, customMotorMixer(0), mixerHeadingStr
);
6289 printServo(dumpMask
, servoParams_CopyArray
, servoParams(0), "servo");
6291 const char *servoMixHeadingStr
= "servo mixer";
6292 if (!(dumpMask
& DO_DIFF
) || customServoMixers(0)->rate
!= 0) {
6293 cliPrintHashLine(servoMixHeadingStr
);
6294 cliPrintLine("smix reset\r\n");
6295 servoMixHeadingStr
= NULL
;
6297 printServoMix(dumpMask
, customServoMixers_CopyArray
, customServoMixers(0), servoMixHeadingStr
);
6301 #if defined(USE_BEEPER)
6302 printBeeper(dumpMask
, beeperConfig_Copy
.beeper_off_flags
, beeperConfig()->beeper_off_flags
, "beeper", BEEPER_ALLOWED_MODES
, "beeper");
6304 #if defined(USE_DSHOT)
6305 printBeeper(dumpMask
, beeperConfig_Copy
.dshotBeaconOffFlags
, beeperConfig()->dshotBeaconOffFlags
, "beacon", DSHOT_BEACON_ALLOWED_MODES
, "beacon");
6307 #endif // USE_BEEPER
6309 printMap(dumpMask
, &rxConfig_Copy
, rxConfig(), "map");
6311 #ifdef USE_LED_STRIP_STATUS_MODE
6312 printLed(dumpMask
, ledStripStatusModeConfig_Copy
.ledConfigs
, ledStripStatusModeConfig()->ledConfigs
, "led");
6314 printColor(dumpMask
, ledStripStatusModeConfig_Copy
.colors
, ledStripStatusModeConfig()->colors
, "color");
6316 printModeColor(dumpMask
, &ledStripStatusModeConfig_Copy
, ledStripStatusModeConfig(), "mode_color");
6319 printAux(dumpMask
, modeActivationConditions_CopyArray
, modeActivationConditions(0), "aux");
6321 printAdjustmentRange(dumpMask
, adjustmentRanges_CopyArray
, adjustmentRanges(0), "adjrange");
6323 printRxRange(dumpMask
, rxChannelRangeConfigs_CopyArray
, rxChannelRangeConfigs(0), "rxrange");
6325 #ifdef USE_VTX_TABLE
6326 printVtxTable(dumpMask
, &vtxTableConfig_Copy
, vtxTableConfig(), "vtxtable");
6329 #ifdef USE_VTX_CONTROL
6330 printVtx(dumpMask
, &vtxConfig_Copy
, vtxConfig(), "vtx");
6333 printRxFailsafe(dumpMask
, rxFailsafeChannelConfigs_CopyArray
, rxFailsafeChannelConfigs(0), "rxfail");
6336 if (dumpMask
& HARDWARE_ONLY
) {
6337 dumpAllValues(cmdName
, HARDWARE_VALUE
, dumpMask
, "master");
6339 dumpAllValues(cmdName
, MASTER_VALUE
, dumpMask
, "master");
6341 if (dumpMask
& DUMP_ALL
) {
6342 for (uint32_t pidProfileIndex
= 0; pidProfileIndex
< PID_PROFILE_COUNT
; pidProfileIndex
++) {
6343 cliDumpPidProfile(cmdName
, pidProfileIndex
, dumpMask
);
6346 pidProfileIndexToUse
= systemConfig_Copy
.pidProfileIndex
;
6348 if (!(dumpMask
& BARE
)) {
6349 cliPrintHashLine("restore original profile selection");
6351 cliProfile(cmdName
, "");
6354 pidProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
6356 for (uint32_t rateIndex
= 0; rateIndex
< CONTROL_RATE_PROFILE_COUNT
; rateIndex
++) {
6357 cliDumpRateProfile(cmdName
, rateIndex
, dumpMask
);
6360 rateProfileIndexToUse
= systemConfig_Copy
.activeRateProfile
;
6362 if (!(dumpMask
& BARE
)) {
6363 cliPrintHashLine("restore original rateprofile selection");
6365 cliRateProfile(cmdName
, "");
6367 cliPrintHashLine("save configuration");
6369 #ifdef USE_CLI_BATCH
6370 batchModeEnabled
= false;
6374 rateProfileIndexToUse
= CURRENT_PROFILE_INDEX
;
6376 cliDumpPidProfile(cmdName
, systemConfig_Copy
.pidProfileIndex
, dumpMask
);
6378 cliDumpRateProfile(cmdName
, systemConfig_Copy
.activeRateProfile
, dumpMask
);
6381 } else if (dumpMask
& DUMP_PROFILE
) {
6382 cliDumpPidProfile(cmdName
, systemConfig_Copy
.pidProfileIndex
, dumpMask
);
6383 } else if (dumpMask
& DUMP_RATES
) {
6384 cliDumpRateProfile(cmdName
, systemConfig_Copy
.activeRateProfile
, dumpMask
);
6387 #ifdef USE_CLI_BATCH
6388 if (batchModeEnabled
) {
6389 cliPrintHashLine("end the command batch");
6390 cliPrintLine("batch end");
6394 // restore configs from copies
6398 static void cliDump(const char *cmdName
, char *cmdline
)
6400 printConfig(cmdName
, cmdline
, false);
6403 static void cliDiff(const char *cmdName
, char *cmdline
)
6405 printConfig(cmdName
, cmdline
, true);
6408 #if defined(USE_USB_MSC)
6409 static void cliMsc(const char *cmdName
, char *cmdline
)
6411 if (mscCheckFilesystemReady()) {
6413 int timezoneOffsetMinutes
= timeConfig()->tz_offsetMinutes
;
6414 if (!isEmpty(cmdline
)) {
6415 timezoneOffsetMinutes
= atoi(cmdline
);
6416 if ((timezoneOffsetMinutes
< TIMEZONE_OFFSET_MINUTES_MIN
) || (timezoneOffsetMinutes
> TIMEZONE_OFFSET_MINUTES_MAX
)) {
6417 cliPrintErrorLinef(cmdName
, "INVALID TIMEZONE OFFSET");
6422 int timezoneOffsetMinutes
= 0;
6425 cliPrintHashLine("Restarting in mass storage mode");
6426 cliPrint("\r\nRebooting");
6428 waitForSerialPortToFinishTransmitting(cliPort
);
6431 systemResetToMsc(timezoneOffsetMinutes
);
6433 cliPrintHashLine("Storage not present or failed to initialize!");
6438 typedef void cliCommandFn(const char* name
, char *cmdline
);
6443 const char *description
;
6446 cliCommandFn
*cliCommand
;
6450 #define CLI_COMMAND_DEF(name, description, args, cliCommand) \
6458 #define CLI_COMMAND_DEF(name, description, args, cliCommand) \
6465 static void cliHelp(const char *cmdName
, char *cmdline
);
6467 // should be sorted a..z for bsearch()
6468 const clicmd_t cmdTable
[] = {
6469 CLI_COMMAND_DEF("adjrange", "configure adjustment ranges", "<index> <unused> <range channel> <start> <end> <function> <select channel> [<center> <scale>]", cliAdjustmentRange
),
6470 CLI_COMMAND_DEF("aux", "configure modes", "<index> <mode> <aux> <start> <end> <logic>", cliAux
),
6471 #ifdef USE_CLI_BATCH
6472 CLI_COMMAND_DEF("batch", "start or end a batch of commands", "start | end", cliBatch
),
6474 #if defined(USE_BEEPER)
6475 #if defined(USE_DSHOT)
6476 CLI_COMMAND_DEF("beacon", "enable/disable Dshot beacon for a condition", "list\r\n"
6477 "\t<->[name]", cliBeacon
),
6479 CLI_COMMAND_DEF("beeper", "enable/disable beeper for a condition", "list\r\n"
6480 "\t<->[name]", cliBeeper
),
6481 #endif // USE_BEEPER
6482 #if defined(USE_RX_BIND)
6483 CLI_COMMAND_DEF("bind_rx", "initiate binding for RX SPI or SRXL2", NULL
, cliRxBind
),
6485 #if defined(USE_FLASH_BOOT_LOADER)
6486 CLI_COMMAND_DEF("bl", "reboot into bootloader", "[flash|rom]", cliBootloader
),
6488 CLI_COMMAND_DEF("bl", "reboot into bootloader", "[rom]", cliBootloader
),
6490 #if defined(USE_BOARD_INFO)
6491 CLI_COMMAND_DEF("board_name", "get / set the name of the board model", "[board name]", cliBoardName
),
6493 #ifdef USE_LED_STRIP_STATUS_MODE
6494 CLI_COMMAND_DEF("color", "configure colors", NULL
, cliColor
),
6496 #if defined(USE_CUSTOM_DEFAULTS)
6497 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{show} {nosave} {bare} {group_id <id>}", cliDefaults
),
6499 CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "{nosave}", cliDefaults
),
6501 CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff
),
6502 #ifdef USE_RESOURCE_MGMT
6506 CLI_COMMAND_DEF("dma", "show/set DMA assignments", "<> | <device> <index> list | <device> <index> [<option>|none] | list | show", cliDma
),
6508 CLI_COMMAND_DEF("dma", "show DMA assignments", "show", cliDma
),
6513 #ifdef USE_DSHOT_TELEMETRY
6514 CLI_COMMAND_DEF("dshot_telemetry_info", "display dshot telemetry info and stats", NULL
, cliDshotTelemetryInfo
),
6517 CLI_COMMAND_DEF("dshotprog", "program DShot ESC(s)", "<index> <command>+", cliDshotProg
),
6519 CLI_COMMAND_DEF("dump", "dump configuration",
6520 "[master|profile|rates|hardware|all] {defaults|bare}", cliDump
),
6521 #ifdef USE_ESCSERIAL
6522 CLI_COMMAND_DEF("escprog", "passthrough esc to serial", "<mode [sk/bl/ki/cc]> <index>", cliEscPassthrough
),
6524 CLI_COMMAND_DEF("exit", NULL
, NULL
, cliExit
),
6525 CLI_COMMAND_DEF("feature", "configure features",
6527 "\t<->[name]", cliFeature
),
6528 #ifdef USE_FLASH_CHIP
6530 CLI_COMMAND_DEF("flash_erase", "erase flash chip", NULL
, cliFlashErase
),
6532 CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL
, cliFlashInfo
),
6533 #if defined(USE_FLASH_TOOLS) && defined(USE_FLASHFS)
6534 CLI_COMMAND_DEF("flash_read", NULL
, "<length> <address>", cliFlashRead
),
6535 CLI_COMMAND_DEF("flash_scan", "scan flash device for errors", NULL
, cliFlashVerify
),
6536 CLI_COMMAND_DEF("flash_write", NULL
, "<address> <message>", cliFlashWrite
),
6539 CLI_COMMAND_DEF("get", "get variable value", "[name]", cliGet
),
6541 CLI_COMMAND_DEF("gpspassthrough", "passthrough gps to serial", NULL
, cliGpsPassthrough
),
6543 #if defined(USE_GYRO_REGISTER_DUMP) && !defined(SIMULATOR_BUILD)
6544 CLI_COMMAND_DEF("gyroregisters", "dump gyro config registers contents", NULL
, cliDumpGyroRegisters
),
6546 CLI_COMMAND_DEF("help", "display command help", "[search string]", cliHelp
),
6547 #ifdef USE_LED_STRIP_STATUS_MODE
6548 CLI_COMMAND_DEF("led", "configure leds", NULL
, cliLed
),
6550 #if defined(USE_BOARD_INFO)
6551 CLI_COMMAND_DEF("manufacturer_id", "get / set the id of the board manufacturer", "[manufacturer id]", cliManufacturerId
),
6553 CLI_COMMAND_DEF("map", "configure rc channel order", "[<map>]", cliMap
),
6554 CLI_COMMAND_DEF("mcu_id", "id of the microcontroller", NULL
, cliMcuId
),
6555 #ifndef USE_QUAD_MIXER_ONLY
6556 CLI_COMMAND_DEF("mixer", "configure mixer", "list\r\n\t<name>", cliMixer
),
6558 CLI_COMMAND_DEF("mmix", "custom motor mixer", NULL
, cliMotorMix
),
6559 #ifdef USE_LED_STRIP_STATUS_MODE
6560 CLI_COMMAND_DEF("mode_color", "configure mode and special colors", NULL
, cliModeColor
),
6562 CLI_COMMAND_DEF("motor", "get/set motor", "<index> [<value>]", cliMotor
),
6565 CLI_COMMAND_DEF("msc", "switch into msc mode", "[<timezone offset minutes>]", cliMsc
),
6567 CLI_COMMAND_DEF("msc", "switch into msc mode", NULL
, cliMsc
),
6571 CLI_COMMAND_DEF("play_sound", NULL
, "[<index>]", cliPlaySound
),
6573 CLI_COMMAND_DEF("profile", "change profile", "[<index>]", cliProfile
),
6574 CLI_COMMAND_DEF("rateprofile", "change rate profile", "[<index>]", cliRateProfile
),
6575 #ifdef USE_RC_SMOOTHING_FILTER
6576 CLI_COMMAND_DEF("rc_smoothing_info", "show rc_smoothing operational settings", NULL
, cliRcSmoothing
),
6577 #endif // USE_RC_SMOOTHING_FILTER
6578 #ifdef USE_RESOURCE_MGMT
6579 CLI_COMMAND_DEF("resource", "show/set resources", "<> | <resource name> <index> [<pin>|none] | show [all]", cliResource
),
6581 CLI_COMMAND_DEF("rxfail", "show/set rx failsafe settings", NULL
, cliRxFailsafe
),
6582 CLI_COMMAND_DEF("rxrange", "configure rx channel ranges", NULL
, cliRxRange
),
6583 CLI_COMMAND_DEF("save", "save and reboot", NULL
, cliSave
),
6585 CLI_COMMAND_DEF("sd_info", "sdcard info", NULL
, cliSdInfo
),
6587 CLI_COMMAND_DEF("serial", "configure serial ports", NULL
, cliSerial
),
6588 #if defined(USE_SERIAL_PASSTHROUGH)
6589 #if defined(USE_PINIO)
6590 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data data from port 1 to VCP / port 2", "<id1> [<baud1>] [<mode1>] [none|<dtr pinio>|reset] [<id2>] [<baud2>] [<mode2>]", cliSerialPassthrough
),
6592 CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data from port 1 to VCP / port 2", "<id1> [<baud1>] [<mode1>] [none|reset] [<id2>] [<baud2>] [<mode2>]", cliSerialPassthrough
),
6596 CLI_COMMAND_DEF("servo", "configure servos", NULL
, cliServo
),
6598 CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet
),
6599 #if defined(USE_SIGNATURE)
6600 CLI_COMMAND_DEF("signature", "get / set the board type signature", "[signature]", cliSignature
),
6602 #if defined(USE_SIMPLIFIED_TUNING)
6603 CLI_COMMAND_DEF("simplified_tuning", "applies or disables simplified tuning", "apply | disable", cliSimplifiedTuning
),
6606 CLI_COMMAND_DEF("smix", "servo mixer", "<rule> <servo> <source> <rate> <speed> <min> <max> <box>\r\n"
6608 "\tload <mixer>\r\n"
6609 "\treverse <servo> <source> r|n", cliServoMix
),
6611 CLI_COMMAND_DEF("status", "show status", NULL
, cliStatus
),
6612 CLI_COMMAND_DEF("tasks", "show task stats", NULL
, cliTasks
),
6613 #ifdef USE_TIMER_MGMT
6614 CLI_COMMAND_DEF("timer", "show/set timers", "<> | <pin> list | <pin> [af<alternate function>|none|<option(deprecated)>] | list | show", cliTimer
),
6616 CLI_COMMAND_DEF("version", "show version", NULL
, cliVersion
),
6617 #ifdef USE_VTX_CONTROL
6619 CLI_COMMAND_DEF("vtx", "vtx channels on switch", NULL
, cliVtx
),
6621 CLI_COMMAND_DEF("vtx", "vtx channels on switch", "<index> <aux_channel> <vtx_band> <vtx_channel> <vtx_power> <start_range> <end_range>", cliVtx
),
6624 #ifdef USE_VTX_TABLE
6625 CLI_COMMAND_DEF("vtx_info", "vtx power config dump", NULL
, cliVtxInfo
),
6626 CLI_COMMAND_DEF("vtxtable", "vtx frequency table", "<band> <bandname> <bandletter> [FACTORY|CUSTOM] <freq> ... <freq>\r\n", cliVtxTable
),
6630 static void cliHelp(const char *cmdName
, char *cmdline
)
6632 bool anyMatches
= false;
6634 for (uint32_t i
= 0; i
< ARRAYLEN(cmdTable
); i
++) {
6635 bool printEntry
= false;
6636 if (isEmpty(cmdline
)) {
6639 if (strcasestr(cmdTable
[i
].name
, cmdline
)
6641 || strcasestr(cmdTable
[i
].description
, cmdline
)
6650 cliPrint(cmdTable
[i
].name
);
6652 if (cmdTable
[i
].description
) {
6653 cliPrintf(" - %s", cmdTable
[i
].description
);
6655 if (cmdTable
[i
].args
) {
6656 cliPrintf("\r\n\t%s", cmdTable
[i
].args
);
6662 if (!isEmpty(cmdline
) && !anyMatches
) {
6663 cliPrintErrorLinef(cmdName
, "NO MATCHES FOR '%s'", cmdline
);
6667 static void processCharacter(const char c
)
6669 if (bufferIndex
&& (c
== '\n' || c
== '\r')) {
6673 #if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS)
6674 if (processingCustomDefaults
) {
6679 // Strip comment starting with # from line
6680 char *p
= cliBuffer
;
6683 bufferIndex
= (uint32_t)(p
- cliBuffer
);
6686 // Strip trailing whitespace
6687 while (bufferIndex
> 0 && cliBuffer
[bufferIndex
- 1] == ' ') {
6691 // Process non-empty lines
6692 if (bufferIndex
> 0) {
6693 cliBuffer
[bufferIndex
] = 0; // null terminate
6695 const clicmd_t
*cmd
;
6697 for (cmd
= cmdTable
; cmd
< cmdTable
+ ARRAYLEN(cmdTable
); cmd
++) {
6698 if ((options
= checkCommand(cliBuffer
, cmd
->name
))) {
6702 if (cmd
< cmdTable
+ ARRAYLEN(cmdTable
)) {
6703 cmd
->cliCommand(cmd
->name
, options
);
6705 cliPrintError("input", "UNKNOWN COMMAND, TRY 'HELP'");
6710 memset(cliBuffer
, 0, sizeof(cliBuffer
));
6712 // 'exit' will reset this flag, so we don't need to print prompt again
6718 } else if (bufferIndex
< sizeof(cliBuffer
) && c
>= 32 && c
<= 126) {
6719 if (!bufferIndex
&& c
== ' ')
6720 return; // Ignore leading spaces
6721 cliBuffer
[bufferIndex
++] = c
;
6726 static void processCharacterInteractive(const char c
)
6728 if (c
== '\t' || c
== '?') {
6729 // do tab completion
6730 const clicmd_t
*cmd
, *pstart
= NULL
, *pend
= NULL
;
6731 uint32_t i
= bufferIndex
;
6732 for (cmd
= cmdTable
; cmd
< cmdTable
+ ARRAYLEN(cmdTable
); cmd
++) {
6733 if (bufferIndex
&& (strncasecmp(cliBuffer
, cmd
->name
, bufferIndex
) != 0)) {
6741 if (pstart
) { /* Buffer matches one or more commands */
6742 for (; ; bufferIndex
++) {
6743 if (pstart
->name
[bufferIndex
] != pend
->name
[bufferIndex
])
6745 if (!pstart
->name
[bufferIndex
] && bufferIndex
< sizeof(cliBuffer
) - 2) {
6746 /* Unambiguous -- append a space */
6747 cliBuffer
[bufferIndex
++] = ' ';
6748 cliBuffer
[bufferIndex
] = '\0';
6751 cliBuffer
[bufferIndex
] = pstart
->name
[bufferIndex
];
6754 if (!bufferIndex
|| pstart
!= pend
) {
6755 /* Print list of ambiguous matches */
6756 cliPrint("\r\n\033[K");
6757 for (cmd
= pstart
; cmd
<= pend
; cmd
++) {
6758 cliPrint(cmd
->name
);
6762 i
= 0; /* Redraw prompt */
6764 for (; i
< bufferIndex
; i
++)
6765 cliWrite(cliBuffer
[i
]);
6766 } else if (!bufferIndex
&& c
== 4) { // CTRL-D
6767 cliExit("", cliBuffer
);
6769 } else if (c
== 12) { // NewPage / CTRL-L
6771 cliPrint("\033[2J\033[1;1H");
6773 } else if (c
== 127) {
6776 cliBuffer
[--bufferIndex
] = 0;
6777 cliPrint("\010 \010");
6780 processCharacter(c
);
6784 void cliProcess(void)
6790 // Flush the buffer to get rid of any MSP data polls sent by configurator after CLI was invoked
6793 while (serialRxBytesWaiting(cliPort
)) {
6794 uint8_t c
= serialRead(cliPort
);
6796 processCharacterInteractive(c
);
6800 #if defined(USE_CUSTOM_DEFAULTS)
6801 static bool cliProcessCustomDefaults(bool quiet
)
6803 if (processingCustomDefaults
|| !hasCustomDefaults()) {
6807 bufWriter_t
*cliWriterTemp
= NULL
;
6809 #if !defined(DEBUG_CUSTOM_DEFAULTS)
6813 cliWriterTemp
= cliWriter
;
6817 cliErrorWriter
= NULL
;
6820 memcpy(cliBufferTemp
, cliBuffer
, sizeof(cliBuffer
));
6821 uint32_t bufferIndexTemp
= bufferIndex
;
6823 processingCustomDefaults
= true;
6825 char *customDefaultsPtr
= customDefaultsStart
;
6826 while (customDefaultsHasNext(customDefaultsPtr
)) {
6827 processCharacter(*customDefaultsPtr
++);
6830 // Process a newline at the very end so that the last command gets executed,
6831 // even when the file did not contain a trailing newline
6832 processCharacter('\r');
6834 processingCustomDefaults
= false;
6836 if (cliWriterTemp
) {
6837 cliWriter
= cliWriterTemp
;
6838 cliErrorWriter
= cliWriter
;
6841 memcpy(cliBuffer
, cliBufferTemp
, sizeof(cliBuffer
));
6842 bufferIndex
= bufferIndexTemp
;
6844 systemConfigMutable()->configurationState
= CONFIGURATION_STATE_DEFAULTS_CUSTOM
;
6850 void cliEnter(serialPort_t
*serialPort
)
6853 cliPort
= serialPort
;
6854 setPrintfSerialPort(cliPort
);
6855 bufWriterInit(&cliWriterDesc
, cliWriteBuffer
, sizeof(cliWriteBuffer
), (bufWrite_t
)serialWriteBufShim
, serialPort
);
6856 cliErrorWriter
= cliWriter
= &cliWriterDesc
;
6859 cliPrintLine("\r\nEntering CLI Mode, type 'exit' to return, or 'help'");
6861 cliPrintLine("\r\nCLI");
6863 setArmingDisabled(ARMING_DISABLED_CLI
);
6867 #ifdef USE_CLI_BATCH
6868 resetCommandBatch();