1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-14 03:50:02 +03:00

Experimental support for on-board custom defaults.

This commit is contained in:
mikeller 2019-06-25 02:13:09 +12:00
parent b310f9b348
commit 7518ec67f5
19 changed files with 390 additions and 174 deletions

View file

@ -30,6 +30,9 @@ EXST ?= no
# compile for target loaded into RAM
RAM_BASED ?= no
# reserve space for custom defaults
CUSTOM_DEFAULTS ?= no
# Debugger optons:
# empty - ordinary build with all optimizations enabled
# RELWITHDEBINFO - ordinary build with debug symbols and all optimizations enabled
@ -124,6 +127,7 @@ FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
LD_FLAGS :=
EXTRA_LD_FLAGS :=
#
# Default Tool options - can be overridden in {mcu}.mk files.
@ -185,6 +189,11 @@ else
.DEFAULT_GOAL := hex
endif
ifeq ($(CUSTOM_DEFAULTS),yes)
TARGET_FLAGS += -DUSE_CUSTOM_DEFAULTS
EXTRA_LD_FLAGS += -Wl,--defsym=USE_CUSTOM_DEFAULTS=1
endif
INCLUDE_DIRS := $(INCLUDE_DIRS) \
$(ROOT)/lib/main/MAVLink
@ -266,7 +275,8 @@ LD_FLAGS = -lm \
-Wl,--cref \
-Wl,--no-wchar-size-warning \
-Wl,--print-memory-usage \
-T$(LD_SCRIPT)
-T$(LD_SCRIPT) \
$(EXTRA_LD_FLAGS)
endif
###############################################################################

View file

@ -24,7 +24,8 @@ MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 992K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 976K : 992K
FLASH_CUSTOM_DEFAULTS (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x080FC000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
@ -38,4 +39,8 @@ REGION_ALIAS("STACKRAM", CCM)
REGION_ALIAS("FASTRAM", CCM)
REGION_ALIAS("VECTAB", RAM)
/* Base address where the defaults are stored. */
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
INCLUDE "stm32_flash_split.ld"

View file

@ -24,7 +24,8 @@ MEMORY
{
FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 464K : 480K
FLASH_CUSTOM_DEFAULTS (r): ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
SYSTEM_MEMORY (rx): ORIGIN = 0x1FFF0000, LENGTH = 29K
@ -36,4 +37,8 @@ REGION_ALIAS("STACKRAM", RAM)
REGION_ALIAS("FASTRAM", RAM)
REGION_ALIAS("VECTAB", RAM)
/* Base address where the defaults are stored. */
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
INCLUDE "stm32_flash_split.ld"

View file

@ -31,7 +31,8 @@ MEMORY
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 16K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = 480K
AXIM_FLASH1 (rx) : ORIGIN = 0x08008000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 464K : 480K
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x0807C000 : 0x08080000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 16K : 0K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K
@ -42,9 +43,14 @@ MEMORY
REGION_ALIAS("FLASH", AXIM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", AXIM_FLASH1)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
/* Base address where the defaults are stored. */
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -33,7 +33,8 @@ MEMORY
AXIM_FLASH (rx) : ORIGIN = 0x08000000, LENGTH = 32K
AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08008000, LENGTH = 32K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = 960K
AXIM_FLASH1 (rx) : ORIGIN = 0x08010000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 928K : 960K
AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = DEFINED(USE_CUSTOM_DEFAULTS) ? 0x080F8000 : 0x08100000, LENGTH = DEFINED(USE_CUSTOM_DEFAULTS) ? 32K : 0K
DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 240K
@ -44,9 +45,14 @@ MEMORY
REGION_ALIAS("FLASH", ITCM_FLASH)
REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG)
REGION_ALIAS("FLASH1", ITCM_FLASH1)
REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS)
REGION_ALIAS("STACKRAM", DTCM_RAM)
REGION_ALIAS("FASTRAM", DTCM_RAM)
REGION_ALIAS("RAM", SRAM1)
/* Base address where the defaults are stored. */
__custom_defaults_start = ORIGIN(FLASH_CUSTOM_DEFAULTS);
__custom_defaults_end = ORIGIN(FLASH_CUSTOM_DEFAULTS) + LENGTH(FLASH_CUSTOM_DEFAULTS);
INCLUDE "stm32_flash_f7_split.ld"

View file

@ -34,6 +34,13 @@ SECTIONS
. = ALIGN(4);
} >FLASH AT >AXIM_FLASH
/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
*(.custom_defaults_address)
} >FLASH1 AT >AXIM_FLASH1
/* The program code and other data goes into FLASH */
.text :
{

View file

@ -55,6 +55,13 @@ SECTIONS
. = ALIGN(4);
} >SYSTEM_MEMORY
/* Storage for the address for the configuration section so we can grab it out of the hex file */
.custom_defaults :
{
. = ALIGN(4);
*(.custom_defaults_address)
} >FLASH1
/* The program code and other data goes into FLASH */
.text :
{

View file

@ -30,7 +30,7 @@
// FIXME remove this for targets that don't need a CLI. Perhaps use a no-op macro when USE_CLI is not enabled
// signal that we're in cli mode
uint8_t cliMode = 0;
bool cliMode = false;
#ifdef USE_CLI
@ -172,14 +172,7 @@ uint8_t cliMode = 0;
#include "cli.h"
typedef struct serialPassthroughPort_e {
int id;
uint32_t baud;
unsigned mode;
serialPort_t *port;
} serialPassthroughPort_t;
static serialPort_t *cliPort;
static serialPort_t *cliPort = NULL;
#ifdef STM32F1
#define CLI_IN_BUFFER_SIZE 128
@ -189,7 +182,7 @@ static serialPort_t *cliPort;
#endif
#define CLI_OUT_BUFFER_SIZE 64
static bufWriter_t *cliWriter;
static bufWriter_t *cliWriter = NULL;
static uint8_t cliWriteBuffer[sizeof(*cliWriter) + CLI_OUT_BUFFER_SIZE];
static char cliBuffer[CLI_IN_BUFFER_SIZE];
@ -219,6 +212,14 @@ static bool signatureUpdated = false;
static const char* const emptyName = "-";
static const char* const emptyString = "";
#if defined(USE_CUSTOM_DEFAULTS)
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsStart = &__custom_defaults_start;
static char __attribute__ ((section(".custom_defaults_address"))) *customDefaultsEnd = &__custom_defaults_end;
static bool processingCustomDefaults = false;
static char cliBufferTemp[CLI_IN_BUFFER_SIZE];
#endif
#ifndef USE_QUAD_MIXER_ONLY
// sync this with mixerMode_e
static const char * const mixerNames[] = {
@ -288,6 +289,13 @@ typedef enum {
REBOOT_TARGET_BOOTLOADER_FLASH,
} rebootTarget_e;
typedef struct serialPassthroughPort_e {
int id;
uint32_t baud;
unsigned mode;
serialPort_t *port;
} serialPassthroughPort_t;
static void backupPgConfig(const pgRegistry_t *pg)
{
memcpy(pg->copy, pg->address, pg->size);
@ -300,6 +308,10 @@ static void restorePgConfig(const pgRegistry_t *pg)
static void backupConfigs(void)
{
if (configIsInCopy) {
return;
}
// make copies of configs to do differencing
PG_FOREACH(pg) {
backupPgConfig(pg);
@ -310,6 +322,10 @@ static void backupConfigs(void)
static void restoreConfigs(void)
{
if (!configIsInCopy) {
return;
}
PG_FOREACH(pg) {
restorePgConfig(pg);
}
@ -317,19 +333,54 @@ static void restoreConfigs(void)
configIsInCopy = false;
}
static void backupAndResetConfigs(void)
#if defined(USE_RESOURCE_MGMT) || defined(USE_TIMER_MGMT)
static bool isReadingConfigFromCopy()
{
return configIsInCopy;
}
#endif
static bool isWritingConfigToCopy()
{
return configIsInCopy
#if defined(USE_CUSTOM_DEFAULTS)
&& !processingCustomDefaults
#endif
;
}
static void backupAndResetConfigs(const bool useCustomDefaults)
{
backupConfigs();
// reset all configs to defaults to do differencing
resetConfigs();
#if defined(USE_CUSTOM_DEFAULTS)
if (useCustomDefaults) {
cliProcessCustomDefaults();
}
#else
UNUSED(useCustomDefaults);
#endif
}
static void cliWriterFlush()
{
if (cliWriter) {
bufWriterFlush(cliWriter);
}
}
static void cliPrint(const char *str)
{
if (cliWriter) {
while (*str) {
bufWriterAppend(cliWriter, *str++);
}
bufWriterFlush(cliWriter);
cliWriterFlush();
}
}
static void cliPrintLinefeed(void)
@ -360,8 +411,10 @@ static void cliPutp(void *p, char ch)
static void cliPrintfva(const char *format, va_list va)
{
if (cliWriter) {
tfp_format(cliWriter, cliPutp, format, va);
bufWriterFlush(cliWriter);
cliWriterFlush();
}
}
static bool cliDumpPrintLinef(dumpFlags_t dumpMask, bool equalsDefault, const char *format, ...)
@ -380,8 +433,10 @@ static bool cliDumpPrintLinef(dumpFlags_t dumpMask, bool equalsDefault, const ch
static void cliWrite(uint8_t ch)
{
if (cliWriter) {
bufWriterAppend(cliWriter, ch);
}
}
static bool cliDefaultPrintLinef(dumpFlags_t dumpMask, bool equalsDefault, const char *format, ...)
{
@ -647,22 +702,16 @@ static uint16_t getValueOffset(const clivalue_t *value)
return 0;
}
void *cliGetValuePointer(const clivalue_t *value)
STATIC_UNIT_TESTED void *cliGetValuePointer(const clivalue_t *value)
{
const pgRegistry_t* rec = pgFind(value->pgn);
if (configIsInCopy) {
if (isWritingConfigToCopy()) {
return CONST_CAST(void *, rec->copy + getValueOffset(value));
} else {
return CONST_CAST(void *, rec->address + getValueOffset(value));
}
}
const void *cliGetDefaultPointer(const clivalue_t *value)
{
const pgRegistry_t* rec = pgFind(value->pgn);
return rec->address + getValueOffset(value);
}
static const char *dumpPgValue(const clivalue_t *value, dumpFlags_t dumpMask, const char *headingStr)
{
const pgRegistry_t *pg = pgFind(value->pgn);
@ -698,7 +747,7 @@ static void dumpAllValues(uint16_t valueSection, dumpFlags_t dumpMask, const cha
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
const clivalue_t *value = &valueTable[i];
bufWriterFlush(cliWriter);
cliWriterFlush();
if ((value->type & VALUE_SECTION_MASK) == valueSection || ((valueSection == MASTER_VALUE) && (value->type & VALUE_SECTION_MASK) == HARDWARE_VALUE)) {
headingStr = dumpPgValue(value, dumpMask, headingStr);
}
@ -826,17 +875,26 @@ static void cliSetVar(const clivalue_t *var, const uint32_t value)
#if defined(USE_RESOURCE_MGMT) && !defined(MINIMAL_CLI)
static void cliRepeat(char ch, uint8_t len)
{
if (cliWriter) {
for (int i = 0; i < len; i++) {
bufWriterAppend(cliWriter, ch);
}
cliPrintLinefeed();
}
}
#endif
static void cliPrompt(void)
{
#if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS)
if (processingCustomDefaults) {
cliPrint("\r\nd: #");
} else
#endif
{
cliPrint("\r\n# ");
}
}
static void cliShowParseError(void)
{
@ -2352,7 +2410,7 @@ static void cliFlashErase(char *cmdline)
cliPrintLine("Erasing,");
#endif
bufWriterFlush(cliWriter);
cliWriterFlush();
flashfsEraseCompletely();
while (!flashfsIsReady()) {
@ -2363,7 +2421,7 @@ static void cliFlashErase(char *cmdline)
cliPrintLinefeed();
}
bufWriterFlush(cliWriter);
cliWriterFlush();
#endif
delay(100);
}
@ -3392,7 +3450,7 @@ static char *checkCommand(char *cmdline, const char *command)
static void cliRebootEx(rebootTarget_e rebootTarget)
{
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
cliWriterFlush();
waitForSerialPortToFinishTransmitting(cliPort);
motorShutdown();
@ -3451,16 +3509,14 @@ static void cliExit(char *cmdline)
UNUSED(cmdline);
cliPrintHashLine("leaving CLI mode, unsaved changes lost");
bufWriterFlush(cliWriter);
cliWriterFlush();
*cliBuffer = '\0';
bufferIndex = 0;
cliMode = 0;
cliMode = false;
// incase a motor was left running during motortest, clear it here
mixerResetDisarmedMotors();
cliReboot();
cliWriter = NULL;
}
#ifdef USE_GPS
@ -4074,6 +4130,12 @@ static void cliSave(char *cmdline)
{
UNUSED(cmdline);
#if defined(USE_CUSTOM_DEFAULTS)
if (processingCustomDefaults) {
return;
}
#endif
#ifdef USE_CLI_BATCH
if (commandBatchActive && commandBatchError) {
cliPrintCommandBatchWarning("PLEASE FIX ERRORS THEN 'SAVE'");
@ -4104,15 +4166,46 @@ static void cliSave(char *cmdline)
cliReboot();
}
#if defined(USE_CUSTOM_DEFAULTS)
static bool isDefaults(char *ptr)
{
return strncmp(ptr, "# Betaflight", 12) == 0;
}
#endif
static void cliDefaults(char *cmdline)
{
bool saveConfigs;
bool saveConfigs = true;
#if defined(USE_CUSTOM_DEFAULTS)
bool useCustomDefaults = true;
#endif
if (isEmpty(cmdline)) {
saveConfigs = true;
} else if (strncasecmp(cmdline, "nosave", 6) == 0) {
saveConfigs = false;
#if defined(USE_CUSTOM_DEFAULTS)
} else if (strncasecmp(cmdline, "bare", 4) == 0) {
useCustomDefaults = false;
} else if (strncasecmp(cmdline, "show", 4) == 0) {
char *ptr = customDefaultsStart;
if (isDefaults(ptr)) {
while (*ptr && ptr < customDefaultsEnd) {
if (*ptr != '\n') {
cliPrintf("%c", *ptr++);
} else {
cliPrintLinefeed();
ptr++;
}
}
} else {
cliPrintError("NO DEFAULTS FOUND");
}
return;
#endif
} else {
cliPrintError("INVALID OPTION");
return;
}
@ -4128,6 +4221,12 @@ static void cliDefaults(char *cmdline)
commandBatchError = false;
#endif
#if defined(USE_CUSTOM_DEFAULTS)
if (useCustomDefaults) {
cliProcessCustomDefaults();
}
#endif
if (saveConfigs) {
cliSave(NULL);
}
@ -4156,7 +4255,7 @@ STATIC_UNIT_TESTED void cliGet(char *cmdline)
pidProfileIndexToUse = getCurrentPidProfileIndex();
rateProfileIndexToUse = getCurrentControlRateProfileIndex();
backupAndResetConfigs();
backupAndResetConfigs(true);
for (uint32_t i = 0; i < valueTableEntryCount; i++) {
if (strcasestr(valueTable[i].name, cmdline)) {
@ -4192,12 +4291,10 @@ STATIC_UNIT_TESTED void cliGet(char *cmdline)
pidProfileIndexToUse = CURRENT_PROFILE_INDEX;
rateProfileIndexToUse = CURRENT_PROFILE_INDEX;
if (matchedCommands) {
return;
}
if (!matchedCommands) {
cliPrintErrorLinef("INVALID NAME");
}
}
static uint8_t getWordLength(char *bufBegin, char *bufEnd)
{
@ -4813,7 +4910,7 @@ static void printResource(dumpFlags_t dumpMask, const char *headingStr)
const pgRegistry_t* pg = pgFind(resourceTable[i].pgn);
const void *currentConfig;
const void *defaultConfig;
if (configIsInCopy) {
if (isReadingConfigFromCopy()) {
currentConfig = pg->copy;
defaultConfig = pg->address;
} else {
@ -5028,7 +5125,7 @@ static const char *printPeripheralDmaopt(dmaoptEntry_t *entry, int index, dumpFl
const void *currentConfig;
const void *defaultConfig;
if (configIsInCopy) {
if (isReadingConfigFromCopy()) {
currentConfig = pg->copy;
defaultConfig = pg->address;
} else {
@ -5141,7 +5238,7 @@ static void printDmaopt(dumpFlags_t dumpMask, const char *headingStr)
const timerIOConfig_t *currentConfig;
const timerIOConfig_t *defaultConfig;
if (configIsInCopy) {
if (isReadingConfigFromCopy()) {
currentConfig = (timerIOConfig_t *)pg->copy;
defaultConfig = (timerIOConfig_t *)pg->address;
} else {
@ -5218,7 +5315,7 @@ static void cliDmaopt(char *cmdline)
const pgRegistry_t* pg = pgFind(entry->pgn);
const void *currentConfig;
if (configIsInCopy) {
if (isWritingConfigToCopy()) {
currentConfig = pg->copy;
} else {
currentConfig = pg->address;
@ -5375,7 +5472,7 @@ static void printTimer(dumpFlags_t dumpMask, const char *headingStr)
const timerIOConfig_t *defaultConfig;
headingStr = cliPrintSectionHeading(dumpMask, false, headingStr);
if (configIsInCopy) {
if (isReadingConfigFromCopy()) {
currentConfig = (timerIOConfig_t *)pg->copy;
defaultConfig = (timerIOConfig_t *)pg->address;
} else {
@ -5784,7 +5881,7 @@ static void printConfig(char *cmdline, bool doDiff)
dumpMask = dumpMask | BARE; // show the diff / dump without extra commands and board specific data
}
backupAndResetConfigs();
backupAndResetConfigs((dumpMask & BARE) == 0);
#ifdef USE_CLI_BATCH
bool batchModeEnabled = false;
@ -5989,7 +6086,7 @@ static void cliMsc(char *cmdline)
#endif
cliPrintHashLine("Restarting in mass storage mode");
cliPrint("\r\nRebooting");
bufWriterFlush(cliWriter);
cliWriterFlush();
waitForSerialPortToFinishTransmitting(cliPort);
motorShutdown();
@ -6057,7 +6154,11 @@ const clicmd_t cmdTable[] = {
#ifdef USE_LED_STRIP_STATUS_MODE
CLI_COMMAND_DEF("color", "configure colors", NULL, cliColor),
#endif
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave]", cliDefaults),
#if defined(USE_CUSTOM_DEFAULTS)
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave|bare|show]", cliDefaults),
#else
CLI_COMMAND_DEF("defaults", "reset to defaults and reboot", "[nosave|show]", cliDefaults),
#endif
CLI_COMMAND_DEF("diff", "list configuration changes from default", "[master|profile|rates|hardware|all] {defaults|bare}", cliDiff),
#ifdef USE_RESOURCE_MGMT
@ -6202,64 +6303,18 @@ static void cliHelp(char *cmdline)
}
}
void cliProcess(void)
static void processCommandCharacter(const char c)
{
if (!cliWriter) {
return;
}
// Be a little bit tricky. Flush the last inputs buffer, if any.
bufWriterFlush(cliWriter);
while (serialRxBytesWaiting(cliPort)) {
uint8_t c = serialRead(cliPort);
if (c == '\t' || c == '?') {
// do tab completion
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
uint32_t i = bufferIndex;
for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0))
continue;
if (!pstart)
pstart = cmd;
pend = cmd;
}
if (pstart) { /* Buffer matches one or more commands */
for (; ; bufferIndex++) {
if (pstart->name[bufferIndex] != pend->name[bufferIndex])
break;
if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
/* Unambiguous -- append a space */
cliBuffer[bufferIndex++] = ' ';
cliBuffer[bufferIndex] = '\0';
break;
}
cliBuffer[bufferIndex] = pstart->name[bufferIndex];
}
}
if (!bufferIndex || pstart != pend) {
/* Print list of ambiguous matches */
cliPrint("\r\033[K");
for (cmd = pstart; cmd <= pend; cmd++) {
cliPrint(cmd->name);
cliWrite('\t');
}
cliPrompt();
i = 0; /* Redraw prompt */
}
for (; i < bufferIndex; i++)
cliWrite(cliBuffer[i]);
} else if (!bufferIndex && c == 4) { // CTRL-D
cliExit(cliBuffer);
return;
} else if (c == 12) { // NewPage / CTRL-L
// clear screen
cliPrint("\033[2J\033[1;1H");
cliPrompt();
} else if (bufferIndex && (c == '\n' || c == '\r')) {
if (bufferIndex && (c == '\n' || c == '\r')) {
// enter pressed
cliPrintLinefeed();
#if defined(USE_CUSTOM_DEFAULTS) && defined(DEBUG_CUSTOM_DEFAULTS)
if (processingCustomDefaults) {
cliPrint("d: ");
}
#endif
// Strip comment starting with # from line
char *p = cliBuffer;
p = strchr(p, '#');
@ -6294,9 +6349,65 @@ void cliProcess(void)
memset(cliBuffer, 0, sizeof(cliBuffer));
// 'exit' will reset this flag, so we don't need to print prompt again
if (!cliMode)
if (!cliMode) {
return;
}
cliPrompt();
} else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
if (!bufferIndex && c == ' ')
return; // Ignore leading spaces
cliBuffer[bufferIndex++] = c;
cliWrite(c);
}
}
static void processCharacter(const char c)
{
if (c == '\t' || c == '?') {
// do tab completion
const clicmd_t *cmd, *pstart = NULL, *pend = NULL;
uint32_t i = bufferIndex;
for (cmd = cmdTable; cmd < cmdTable + ARRAYLEN(cmdTable); cmd++) {
if (bufferIndex && (strncasecmp(cliBuffer, cmd->name, bufferIndex) != 0)) {
continue;
}
if (!pstart) {
pstart = cmd;
}
pend = cmd;
}
if (pstart) { /* Buffer matches one or more commands */
for (; ; bufferIndex++) {
if (pstart->name[bufferIndex] != pend->name[bufferIndex])
break;
if (!pstart->name[bufferIndex] && bufferIndex < sizeof(cliBuffer) - 2) {
/* Unambiguous -- append a space */
cliBuffer[bufferIndex++] = ' ';
cliBuffer[bufferIndex] = '\0';
break;
}
cliBuffer[bufferIndex] = pstart->name[bufferIndex];
}
}
if (!bufferIndex || pstart != pend) {
/* Print list of ambiguous matches */
cliPrint("\r\033[K");
for (cmd = pstart; cmd <= pend; cmd++) {
cliPrint(cmd->name);
cliWrite('\t');
}
cliPrompt();
i = 0; /* Redraw prompt */
}
for (; i < bufferIndex; i++)
cliWrite(cliBuffer[i]);
} else if (!bufferIndex && c == 4) { // CTRL-D
cliExit(cliBuffer);
return;
} else if (c == 12) { // NewPage / CTRL-L
// clear screen
cliPrint("\033[2J\033[1;1H");
cliPrompt();
} else if (c == 127) {
// backspace
@ -6304,18 +6415,64 @@ void cliProcess(void)
cliBuffer[--bufferIndex] = 0;
cliPrint("\010 \010");
}
} else if (bufferIndex < sizeof(cliBuffer) && c >= 32 && c <= 126) {
if (!bufferIndex && c == ' ')
continue; // Ignore leading spaces
cliBuffer[bufferIndex++] = c;
cliWrite(c);
}
} else {
processCommandCharacter(c);
}
}
void cliProcess(void)
{
if (!cliWriter) {
return;
}
// Flush the buffer to get rid of any MSP data polls sent by configurator after CLI was invoked
cliWriterFlush();
while (serialRxBytesWaiting(cliPort)) {
uint8_t c = serialRead(cliPort);
processCharacter(c);
}
}
#if defined(USE_CUSTOM_DEFAULTS)
void cliProcessCustomDefaults(void)
{
if (processingCustomDefaults) {
return;
}
char *ptr = customDefaultsStart;
if (isDefaults(ptr)) {
#if !defined(DEBUG_CUSTOM_DEFAULTS)
bufWriter_t *cliWriterTemp = cliWriter;
cliWriter = NULL;
#endif
memcpy(cliBufferTemp, cliBuffer, sizeof(cliBuffer));
uint32_t bufferIndexTemp = bufferIndex;
bufferIndex = 0;
processingCustomDefaults = true;
while (*ptr && ptr != 0xFF && ptr < customDefaultsEnd) {
processCommandCharacter(*ptr++);
}
processingCustomDefaults = false;
#if !defined(DEBUG_CUSTOM_DEFAULTS)
cliWriter = cliWriterTemp;
#endif
memcpy(cliBuffer, cliBufferTemp, sizeof(cliBuffer));
bufferIndex = bufferIndexTemp;
} else {
cliPrintError("NO DEFAULTS FOUND");
}
}
#endif
void cliEnter(serialPort_t *serialPort)
{
cliMode = 1;
cliMode = true;
cliPort = serialPort;
setPrintfSerialPort(cliPort);
cliWriter = bufWriterInit(cliWriteBuffer, sizeof(cliWriteBuffer), (bufWrite_t)serialWriteBufShim, serialPort);
@ -6335,9 +6492,4 @@ void cliEnter(serialPort_t *serialPort)
resetCommandBatch();
#endif
}
void cliInit(const serialConfig_t *serialConfig)
{
UNUSED(serialConfig);
}
#endif // USE_CLI

View file

@ -20,14 +20,11 @@
#pragma once
extern uint8_t cliMode;
#include <stdbool.h>
struct clivalue_s;
void *cliGetValuePointer(const struct clivalue_s *value);
const void *cliGetDefaultPointer(const struct clivalue_s *value);
extern bool cliMode;
struct serialConfig_s;
void cliInit(const struct serialConfig_s *serialConfig);
void cliProcess(void);
void cliProcessCustomDefaults(void);
struct serialPort_s;
void cliEnter(struct serialPort_s *serialPort);

View file

@ -30,8 +30,6 @@
#include "build/build_config.h"
#include "build/debug.h"
#include "cli/cli.h"
#include "cms/cms.h"
#include "cms/cms_types.h"
@ -725,10 +723,6 @@ void init(void)
mspInit();
mspSerialInit();
#ifdef USE_CLI
cliInit(serialConfig());
#endif
failsafeInit();
rxInit();

View file

@ -1,6 +1,9 @@
F405_TARGETS += $(TARGET)
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
CUSTOM_DEFAULTS = yes
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \

View file

@ -2,6 +2,8 @@ F411_TARGETS += $(TARGET)
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
CUSTOM_DEFAULTS = yes
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \

View file

@ -1,4 +1,5 @@
F411_TARGETS += $(TARGET)
FEATURES += VCP SDCARD_SPI ONBOARDFLASH
TARGET_SRC = \

View file

@ -1,4 +1,5 @@
F405_TARGETS += $(TARGET)
FEATURES += VCP SDCARD_SPI MSC
TARGET_SRC = \

View file

@ -1,6 +1,9 @@
F7X5XG_TARGETS += $(TARGET)
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
CUSTOM_DEFAULTS = yes
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \

View file

@ -1,6 +1,9 @@
F7X2RE_TARGETS += $(TARGET)
FEATURES += SDCARD_SPI VCP ONBOARDFLASH
CUSTOM_DEFAULTS = yes
TARGET_SRC = \
$(addprefix drivers/accgyro/,$(notdir $(wildcard $(SRC_DIR)/drivers/accgyro/*.c))) \
$(addprefix drivers/barometer/,$(notdir $(wildcard $(SRC_DIR)/drivers/barometer/*.c))) \

View file

@ -359,6 +359,8 @@ extern uint8_t eepromData[EEPROM_SIZE];
#endif
extern uint8_t __config_start; // configured via linker script when building binaries.
extern uint8_t __config_end;
extern char __custom_defaults_start;
extern char __custom_defaults_end;
#endif
#if defined(USE_EXST) && !defined(RAMBASED)

View file

@ -56,6 +56,7 @@ extern "C" {
void cliSet(char *cmdline);
void cliGet(char *cmdline);
int cliGetSettingIndex(char *name, uint8_t length);
void *cliGetValuePointer(const clivalue_t *value);
const clivalue_t valueTable[] = {
{ "array_unit_test", VAR_INT8 | MODE_ARRAY | MASTER_VALUE, .config.array.length = 3, PG_RESERVED_FOR_TESTING_1, 0 },

11
src/utils/make_config_hex.sh Executable file
View file

@ -0,0 +1,11 @@
#!/bin/bash
INPUT_FILE=$1
DESTINATION_DIR=$2
TARGET_ADDRESS=0x080FC000
srec_cat ${INPUT_FILE} -binary -offset ${TARGET_ADDRESS} \
-generate '(' -maximum-address ${INPUT_FILE} -binary -maximum-address ${INPUT_FILE} -binary -offset 1 ')' \
-constant 0x00 -offset ${TARGET_ADDRESS} \
-output ${DESTINATION_DIR}/$(basename ${INPUT_FILE}).hex -intel