mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Merge branch 'master' into 8107-osd-profile-names
This commit is contained in:
commit
9ae53d94d0
100 changed files with 3297 additions and 342 deletions
13
.github/no-response.yml
vendored
Normal file
13
.github/no-response.yml
vendored
Normal file
|
@ -0,0 +1,13 @@
|
||||||
|
# Configuration for probot-no-response - https://github.com/probot/no-response
|
||||||
|
|
||||||
|
# Number of days of inactivity before an Issue is closed for lack of response
|
||||||
|
daysUntilClose: 1
|
||||||
|
# Label requiring a response
|
||||||
|
responseRequiredLabel: Missing Information
|
||||||
|
# Comment to post when closing an Issue for lack of response. Set to `false` to disable
|
||||||
|
closeComment: >
|
||||||
|
This issue has been automatically closed because there has been no response
|
||||||
|
to our request for more information from the original author. With only the
|
||||||
|
information that is currently in the issue, we don't have enough information
|
||||||
|
to take action. Please reach out if you have or find the answers we need so
|
||||||
|
that we can investigate further.
|
30
Makefile
30
Makefile
|
@ -16,7 +16,7 @@
|
||||||
#
|
#
|
||||||
|
|
||||||
# The target to build, see VALID_TARGETS below
|
# The target to build, see VALID_TARGETS below
|
||||||
TARGET ?= BETAFLIGHTF3
|
TARGET ?= OMNIBUSF4
|
||||||
|
|
||||||
# Compile-time options
|
# Compile-time options
|
||||||
OPTIONS ?=
|
OPTIONS ?=
|
||||||
|
@ -35,7 +35,7 @@ DEBUG ?=
|
||||||
DEBUG_HARDFAULTS ?=
|
DEBUG_HARDFAULTS ?=
|
||||||
|
|
||||||
# Serial port/Device for flashing
|
# Serial port/Device for flashing
|
||||||
SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
|
SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyACM*) $(firstword $(wildcard /dev/ttyUSB*) no-port-found))
|
||||||
|
|
||||||
# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
|
# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override.
|
||||||
FLASH_SIZE ?=
|
FLASH_SIZE ?=
|
||||||
|
@ -427,14 +427,32 @@ clean_all: $(CLEAN_TARGETS)
|
||||||
## all_clean : clean all valid targets (alias for above)
|
## all_clean : clean all valid targets (alias for above)
|
||||||
all_clean: $(TARGETS_CLEAN)
|
all_clean: $(TARGETS_CLEAN)
|
||||||
|
|
||||||
|
FLASH_TARGETS = $(addprefix flash_,$(VALID_TARGETS) )
|
||||||
|
|
||||||
flash_$(TARGET): $(TARGET_HEX)
|
## flash_<TARGET> : build and flash a target
|
||||||
|
$(FLASH_TARGETS):
|
||||||
|
ifneq (,$(findstring /dev/ttyUSB,$(SERIAL_DEVICE)))
|
||||||
|
$(V0) $(MAKE) -j hex TARGET=$(subst flash_,,$@)
|
||||||
|
$(V0) $(MAKE) tty_flash TARGET=$(subst flash_,,$@)
|
||||||
|
else
|
||||||
|
$(V0) $(MAKE) -j binary TARGET=$(subst flash_,,$@)
|
||||||
|
$(V0) $(MAKE) dfu_flash TARGET=$(subst flash_,,$@)
|
||||||
|
endif
|
||||||
|
|
||||||
|
## tty_flash : flash firmware (.hex) onto flight controller via a serial port
|
||||||
|
tty_flash:
|
||||||
$(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
|
$(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
|
||||||
$(V0) echo -n 'R' >$(SERIAL_DEVICE)
|
$(V0) echo -n 'R' > $(SERIAL_DEVICE)
|
||||||
$(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
|
$(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE)
|
||||||
|
|
||||||
## flash : flash firmware (.hex) onto flight controller
|
## dfu_flash : flash firmware (.bin) onto flight controller via a DFU mode
|
||||||
flash: flash_$(TARGET)
|
dfu_flash:
|
||||||
|
ifneq (no-port-found,$(SERIAL_DEVICE))
|
||||||
|
# potentially this is because the MCU already is in DFU mode, try anyway
|
||||||
|
$(V0) echo -n 'R' > $(SERIAL_DEVICE)
|
||||||
|
$(V0) sleep 1
|
||||||
|
endif
|
||||||
|
$(V0) dfu-util -a 0 -D $(TARGET_BIN) -s 0x08000000:leave
|
||||||
|
|
||||||
st-flash_$(TARGET): $(TARGET_BIN)
|
st-flash_$(TARGET): $(TARGET_BIN)
|
||||||
$(V0) st-flash --reset write $< 0x08000000
|
$(V0) st-flash --reset write $< 0x08000000
|
||||||
|
|
|
@ -364,6 +364,7 @@ ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
|
||||||
SRC += \
|
SRC += \
|
||||||
drivers/flash.c \
|
drivers/flash.c \
|
||||||
drivers/flash_m25p16.c \
|
drivers/flash_m25p16.c \
|
||||||
|
drivers/flash_w25n01g.c \
|
||||||
drivers/flash_w25m.c \
|
drivers/flash_w25m.c \
|
||||||
io/flashfs.c \
|
io/flashfs.c \
|
||||||
pg/flash.c \
|
pg/flash.c \
|
||||||
|
|
|
@ -1225,6 +1225,10 @@ static bool blackboxWriteSysinfo(void)
|
||||||
|
|
||||||
char buf[FORMATTED_DATE_TIME_BUFSIZE];
|
char buf[FORMATTED_DATE_TIME_BUFSIZE];
|
||||||
|
|
||||||
|
#ifdef USE_RC_SMOOTHING_FILTER
|
||||||
|
rcSmoothingFilter_t *rcSmoothingData = getRcSmoothingData();
|
||||||
|
#endif
|
||||||
|
|
||||||
const controlRateConfig_t *currentControlRateProfile = controlRateProfiles(systemConfig()->activeRateProfile);
|
const controlRateConfig_t *currentControlRateProfile = controlRateProfiles(systemConfig()->activeRateProfile);
|
||||||
switch (xmitState.headerIndex) {
|
switch (xmitState.headerIndex) {
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware type", "%s", "Cleanflight");
|
BLACKBOX_PRINT_HEADER_LINE("Firmware type", "%s", "Cleanflight");
|
||||||
|
@ -1377,16 +1381,16 @@ static bool blackboxWriteSysinfo(void)
|
||||||
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
BLACKBOX_PRINT_HEADER_LINE("features", "%d", featureConfig()->enabledFeatures);
|
||||||
|
|
||||||
#ifdef USE_RC_SMOOTHING_FILTER
|
#ifdef USE_RC_SMOOTHING_FILTER
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_type", "%d", rxConfig()->rc_smoothing_type);
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_type", "%d", rcSmoothingData->inputFilterType);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_debug_axis", "%d", rxConfig()->rc_smoothing_debug_axis);
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_debug_axis", "%d", rcSmoothingData->debugAxis);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_cutoffs", "%d, %d", rxConfig()->rc_smoothing_input_cutoff,
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_cutoffs", "%d, %d", rcSmoothingData->inputCutoffSetting,
|
||||||
rxConfig()->rc_smoothing_derivative_cutoff);
|
rcSmoothingData->derivativeCutoffSetting);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_auto_factor", "%d", rxConfig()->rc_smoothing_auto_factor);
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_auto_factor", "%d", rcSmoothingData->autoSmoothnessFactor);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_filter_type", "%d, %d", rxConfig()->rc_smoothing_input_type,
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_filter_type", "%d, %d", rcSmoothingData->inputFilterType,
|
||||||
rxConfig()->rc_smoothing_derivative_type);
|
rcSmoothingData->derivativeFilterType);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_active_cutoffs", "%d, %d", rcSmoothingGetValue(RC_SMOOTHING_VALUE_INPUT_ACTIVE),
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_active_cutoffs", "%d, %d", rcSmoothingData->inputCutoffFrequency,
|
||||||
rcSmoothingGetValue(RC_SMOOTHING_VALUE_DERIVATIVE_ACTIVE));
|
rcSmoothingData->derivativeCutoffFrequency);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_rx_average", "%d", rcSmoothingGetValue(RC_SMOOTHING_VALUE_AVERAGE_FRAME));
|
BLACKBOX_PRINT_HEADER_LINE("rc_smoothing_rx_average", "%d", rcSmoothingData->averageFrameTimeUs);
|
||||||
#endif // USE_RC_SMOOTHING_FILTER
|
#endif // USE_RC_SMOOTHING_FILTER
|
||||||
|
|
||||||
|
|
||||||
|
|
|
@ -508,11 +508,11 @@ static void printValuePointer(const clivalue_t *var, const void *valuePointer, b
|
||||||
switch (var->type & VALUE_MODE_MASK) {
|
switch (var->type & VALUE_MODE_MASK) {
|
||||||
case MODE_DIRECT:
|
case MODE_DIRECT:
|
||||||
if ((var->type & VALUE_TYPE_MASK) == VAR_UINT32) {
|
if ((var->type & VALUE_TYPE_MASK) == VAR_UINT32) {
|
||||||
cliPrintf("%d", value);
|
cliPrintf("%u", (uint32_t)value);
|
||||||
if ((uint32_t) value > var->config.u32Max) {
|
if ((uint32_t)value > var->config.u32Max) {
|
||||||
valueIsCorrupted = true;
|
valueIsCorrupted = true;
|
||||||
} else if (full) {
|
} else if (full) {
|
||||||
cliPrintf(" 0 %d", var->config.u32Max);
|
cliPrintf(" 0 %u", var->config.u32Max);
|
||||||
}
|
}
|
||||||
} else {
|
} else {
|
||||||
int min;
|
int min;
|
||||||
|
@ -697,7 +697,7 @@ static void cliPrintVarRange(const clivalue_t *var)
|
||||||
case (MODE_DIRECT): {
|
case (MODE_DIRECT): {
|
||||||
switch (var->type & VALUE_TYPE_MASK) {
|
switch (var->type & VALUE_TYPE_MASK) {
|
||||||
case VAR_UINT32:
|
case VAR_UINT32:
|
||||||
cliPrintLinef("Allowed range: %d - %d", 0, var->config.u32Max);
|
cliPrintLinef("Allowed range: 0 - %u", var->config.u32Max);
|
||||||
|
|
||||||
break;
|
break;
|
||||||
case VAR_UINT8:
|
case VAR_UINT8:
|
||||||
|
@ -2209,16 +2209,36 @@ static void cliSdInfo(char *cmdline)
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASH_CHIP
|
||||||
|
|
||||||
static void cliFlashInfo(char *cmdline)
|
static void cliFlashInfo(char *cmdline)
|
||||||
{
|
{
|
||||||
const flashGeometry_t *layout = flashfsGetGeometry();
|
const flashGeometry_t *layout = flashGetGeometry();
|
||||||
|
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
|
||||||
cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u, usedSize=%u",
|
cliPrintLinef("Flash sectors=%u, sectorSize=%u, pagesPerSector=%u, pageSize=%u, totalSize=%u",
|
||||||
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize, flashfsGetOffset());
|
layout->sectors, layout->sectorSize, layout->pagesPerSector, layout->pageSize, layout->totalSize);
|
||||||
|
|
||||||
|
for (uint8_t index = 0; index < FLASH_MAX_PARTITIONS; index++) {
|
||||||
|
const flashPartition_t *partition;
|
||||||
|
if (index == 0) {
|
||||||
|
cliPrintLine("Paritions:");
|
||||||
|
}
|
||||||
|
partition = flashPartitionFindByIndex(index);
|
||||||
|
if (!partition) {
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
cliPrintLinef(" %d: %s %u %u", index, flashPartitionGetTypeName(partition->type), partition->startSector, partition->endSector);
|
||||||
|
}
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
|
||||||
|
|
||||||
|
cliPrintLinef("FlashFS size=%u, usedSize=%u",
|
||||||
|
FLASH_PARTITION_SECTOR_COUNT(flashPartition) * layout->sectorSize,
|
||||||
|
flashfsGetOffset()
|
||||||
|
);
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -2239,7 +2259,6 @@ static void cliFlashErase(char *cmdline)
|
||||||
|
|
||||||
bufWriterFlush(cliWriter);
|
bufWriterFlush(cliWriter);
|
||||||
flashfsEraseCompletely();
|
flashfsEraseCompletely();
|
||||||
flashfsInit();
|
|
||||||
|
|
||||||
while (!flashfsIsReady()) {
|
while (!flashfsIsReady()) {
|
||||||
#ifndef MINIMAL_CLI
|
#ifndef MINIMAL_CLI
|
||||||
|
@ -2260,6 +2279,18 @@ static void cliFlashErase(char *cmdline)
|
||||||
|
|
||||||
#ifdef USE_FLASH_TOOLS
|
#ifdef USE_FLASH_TOOLS
|
||||||
|
|
||||||
|
static void cliFlashVerify(char *cmdline)
|
||||||
|
{
|
||||||
|
UNUSED(cmdline);
|
||||||
|
|
||||||
|
cliPrintLine("Verifying");
|
||||||
|
if (flashfsVerifyEntireFlash()) {
|
||||||
|
cliPrintLine("Success");
|
||||||
|
} else {
|
||||||
|
cliPrintLine("Failed");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void cliFlashWrite(char *cmdline)
|
static void cliFlashWrite(char *cmdline)
|
||||||
{
|
{
|
||||||
const uint32_t address = atoi(cmdline);
|
const uint32_t address = atoi(cmdline);
|
||||||
|
@ -4066,7 +4097,7 @@ STATIC_UNIT_TESTED void cliSet(char *cmdline)
|
||||||
switch (val->type & VALUE_MODE_MASK) {
|
switch (val->type & VALUE_MODE_MASK) {
|
||||||
case MODE_DIRECT: {
|
case MODE_DIRECT: {
|
||||||
if ((val->type & VALUE_TYPE_MASK) == VAR_UINT32) {
|
if ((val->type & VALUE_TYPE_MASK) == VAR_UINT32) {
|
||||||
uint32_t value = strtol(eqptr, NULL, 10);
|
uint32_t value = strtoul(eqptr, NULL, 10);
|
||||||
|
|
||||||
if (value <= val->config.u32Max) {
|
if (value <= val->config.u32Max) {
|
||||||
cliSetVar(val, value);
|
cliSetVar(val, value);
|
||||||
|
@ -4422,10 +4453,11 @@ static void cliVersion(char *cmdline)
|
||||||
static void cliRcSmoothing(char *cmdline)
|
static void cliRcSmoothing(char *cmdline)
|
||||||
{
|
{
|
||||||
UNUSED(cmdline);
|
UNUSED(cmdline);
|
||||||
|
rcSmoothingFilter_t *rcSmoothingData = getRcSmoothingData();
|
||||||
cliPrint("# RC Smoothing Type: ");
|
cliPrint("# RC Smoothing Type: ");
|
||||||
if (rxConfig()->rc_smoothing_type == RC_SMOOTHING_TYPE_FILTER) {
|
if (rxConfig()->rc_smoothing_type == RC_SMOOTHING_TYPE_FILTER) {
|
||||||
cliPrintLine("FILTER");
|
cliPrintLine("FILTER");
|
||||||
uint16_t avgRxFrameMs = rcSmoothingGetValue(RC_SMOOTHING_VALUE_AVERAGE_FRAME);
|
uint16_t avgRxFrameMs = rcSmoothingData->averageFrameTimeUs;
|
||||||
if (rcSmoothingAutoCalculate()) {
|
if (rcSmoothingAutoCalculate()) {
|
||||||
cliPrint("# Detected RX frame rate: ");
|
cliPrint("# Detected RX frame rate: ");
|
||||||
if (avgRxFrameMs == 0) {
|
if (avgRxFrameMs == 0) {
|
||||||
|
@ -4435,20 +4467,20 @@ static void cliRcSmoothing(char *cmdline)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
cliPrint("# Input filter type: ");
|
cliPrint("# Input filter type: ");
|
||||||
cliPrintLinef(lookupTables[TABLE_RC_SMOOTHING_INPUT_TYPE].values[rxConfig()->rc_smoothing_input_type]);
|
cliPrintLinef(lookupTables[TABLE_RC_SMOOTHING_INPUT_TYPE].values[rcSmoothingData->inputFilterType]);
|
||||||
cliPrintf("# Active input cutoff: %dhz ", rcSmoothingGetValue(RC_SMOOTHING_VALUE_INPUT_ACTIVE));
|
cliPrintf("# Active input cutoff: %dhz ", rcSmoothingData->inputCutoffFrequency);
|
||||||
if (rxConfig()->rc_smoothing_input_cutoff == 0) {
|
if (rcSmoothingData->inputCutoffSetting == 0) {
|
||||||
cliPrintLine("(auto)");
|
cliPrintLine("(auto)");
|
||||||
} else {
|
} else {
|
||||||
cliPrintLine("(manual)");
|
cliPrintLine("(manual)");
|
||||||
}
|
}
|
||||||
cliPrint("# Derivative filter type: ");
|
cliPrint("# Derivative filter type: ");
|
||||||
cliPrintLinef(lookupTables[TABLE_RC_SMOOTHING_DERIVATIVE_TYPE].values[rxConfig()->rc_smoothing_derivative_type]);
|
cliPrintLinef(lookupTables[TABLE_RC_SMOOTHING_DERIVATIVE_TYPE].values[rcSmoothingData->derivativeFilterType]);
|
||||||
cliPrintf("# Active derivative cutoff: %dhz (", rcSmoothingGetValue(RC_SMOOTHING_VALUE_DERIVATIVE_ACTIVE));
|
cliPrintf("# Active derivative cutoff: %dhz (", rcSmoothingData->derivativeCutoffFrequency);
|
||||||
if (rxConfig()->rc_smoothing_derivative_type == RC_SMOOTHING_DERIVATIVE_OFF) {
|
if (rcSmoothingData->derivativeFilterType == RC_SMOOTHING_DERIVATIVE_OFF) {
|
||||||
cliPrintLine("off)");
|
cliPrintLine("off)");
|
||||||
} else {
|
} else {
|
||||||
if (rxConfig()->rc_smoothing_derivative_cutoff == 0) {
|
if (rcSmoothingData->derivativeCutoffSetting == 0) {
|
||||||
cliPrintLine("auto)");
|
cliPrintLine("auto)");
|
||||||
} else {
|
} else {
|
||||||
cliPrintLine("manual)");
|
cliPrintLine("manual)");
|
||||||
|
@ -4876,7 +4908,7 @@ static void printTimerDmaoptDetails(const ioTag_t ioTag, const timerHardware_t *
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
static const char *printTimerDmaopt(const timerIOConfig_t *currentConfig, const timerIOConfig_t *defaultConfig, unsigned index, dumpFlags_t dumpMask, bool defaultIsUsed[], const char *headingStr)
|
static const char *printTimerDmaopt(const timerIOConfig_t *currentConfig, const timerIOConfig_t *defaultConfig, unsigned index, dumpFlags_t dumpMask, bool tagsInUse[], const char *headingStr)
|
||||||
{
|
{
|
||||||
const ioTag_t ioTag = currentConfig[index].ioTag;
|
const ioTag_t ioTag = currentConfig[index].ioTag;
|
||||||
|
|
||||||
|
@ -4888,18 +4920,22 @@ static const char *printTimerDmaopt(const timerIOConfig_t *currentConfig, const
|
||||||
const dmaoptValue_t dmaopt = currentConfig[index].dmaopt;
|
const dmaoptValue_t dmaopt = currentConfig[index].dmaopt;
|
||||||
|
|
||||||
dmaoptValue_t defaultDmaopt = DMA_OPT_UNUSED;
|
dmaoptValue_t defaultDmaopt = DMA_OPT_UNUSED;
|
||||||
|
bool equalsDefault = defaultDmaopt == dmaopt;
|
||||||
if (defaultConfig) {
|
if (defaultConfig) {
|
||||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
if (defaultConfig[i].ioTag == ioTag) {
|
if (defaultConfig[i].ioTag == ioTag) {
|
||||||
defaultDmaopt = defaultConfig[index].dmaopt;
|
defaultDmaopt = defaultConfig[i].dmaopt;
|
||||||
defaultIsUsed[index] = true;
|
|
||||||
|
// 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.
|
||||||
|
equalsDefault = (defaultDmaopt == dmaopt) && (defaultConfig[i].index == currentConfig[index].index || dmaopt == DMA_OPT_UNUSED);
|
||||||
|
|
||||||
|
tagsInUse[index] = true;
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
const bool equalsDefault = defaultDmaopt == dmaopt;
|
|
||||||
headingStr = cliPrintSectionHeading(dumpMask, !equalsDefault, headingStr);
|
headingStr = cliPrintSectionHeading(dumpMask, !equalsDefault, headingStr);
|
||||||
|
|
||||||
if (defaultConfig) {
|
if (defaultConfig) {
|
||||||
|
@ -4934,14 +4970,14 @@ static void printDmaopt(dumpFlags_t dumpMask, const char *headingStr)
|
||||||
defaultConfig = NULL;
|
defaultConfig = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool defaultIsUsed[MAX_TIMER_PINMAP_COUNT] = { false };
|
bool tagsInUse[MAX_TIMER_PINMAP_COUNT] = { false };
|
||||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
headingStr = printTimerDmaopt(currentConfig, defaultConfig, i, dumpMask, defaultIsUsed, headingStr);
|
headingStr = printTimerDmaopt(currentConfig, defaultConfig, i, dumpMask, tagsInUse, headingStr);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (defaultConfig) {
|
if (defaultConfig) {
|
||||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
if (!defaultIsUsed[i] && defaultConfig[i].ioTag && defaultConfig[i].dmaopt != DMA_OPT_UNUSED) {
|
if (!tagsInUse[i] && defaultConfig[i].ioTag && defaultConfig[i].dmaopt != DMA_OPT_UNUSED) {
|
||||||
const timerHardware_t *timer = timerGetByTagAndIndex(defaultConfig[i].ioTag, defaultConfig[i].index);
|
const timerHardware_t *timer = timerGetByTagAndIndex(defaultConfig[i].ioTag, defaultConfig[i].index);
|
||||||
headingStr = cliPrintSectionHeading(dumpMask, true, headingStr);
|
headingStr = cliPrintSectionHeading(dumpMask, true, headingStr);
|
||||||
printTimerDmaoptDetails(defaultConfig[i].ioTag, timer, defaultConfig[i].dmaopt, false, dumpMask, cliDefaultPrintLinef);
|
printTimerDmaoptDetails(defaultConfig[i].ioTag, timer, defaultConfig[i].dmaopt, false, dumpMask, cliDefaultPrintLinef);
|
||||||
|
@ -5218,11 +5254,22 @@ static void printTimerDetails(const ioTag_t ioTag, const unsigned timerIndex, co
|
||||||
const char *emptyFormat = "timer %c%02d NONE";
|
const char *emptyFormat = "timer %c%02d NONE";
|
||||||
|
|
||||||
if (timerIndex > 0) {
|
if (timerIndex > 0) {
|
||||||
printValue(dumpMask, equalsDefault, format,
|
const bool printDetails = printValue(dumpMask, equalsDefault, format,
|
||||||
IO_GPIOPortIdxByTag(ioTag) + 'A',
|
IO_GPIOPortIdxByTag(ioTag) + 'A',
|
||||||
IO_GPIOPinIdxByTag(ioTag),
|
IO_GPIOPinIdxByTag(ioTag),
|
||||||
timerIndex - 1
|
timerIndex - 1
|
||||||
);
|
);
|
||||||
|
if (printDetails) {
|
||||||
|
const timerHardware_t *timer = timerGetByTagAndIndex(ioTag, timerIndex);
|
||||||
|
printValue(dumpMask, false,
|
||||||
|
"# pin %c%02d: TIM%d CH%d%s (AF%d)",
|
||||||
|
IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag),
|
||||||
|
timerGetTIMNumber(timer->tim),
|
||||||
|
CC_INDEX_FROM_CHANNEL(timer->channel) + 1,
|
||||||
|
timer->output & TIMER_OUTPUT_N_CHANNEL ? "N" : "",
|
||||||
|
timer->alternateFunction
|
||||||
|
);
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
printValue(dumpMask, equalsDefault, emptyFormat,
|
printValue(dumpMask, equalsDefault, emptyFormat,
|
||||||
IO_GPIOPortIdxByTag(ioTag) + 'A',
|
IO_GPIOPortIdxByTag(ioTag) + 'A',
|
||||||
|
@ -5246,7 +5293,7 @@ static void printTimer(dumpFlags_t dumpMask, const char *headingStr)
|
||||||
defaultConfig = NULL;
|
defaultConfig = NULL;
|
||||||
}
|
}
|
||||||
|
|
||||||
bool defaultIsUsed[MAX_TIMER_PINMAP_COUNT] = { false };
|
bool tagsInUse[MAX_TIMER_PINMAP_COUNT] = { false };
|
||||||
for (unsigned int i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned int i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
const ioTag_t ioTag = currentConfig[i].ioTag;
|
const ioTag_t ioTag = currentConfig[i].ioTag;
|
||||||
|
|
||||||
|
@ -5261,7 +5308,7 @@ static void printTimer(dumpFlags_t dumpMask, const char *headingStr)
|
||||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
if (defaultConfig[i].ioTag == ioTag) {
|
if (defaultConfig[i].ioTag == ioTag) {
|
||||||
defaultTimerIndex = defaultConfig[i].index;
|
defaultTimerIndex = defaultConfig[i].index;
|
||||||
defaultIsUsed[i] = true;
|
tagsInUse[i] = true;
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
@ -5279,7 +5326,7 @@ static void printTimer(dumpFlags_t dumpMask, const char *headingStr)
|
||||||
|
|
||||||
if (defaultConfig) {
|
if (defaultConfig) {
|
||||||
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
for (unsigned i = 0; i < MAX_TIMER_PINMAP_COUNT; i++) {
|
||||||
if (!defaultIsUsed[i] && defaultConfig[i].ioTag) {
|
if (!tagsInUse[i] && defaultConfig[i].ioTag) {
|
||||||
headingStr = cliPrintSectionHeading(DO_DIFF, true, headingStr);
|
headingStr = cliPrintSectionHeading(DO_DIFF, true, headingStr);
|
||||||
printTimerDetails(defaultConfig[i].ioTag, defaultConfig[i].index, false, dumpMask, cliDefaultPrintLinef);
|
printTimerDetails(defaultConfig[i].ioTag, defaultConfig[i].index, false, dumpMask, cliDefaultPrintLinef);
|
||||||
|
|
||||||
|
@ -5354,16 +5401,35 @@ static void cliTimer(char *cmdline)
|
||||||
/* output the list of available options */
|
/* output the list of available options */
|
||||||
const timerHardware_t *timer;
|
const timerHardware_t *timer;
|
||||||
for (unsigned index = 0; (timer = timerGetByTagAndIndex(ioTag, index + 1)); index++) {
|
for (unsigned index = 0; (timer = timerGetByTagAndIndex(ioTag, index + 1)); index++) {
|
||||||
cliPrintLinef("# %d: TIM%d CH%d",
|
cliPrintLinef("# %d: TIM%d CH%d%s (AF%d)",
|
||||||
index,
|
index,
|
||||||
timerGetTIMNumber(timer->tim),
|
timerGetTIMNumber(timer->tim),
|
||||||
CC_INDEX_FROM_CHANNEL(timer->channel) + 1
|
CC_INDEX_FROM_CHANNEL(timer->channel) + 1,
|
||||||
|
timer->output & TIMER_OUTPUT_N_CHANNEL ? "N" : "",
|
||||||
|
timer->alternateFunction
|
||||||
);
|
);
|
||||||
}
|
}
|
||||||
|
|
||||||
return;
|
return;
|
||||||
} else if (strcasecmp(pch, "none") == 0) {
|
} else if (strcasecmp(pch, "none") == 0) {
|
||||||
timerIndex = TIMER_INDEX_UNDEFINED;
|
timerIndex = TIMER_INDEX_UNDEFINED;
|
||||||
|
} else if (strncasecmp(pch, "af", 2) == 0) {
|
||||||
|
unsigned alternateFunction = atoi(&pch[2]);
|
||||||
|
|
||||||
|
const timerHardware_t *timer;
|
||||||
|
for (unsigned index = 0; (timer = timerGetByTagAndIndex(ioTag, index + 1)); index++) {
|
||||||
|
if (timer->alternateFunction == alternateFunction) {
|
||||||
|
timerIndex = index;
|
||||||
|
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!timer) {
|
||||||
|
cliPrintErrorLinef("INVALID ALTERNATE FUNCTION FOR %c%02d: '%s'", IO_GPIOPortIdxByTag(ioTag) + 'A', IO_GPIOPinIdxByTag(ioTag), pch);
|
||||||
|
|
||||||
|
return;
|
||||||
|
}
|
||||||
} else {
|
} else {
|
||||||
timerIndex = atoi(pch);
|
timerIndex = atoi(pch);
|
||||||
|
|
||||||
|
@ -5779,6 +5845,7 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
|
CLI_COMMAND_DEF("flash_info", "show flash chip info", NULL, cliFlashInfo),
|
||||||
#ifdef USE_FLASH_TOOLS
|
#ifdef USE_FLASH_TOOLS
|
||||||
CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
|
CLI_COMMAND_DEF("flash_read", NULL, "<length> <address>", cliFlashRead),
|
||||||
|
CLI_COMMAND_DEF("flash_scan", "scan flash device for errors", NULL, cliFlashVerify),
|
||||||
CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
|
CLI_COMMAND_DEF("flash_write", NULL, "<address> <message>", cliFlashWrite),
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
@ -5857,7 +5924,7 @@ const clicmd_t cmdTable[] = {
|
||||||
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
|
CLI_COMMAND_DEF("tasks", "show task stats", NULL, cliTasks),
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_TIMER_MGMT
|
#ifdef USE_TIMER_MGMT
|
||||||
CLI_COMMAND_DEF("timer", "show/set timers", "<> | <pin> list | <pin> [<option>|none] | list | show", cliTimer),
|
CLI_COMMAND_DEF("timer", "show/set timers", "<> | <pin> list | <pin> [<option>|af<altenate function>|none] | list | show", cliTimer),
|
||||||
#endif
|
#endif
|
||||||
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
|
CLI_COMMAND_DEF("version", "show version", NULL, cliVersion),
|
||||||
#ifdef USE_VTX_CONTROL
|
#ifdef USE_VTX_CONTROL
|
||||||
|
|
|
@ -325,7 +325,7 @@ static const char * const lookupTableGyroOverflowCheck[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static const char * const lookupTableRatesType[] = {
|
static const char * const lookupTableRatesType[] = {
|
||||||
"BETAFLIGHT", "RACEFLIGHT"
|
"BETAFLIGHT", "RACEFLIGHT", "KISS"
|
||||||
};
|
};
|
||||||
|
|
||||||
#ifdef USE_OVERCLOCK
|
#ifdef USE_OVERCLOCK
|
||||||
|
@ -356,6 +356,9 @@ static const char * const lookupTableThrottleLimitType[] = {
|
||||||
static const char * const lookupTableRescueSanityType[] = {
|
static const char * const lookupTableRescueSanityType[] = {
|
||||||
"RESCUE_SANITY_OFF", "RESCUE_SANITY_ON", "RESCUE_SANITY_FS_ONLY"
|
"RESCUE_SANITY_OFF", "RESCUE_SANITY_ON", "RESCUE_SANITY_FS_ONLY"
|
||||||
};
|
};
|
||||||
|
static const char * const lookupTableRescueAltitudeMode[] = {
|
||||||
|
"MAX_ALT", "FIXED_ALT", "CURRENT_ALT"
|
||||||
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_MAX7456
|
#ifdef USE_MAX7456
|
||||||
|
@ -472,6 +475,7 @@ const lookupTableEntry_t lookupTables[] = {
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableGPSSBASMode),
|
LOOKUP_TABLE_ENTRY(lookupTableGPSSBASMode),
|
||||||
#ifdef USE_GPS_RESCUE
|
#ifdef USE_GPS_RESCUE
|
||||||
LOOKUP_TABLE_ENTRY(lookupTableRescueSanityType),
|
LOOKUP_TABLE_ENTRY(lookupTableRescueSanityType),
|
||||||
|
LOOKUP_TABLE_ENTRY(lookupTableRescueAltitudeMode),
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
|
@ -904,10 +908,11 @@ const clivalue_t valueTable[] = {
|
||||||
{ "gps_rescue_throttle_min", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMin) },
|
{ "gps_rescue_throttle_min", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMin) },
|
||||||
{ "gps_rescue_throttle_max", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMax) },
|
{ "gps_rescue_throttle_max", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMax) },
|
||||||
{ "gps_rescue_throttle_hover", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleHover) },
|
{ "gps_rescue_throttle_hover", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleHover) },
|
||||||
{ "gps_rescue_sanity_checks", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_RESCUE }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, sanityChecks) },
|
{ "gps_rescue_sanity_checks", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_RESCUE_SANITY_CHECK }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, sanityChecks) },
|
||||||
{ "gps_rescue_min_sats", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 5, 50 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, minSats) },
|
{ "gps_rescue_min_sats", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 5, 50 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, minSats) },
|
||||||
{ "gps_rescue_min_dth", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 50, 1000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, minRescueDth) },
|
{ "gps_rescue_min_dth", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 50, 1000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, minRescueDth) },
|
||||||
{ "gps_rescue_allow_arming_without_fix", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, allowArmingWithoutFix) },
|
{ "gps_rescue_allow_arming_without_fix", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, allowArmingWithoutFix) },
|
||||||
|
{ "gps_rescue_alt_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_GPS_RESCUE_ALT_MODE }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, altitudeMode) },
|
||||||
#ifdef USE_MAG
|
#ifdef USE_MAG
|
||||||
{ "gps_rescue_use_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, useMag) },
|
{ "gps_rescue_use_mag", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, useMag) },
|
||||||
#endif
|
#endif
|
||||||
|
@ -1154,7 +1159,7 @@ const clivalue_t valueTable[] = {
|
||||||
|
|
||||||
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
|
{ "osd_rssi_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, rssi_alarm) },
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
{ "osd_link_quality_alarm", VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_OSD_CONFIG, offsetof(osdConfig_t, link_quality_alarm) },
|
{ "osd_link_quality_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 300 }, PG_OSD_CONFIG, offsetof(osdConfig_t, link_quality_alarm) },
|
||||||
#endif
|
#endif
|
||||||
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
{ "osd_cap_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 20000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, cap_alarm) },
|
||||||
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
{ "osd_alt_alarm", VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 10000 }, PG_OSD_CONFIG, offsetof(osdConfig_t, alt_alarm) },
|
||||||
|
@ -1285,7 +1290,9 @@ const clivalue_t valueTable[] = {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// PG_SYSTEM_CONFIG
|
// PG_SYSTEM_CONFIG
|
||||||
|
#if defined(STM32F4)
|
||||||
{ "system_hse_mhz", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, 30 }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, hseMhz) },
|
{ "system_hse_mhz", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, 30 }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, hseMhz) },
|
||||||
|
#endif
|
||||||
#if defined(USE_TASK_STATISTICS)
|
#if defined(USE_TASK_STATISTICS)
|
||||||
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
|
{ "task_statistics", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_SYSTEM_CONFIG, offsetof(systemConfig_t, task_statistics) },
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -34,7 +34,8 @@ typedef enum {
|
||||||
TABLE_GPS_SBAS_MODE,
|
TABLE_GPS_SBAS_MODE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_GPS_RESCUE
|
#ifdef USE_GPS_RESCUE
|
||||||
TABLE_GPS_RESCUE,
|
TABLE_GPS_RESCUE_SANITY_CHECK,
|
||||||
|
TABLE_GPS_RESCUE_ALT_MODE,
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_BLACKBOX
|
#ifdef USE_BLACKBOX
|
||||||
TABLE_BLACKBOX_DEVICE,
|
TABLE_BLACKBOX_DEVICE,
|
||||||
|
|
|
@ -126,9 +126,11 @@ static void cmsx_Blackbox_GetDeviceStatus(void)
|
||||||
if (storageDeviceIsWorking) {
|
if (storageDeviceIsWorking) {
|
||||||
tfp_sprintf(cmsx_BlackboxStatus, "READY");
|
tfp_sprintf(cmsx_BlackboxStatus, "READY");
|
||||||
|
|
||||||
const flashGeometry_t *geometry = flashfsGetGeometry();
|
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
|
||||||
|
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||||
|
|
||||||
storageUsed = flashfsGetOffset() / 1024;
|
storageUsed = flashfsGetOffset() / 1024;
|
||||||
storageFree = (geometry->totalSize / 1024) - storageUsed;
|
storageFree = ((FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize) / 1024) - storageUsed;
|
||||||
} else {
|
} else {
|
||||||
tfp_sprintf(cmsx_BlackboxStatus, "FAULT");
|
tfp_sprintf(cmsx_BlackboxStatus, "FAULT");
|
||||||
}
|
}
|
||||||
|
|
|
@ -159,6 +159,7 @@ CMS_Menu menuOsdActiveElems = {
|
||||||
};
|
};
|
||||||
|
|
||||||
static uint8_t osdConfig_rssi_alarm;
|
static uint8_t osdConfig_rssi_alarm;
|
||||||
|
static uint16_t osdConfig_link_quality_alarm;
|
||||||
static uint16_t osdConfig_cap_alarm;
|
static uint16_t osdConfig_cap_alarm;
|
||||||
static uint16_t osdConfig_alt_alarm;
|
static uint16_t osdConfig_alt_alarm;
|
||||||
static uint8_t batteryConfig_vbatDurationForWarning;
|
static uint8_t batteryConfig_vbatDurationForWarning;
|
||||||
|
@ -167,6 +168,7 @@ static uint8_t batteryConfig_vbatDurationForCritical;
|
||||||
static long menuAlarmsOnEnter(void)
|
static long menuAlarmsOnEnter(void)
|
||||||
{
|
{
|
||||||
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
osdConfig_rssi_alarm = osdConfig()->rssi_alarm;
|
||||||
|
osdConfig_link_quality_alarm = osdConfig()->link_quality_alarm;
|
||||||
osdConfig_cap_alarm = osdConfig()->cap_alarm;
|
osdConfig_cap_alarm = osdConfig()->cap_alarm;
|
||||||
osdConfig_alt_alarm = osdConfig()->alt_alarm;
|
osdConfig_alt_alarm = osdConfig()->alt_alarm;
|
||||||
batteryConfig_vbatDurationForWarning = batteryConfig()->vbatDurationForWarning;
|
batteryConfig_vbatDurationForWarning = batteryConfig()->vbatDurationForWarning;
|
||||||
|
@ -180,6 +182,7 @@ static long menuAlarmsOnExit(const OSD_Entry *self)
|
||||||
UNUSED(self);
|
UNUSED(self);
|
||||||
|
|
||||||
osdConfigMutable()->rssi_alarm = osdConfig_rssi_alarm;
|
osdConfigMutable()->rssi_alarm = osdConfig_rssi_alarm;
|
||||||
|
osdConfigMutable()->link_quality_alarm = osdConfig_link_quality_alarm;
|
||||||
osdConfigMutable()->cap_alarm = osdConfig_cap_alarm;
|
osdConfigMutable()->cap_alarm = osdConfig_cap_alarm;
|
||||||
osdConfigMutable()->alt_alarm = osdConfig_alt_alarm;
|
osdConfigMutable()->alt_alarm = osdConfig_alt_alarm;
|
||||||
batteryConfigMutable()->vbatDurationForWarning = batteryConfig_vbatDurationForWarning;
|
batteryConfigMutable()->vbatDurationForWarning = batteryConfig_vbatDurationForWarning;
|
||||||
|
@ -192,6 +195,7 @@ const OSD_Entry menuAlarmsEntries[] =
|
||||||
{
|
{
|
||||||
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
||||||
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0},
|
{"RSSI", OME_UINT8, NULL, &(OSD_UINT8_t){&osdConfig_rssi_alarm, 5, 90, 5}, 0},
|
||||||
|
{"LINK QUALITY", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_link_quality_alarm, 5, 300, 5}, 0},
|
||||||
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0},
|
{"MAIN BAT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_cap_alarm, 50, 30000, 50}, 0},
|
||||||
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0},
|
{"MAX ALT", OME_UINT16, NULL, &(OSD_UINT16_t){&osdConfig_alt_alarm, 1, 200, 1}, 0},
|
||||||
{"VBAT WARN DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForWarning, 0, 200, 1 }, 0 },
|
{"VBAT WARN DUR", OME_UINT8, NULL, &(OSD_UINT8_t){ &batteryConfig_vbatDurationForWarning, 0, 200, 1 }, 0 },
|
||||||
|
|
|
@ -1,18 +1,21 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*
|
*
|
||||||
* Author: Dominic Clifton
|
* Author: Dominic Clifton
|
||||||
*/
|
*/
|
||||||
|
|
|
@ -1,22 +1,25 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* HAL version resurrected from v3.1.7 (by jflyper)
|
||||||
*/
|
*/
|
||||||
|
|
||||||
// HAL version resurrected from v3.1.7
|
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <strings.h>
|
#include <strings.h>
|
||||||
|
|
|
@ -20,6 +20,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -30,8 +31,10 @@
|
||||||
#include "flash.h"
|
#include "flash.h"
|
||||||
#include "flash_impl.h"
|
#include "flash_impl.h"
|
||||||
#include "flash_m25p16.h"
|
#include "flash_m25p16.h"
|
||||||
|
#include "flash_w25n01g.h"
|
||||||
#include "flash_w25m.h"
|
#include "flash_w25m.h"
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_quadspi.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
#include "drivers/time.h"
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
@ -39,16 +42,52 @@ static busDevice_t busInstance;
|
||||||
static busDevice_t *busdev;
|
static busDevice_t *busdev;
|
||||||
|
|
||||||
static flashDevice_t flashDevice;
|
static flashDevice_t flashDevice;
|
||||||
|
static flashPartitionTable_t flashPartitionTable;
|
||||||
|
static int flashPartitions = 0;
|
||||||
|
|
||||||
|
#define FLASH_INSTRUCTION_RDID 0x9F
|
||||||
|
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
static bool flashQuadSpiInit(const flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
QUADSPI_TypeDef *quadSpiInstance = quadSpiInstanceByDevice(QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice));
|
||||||
|
quadSpiSetDivisor(quadSpiInstance, QUADSPI_CLOCK_INITIALISATION);
|
||||||
|
|
||||||
|
uint8_t readIdResponse[4];
|
||||||
|
bool status = quadSpiReceive1LINE(quadSpiInstance, FLASH_INSTRUCTION_RDID, 8, readIdResponse, sizeof(readIdResponse));
|
||||||
|
if (!status) {
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
flashDevice.io.mode = FLASHIO_QUADSPI;
|
||||||
|
flashDevice.io.handle.quadSpi = quadSpiInstance;
|
||||||
|
|
||||||
|
// Manufacturer, memory type, and capacity
|
||||||
|
uint32_t chipID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]);
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_W25N01G
|
||||||
|
quadSpiSetDivisor(quadSpiInstance, QUADSPI_CLOCK_ULTRAFAST);
|
||||||
|
|
||||||
|
if (w25n01g_detect(&flashDevice, chipID)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
#endif // USE_QUADSPI
|
||||||
|
|
||||||
|
#ifdef USE_SPI
|
||||||
|
|
||||||
void flashPreInit(const flashConfig_t *flashConfig)
|
void flashPreInit(const flashConfig_t *flashConfig)
|
||||||
{
|
{
|
||||||
spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1);
|
spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1);
|
||||||
}
|
}
|
||||||
|
|
||||||
// Read chip identification and send it to device detect
|
static bool flashSpiInit(const flashConfig_t *flashConfig)
|
||||||
|
|
||||||
bool flashInit(const flashConfig_t *flashConfig)
|
|
||||||
{
|
{
|
||||||
|
// Read chip identification and send it to device detect
|
||||||
|
|
||||||
busdev = &busInstance;
|
busdev = &busInstance;
|
||||||
|
|
||||||
if (flashConfig->csTag) {
|
if (flashConfig->csTag) {
|
||||||
|
@ -84,27 +123,29 @@ bool flashInit(const flashConfig_t *flashConfig)
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
flashDevice.busdev = busdev;
|
flashDevice.io.mode = FLASHIO_SPI;
|
||||||
|
flashDevice.io.handle.busdev = busdev;
|
||||||
|
|
||||||
const uint8_t out[] = { SPIFLASH_INSTRUCTION_RDID, 0, 0, 0 };
|
const uint8_t out[] = { FLASH_INSTRUCTION_RDID, 0, 0, 0, 0 };
|
||||||
|
|
||||||
delay(50); // short delay required after initialisation of SPI device instance.
|
delay(50); // short delay required after initialisation of SPI device instance.
|
||||||
|
|
||||||
/* Just in case transfer fails and writes nothing, so we don't try to verify the ID against random garbage
|
/*
|
||||||
* from the stack:
|
* Some newer chips require one dummy byte to be read; we can read
|
||||||
|
* 4 bytes for these chips while retaining backward compatibility.
|
||||||
*/
|
*/
|
||||||
uint8_t in[4];
|
uint8_t readIdResponse[5];
|
||||||
in[1] = 0;
|
readIdResponse[1] = readIdResponse[2] = 0;
|
||||||
|
|
||||||
// Clearing the CS bit terminates the command early so we don't have to read the chip UID:
|
// Clearing the CS bit terminates the command early so we don't have to read the chip UID:
|
||||||
#ifdef USE_SPI_TRANSACTION
|
#ifdef USE_SPI_TRANSACTION
|
||||||
spiBusTransactionTransfer(busdev, out, in, sizeof(out));
|
spiBusTransactionTransfer(busdev, out, readIdResponse, sizeof(out));
|
||||||
#else
|
#else
|
||||||
spiBusTransfer(busdev, out, in, sizeof(out));
|
spiBusTransfer(busdev, out, readIdResponse, sizeof(out));
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// Manufacturer, memory type, and capacity
|
// Manufacturer, memory type, and capacity
|
||||||
uint32_t chipID = (in[1] << 16) | (in[2] << 8) | (in[3]);
|
uint32_t chipID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]);
|
||||||
|
|
||||||
#ifdef USE_FLASH_M25P16
|
#ifdef USE_FLASH_M25P16
|
||||||
if (m25p16_detect(&flashDevice, chipID)) {
|
if (m25p16_detect(&flashDevice, chipID)) {
|
||||||
|
@ -112,7 +153,22 @@ bool flashInit(const flashConfig_t *flashConfig)
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASH_W25M
|
#ifdef USE_FLASH_W25M512
|
||||||
|
if (w25m_detect(&flashDevice, chipID)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Newer chips
|
||||||
|
chipID = (readIdResponse[2] << 16) | (readIdResponse[3] << 8) | (readIdResponse[4]);
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_W25N01G
|
||||||
|
if (w25n01g_detect(&flashDevice, chipID)) {
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_W25M02G
|
||||||
if (w25m_detect(&flashDevice, chipID)) {
|
if (w25m_detect(&flashDevice, chipID)) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
@ -122,6 +178,27 @@ bool flashInit(const flashConfig_t *flashConfig)
|
||||||
|
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
#endif // USE_SPI
|
||||||
|
|
||||||
|
bool flashDeviceInit(const flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
#ifdef USE_SPI
|
||||||
|
bool useSpi = (SPI_CFG_TO_DEV(flashConfig->spiDevice) != SPIINVALID);
|
||||||
|
|
||||||
|
if (useSpi) {
|
||||||
|
return flashSpiInit(flashConfig);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
bool useQuadSpi = (QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice) != QUADSPIINVALID);
|
||||||
|
if (useQuadSpi) {
|
||||||
|
return flashQuadSpiInit(flashConfig);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
bool flashIsReady(void)
|
bool flashIsReady(void)
|
||||||
{
|
{
|
||||||
|
@ -185,4 +262,137 @@ const flashGeometry_t *flashGetGeometry(void)
|
||||||
|
|
||||||
return &noFlashGeometry;
|
return &noFlashGeometry;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Flash partitioning
|
||||||
|
*
|
||||||
|
* Partition table is not currently stored on the flash, in-memory only.
|
||||||
|
*
|
||||||
|
* Partitions are required so that Badblock management (inc spare blocks), FlashFS (Blackbox Logging), Configuration and Firmware can be kept separate and tracked.
|
||||||
|
*
|
||||||
|
* XXX FIXME
|
||||||
|
* XXX Note that Flash FS must start at sector 0.
|
||||||
|
* XXX There is existing blackbox/flash FS code the relies on this!!!
|
||||||
|
* XXX This restriction can and will be fixed by creating a set of flash operation functions that take partition as an additional parameter.
|
||||||
|
*/
|
||||||
|
|
||||||
|
static void flashConfigurePartitions(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||||
|
if (flashGeometry->totalSize == 0) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
flashSector_t startSector = 0;
|
||||||
|
flashSector_t endSector = flashGeometry->sectors - 1; // 0 based index
|
||||||
|
|
||||||
|
const flashPartition_t *badBlockPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT);
|
||||||
|
if (badBlockPartition) {
|
||||||
|
endSector = badBlockPartition->startSector - 1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#if defined(FIRMWARE_SIZE)
|
||||||
|
const uint32_t firmwareSize = (FIRMWARE_SIZE * 1024);
|
||||||
|
flashSector_t firmwareSectors = (firmwareSize / flashGeometry->sectorSize);
|
||||||
|
|
||||||
|
if (firmwareSize % flashGeometry->sectorSize > 0) {
|
||||||
|
firmwareSectors++; // needs a portion of a sector.
|
||||||
|
}
|
||||||
|
|
||||||
|
startSector = (endSector + 1) - firmwareSectors; // + 1 for inclusive
|
||||||
|
|
||||||
|
flashPartitionSet(FLASH_PARTITION_TYPE_FIRMWARE, startSector, endSector);
|
||||||
|
|
||||||
|
endSector = startSector - 1;
|
||||||
|
startSector = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(EEPROM_IN_EXTERNAL_FLASH)
|
||||||
|
const uint32_t configSize = EEPROM_SIZE;
|
||||||
|
flashSector_t configSectors = (configSize / flashGeometry->sectorSize);
|
||||||
|
|
||||||
|
if (configSize % flashGeometry->sectorSize > 0) {
|
||||||
|
configSectors++; // needs a portion of a sector.
|
||||||
|
}
|
||||||
|
|
||||||
|
startSector = (endSector + 1) - configSectors; // + 1 for inclusive
|
||||||
|
|
||||||
|
flashPartitionSet(FLASH_PARTITION_TYPE_CONFIG, startSector, endSector);
|
||||||
|
|
||||||
|
endSector = startSector - 1;
|
||||||
|
startSector = 0;
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
flashPartitionSet(FLASH_PARTITION_TYPE_FLASHFS, startSector, endSector);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
flashPartition_t *flashPartitionFindByType(uint8_t type)
|
||||||
|
{
|
||||||
|
for (int index = 0; index < FLASH_MAX_PARTITIONS; index++) {
|
||||||
|
flashPartition_t *candidate = &flashPartitionTable.partitions[index];
|
||||||
|
if (candidate->type == type) {
|
||||||
|
return candidate;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
const flashPartition_t *flashPartitionFindByIndex(uint8_t index)
|
||||||
|
{
|
||||||
|
if (index >= flashPartitions) {
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
return &flashPartitionTable.partitions[index];
|
||||||
|
}
|
||||||
|
|
||||||
|
void flashPartitionSet(uint8_t type, uint32_t startSector, uint32_t endSector)
|
||||||
|
{
|
||||||
|
flashPartition_t *entry = flashPartitionFindByType(type);
|
||||||
|
|
||||||
|
if (!entry) {
|
||||||
|
if (flashPartitions == FLASH_MAX_PARTITIONS - 1) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
entry = &flashPartitionTable.partitions[flashPartitions++];
|
||||||
|
}
|
||||||
|
|
||||||
|
entry->type = type;
|
||||||
|
entry->startSector = startSector;
|
||||||
|
entry->endSector = endSector;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Must be in sync with FLASH_PARTITION_TYPE
|
||||||
|
static const char *flashPartitionNames[] = {
|
||||||
|
"UNKNOWN ",
|
||||||
|
"PARTITION",
|
||||||
|
"FLASHFS ",
|
||||||
|
"BBMGMT ",
|
||||||
|
"FIRMWARE ",
|
||||||
|
"CONFIG ",
|
||||||
|
};
|
||||||
|
|
||||||
|
const char *flashPartitionGetTypeName(flashPartitionType_e type)
|
||||||
|
{
|
||||||
|
if (type < ARRAYLEN(flashPartitionNames)) {
|
||||||
|
return flashPartitionNames[type];
|
||||||
|
}
|
||||||
|
|
||||||
|
return NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool flashInit(const flashConfig_t *flashConfig)
|
||||||
|
{
|
||||||
|
memset(&flashPartitionTable, 0x00, sizeof(flashPartitionTable));
|
||||||
|
|
||||||
|
bool haveFlash = flashDeviceInit(flashConfig);
|
||||||
|
|
||||||
|
flashConfigurePartitions();
|
||||||
|
|
||||||
|
return haveFlash;
|
||||||
|
}
|
||||||
#endif // USE_FLASH_CHIP
|
#endif // USE_FLASH_CHIP
|
||||||
|
|
|
@ -36,8 +36,10 @@ typedef enum {
|
||||||
FLASH_TYPE_NAND
|
FLASH_TYPE_NAND
|
||||||
} flashType_e;
|
} flashType_e;
|
||||||
|
|
||||||
|
typedef uint16_t flashSector_t;
|
||||||
|
|
||||||
typedef struct flashGeometry_s {
|
typedef struct flashGeometry_s {
|
||||||
uint16_t sectors; // Count of the number of erasable blocks on the device
|
flashSector_t sectors; // Count of the number of erasable blocks on the device
|
||||||
uint16_t pageSize; // In bytes
|
uint16_t pageSize; // In bytes
|
||||||
uint32_t sectorSize; // This is just pagesPerSector * pageSize
|
uint32_t sectorSize; // This is just pagesPerSector * pageSize
|
||||||
uint32_t totalSize; // This is just sectorSize * sectors
|
uint32_t totalSize; // This is just sectorSize * sectors
|
||||||
|
@ -59,3 +61,36 @@ void flashPageProgram(uint32_t address, const uint8_t *data, int length);
|
||||||
int flashReadBytes(uint32_t address, uint8_t *buffer, int length);
|
int flashReadBytes(uint32_t address, uint8_t *buffer, int length);
|
||||||
void flashFlush(void);
|
void flashFlush(void);
|
||||||
const flashGeometry_t *flashGetGeometry(void);
|
const flashGeometry_t *flashGetGeometry(void);
|
||||||
|
|
||||||
|
//
|
||||||
|
// flash partitioning api
|
||||||
|
//
|
||||||
|
|
||||||
|
typedef struct flashPartition_s {
|
||||||
|
uint8_t type;
|
||||||
|
flashSector_t startSector;
|
||||||
|
flashSector_t endSector;
|
||||||
|
} flashPartition_t;
|
||||||
|
|
||||||
|
#define FLASH_PARTITION_SECTOR_COUNT(partition) (partition->endSector + 1 - partition->startSector) // + 1 for inclusive, start and end sector can be the same sector.
|
||||||
|
|
||||||
|
// Must be in sync with flashPartitionTypeNames[]
|
||||||
|
// Should not be deleted or reordered once the code is writing a table to a flash.
|
||||||
|
typedef enum {
|
||||||
|
FLASH_PARTITION_TYPE_UNKNOWN = 0,
|
||||||
|
FLASH_PARTITION_TYPE_PARTITION_TABLE,
|
||||||
|
FLASH_PARTITION_TYPE_FLASHFS,
|
||||||
|
FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
|
||||||
|
FLASH_PARTITION_TYPE_FIRMWARE,
|
||||||
|
FLASH_PARTITION_TYPE_CONFIG,
|
||||||
|
FLASH_MAX_PARTITIONS
|
||||||
|
} flashPartitionType_e;
|
||||||
|
|
||||||
|
typedef struct flashPartitionTable_s {
|
||||||
|
flashPartition_t partitions[FLASH_MAX_PARTITIONS];
|
||||||
|
} flashPartitionTable_t;
|
||||||
|
|
||||||
|
void flashPartitionSet(uint8_t index, uint32_t startSector, uint32_t endSector);
|
||||||
|
flashPartition_t *flashPartitionFindByType(flashPartitionType_e type);
|
||||||
|
const flashPartition_t *flashPartitionFindByIndex(uint8_t index);
|
||||||
|
const char *flashPartitionGetTypeName(flashPartitionType_e type);
|
||||||
|
|
|
@ -28,8 +28,23 @@
|
||||||
|
|
||||||
struct flashVTable_s;
|
struct flashVTable_s;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
FLASHIO_NONE = 0,
|
||||||
|
FLASHIO_SPI,
|
||||||
|
FLASHIO_QUADSPI
|
||||||
|
} flashDeviceIoMode_e;
|
||||||
|
|
||||||
|
typedef struct flashDeviceIO_s {
|
||||||
|
union {
|
||||||
|
busDevice_t *busdev; // Device interface dependent handle (spi/i2c)
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
QUADSPI_TypeDef *quadSpi;
|
||||||
|
#endif
|
||||||
|
} handle;
|
||||||
|
flashDeviceIoMode_e mode;
|
||||||
|
} flashDeviceIO_t;
|
||||||
|
|
||||||
typedef struct flashDevice_s {
|
typedef struct flashDevice_s {
|
||||||
busDevice_t *busdev;
|
|
||||||
const struct flashVTable_s *vTable;
|
const struct flashVTable_s *vTable;
|
||||||
flashGeometry_t geometry;
|
flashGeometry_t geometry;
|
||||||
uint32_t currentWriteAddress;
|
uint32_t currentWriteAddress;
|
||||||
|
@ -38,6 +53,7 @@ typedef struct flashDevice_s {
|
||||||
// for writes. This allows us to avoid polling for writable status
|
// for writes. This allows us to avoid polling for writable status
|
||||||
// when it is definitely ready already.
|
// when it is definitely ready already.
|
||||||
bool couldBeBusy;
|
bool couldBeBusy;
|
||||||
|
flashDeviceIO_t io;
|
||||||
} flashDevice_t;
|
} flashDevice_t;
|
||||||
|
|
||||||
typedef struct flashVTable_s {
|
typedef struct flashVTable_s {
|
||||||
|
|
|
@ -126,7 +126,7 @@ static void m25p16_performOneByteCommand(busDevice_t *bus, uint8_t command)
|
||||||
*/
|
*/
|
||||||
static void m25p16_writeEnable(flashDevice_t *fdevice)
|
static void m25p16_writeEnable(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_WRITE_ENABLE);
|
m25p16_performOneByteCommand(fdevice->io.handle.busdev, M25P16_INSTRUCTION_WRITE_ENABLE);
|
||||||
|
|
||||||
// Assume that we're about to do some writing, so the device is just about to become busy
|
// Assume that we're about to do some writing, so the device is just about to become busy
|
||||||
fdevice->couldBeBusy = true;
|
fdevice->couldBeBusy = true;
|
||||||
|
@ -145,7 +145,7 @@ static uint8_t m25p16_readStatus(busDevice_t *bus)
|
||||||
static bool m25p16_isReady(flashDevice_t *fdevice)
|
static bool m25p16_isReady(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
// If couldBeBusy is false, don't bother to poll the flash chip for its status
|
// If couldBeBusy is false, don't bother to poll the flash chip for its status
|
||||||
fdevice->couldBeBusy = fdevice->couldBeBusy && ((m25p16_readStatus(fdevice->busdev) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
|
fdevice->couldBeBusy = fdevice->couldBeBusy && ((m25p16_readStatus(fdevice->io.handle.busdev) & M25P16_STATUS_FLAG_WRITE_IN_PROGRESS) != 0);
|
||||||
|
|
||||||
return !fdevice->couldBeBusy;
|
return !fdevice->couldBeBusy;
|
||||||
}
|
}
|
||||||
|
@ -219,7 +219,7 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID)
|
||||||
|
|
||||||
if (fdevice->geometry.totalSize > 16 * 1024 * 1024) {
|
if (fdevice->geometry.totalSize > 16 * 1024 * 1024) {
|
||||||
fdevice->isLargeFlash = true;
|
fdevice->isLargeFlash = true;
|
||||||
m25p16_performOneByteCommand(fdevice->busdev, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE);
|
m25p16_performOneByteCommand(fdevice->io.handle.busdev, W25Q256_INSTRUCTION_ENTER_4BYTE_ADDRESS_MODE);
|
||||||
}
|
}
|
||||||
|
|
||||||
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
|
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
|
||||||
|
@ -250,7 +250,7 @@ static void m25p16_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
||||||
|
|
||||||
m25p16_writeEnable(fdevice);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
m25p16_transfer(fdevice->busdev, out, NULL, sizeof(out));
|
m25p16_transfer(fdevice->io.handle.busdev, out, NULL, sizeof(out));
|
||||||
}
|
}
|
||||||
|
|
||||||
static void m25p16_eraseCompletely(flashDevice_t *fdevice)
|
static void m25p16_eraseCompletely(flashDevice_t *fdevice)
|
||||||
|
@ -259,7 +259,7 @@ static void m25p16_eraseCompletely(flashDevice_t *fdevice)
|
||||||
|
|
||||||
m25p16_writeEnable(fdevice);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
m25p16_performOneByteCommand(fdevice->busdev, M25P16_INSTRUCTION_BULK_ERASE);
|
m25p16_performOneByteCommand(fdevice->io.handle.busdev, M25P16_INSTRUCTION_BULK_ERASE);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
|
static void m25p16_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
|
||||||
|
@ -280,18 +280,18 @@ static void m25p16_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *da
|
||||||
m25p16_writeEnable(fdevice);
|
m25p16_writeEnable(fdevice);
|
||||||
|
|
||||||
#ifdef USE_SPI_TRANSACTION
|
#ifdef USE_SPI_TRANSACTION
|
||||||
spiBusTransactionBegin(fdevice->busdev);
|
spiBusTransactionBegin(fdevice->io.handle.busdev);
|
||||||
#else
|
#else
|
||||||
m25p16_enable(fdevice->busdev);
|
m25p16_enable(fdevice->io.handle.busdev);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
||||||
spiTransfer(fdevice->busdev->busdev_u.spi.instance, data, NULL, length);
|
spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, data, NULL, length);
|
||||||
|
|
||||||
#ifdef USE_SPI_TRANSACTION
|
#ifdef USE_SPI_TRANSACTION
|
||||||
spiBusTransactionEnd(fdevice->busdev);
|
spiBusTransactionEnd(fdevice->io.handle.busdev);
|
||||||
#else
|
#else
|
||||||
m25p16_disable(fdevice->busdev);
|
m25p16_disable(fdevice->io.handle.busdev);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
fdevice->currentWriteAddress += length;
|
fdevice->currentWriteAddress += length;
|
||||||
|
@ -345,18 +345,18 @@ static int m25p16_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *b
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_SPI_TRANSACTION
|
#ifdef USE_SPI_TRANSACTION
|
||||||
spiBusTransactionBegin(fdevice->busdev);
|
spiBusTransactionBegin(fdevice->io.handle.busdev);
|
||||||
#else
|
#else
|
||||||
m25p16_enable(fdevice->busdev);
|
m25p16_enable(fdevice->io.handle.busdev);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
spiTransfer(fdevice->busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, command, NULL, fdevice->isLargeFlash ? 5 : 4);
|
||||||
spiTransfer(fdevice->busdev->busdev_u.spi.instance, NULL, buffer, length);
|
spiTransfer(fdevice->io.handle.busdev->busdev_u.spi.instance, NULL, buffer, length);
|
||||||
|
|
||||||
#ifdef USE_SPI_TRANSACTION
|
#ifdef USE_SPI_TRANSACTION
|
||||||
spiBusTransactionEnd(fdevice->busdev);
|
spiBusTransactionEnd(fdevice->io.handle.busdev);
|
||||||
#else
|
#else
|
||||||
m25p16_disable(fdevice->busdev);
|
m25p16_disable(fdevice->io.handle.busdev);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
return length;
|
return length;
|
||||||
|
|
|
@ -84,7 +84,7 @@ static bool w25m_isReady(flashDevice_t *fdevice)
|
||||||
|
|
||||||
for (int die = 0 ; die < dieCount ; die++) {
|
for (int die = 0 ; die < dieCount ; die++) {
|
||||||
if (dieDevice[die].couldBeBusy) {
|
if (dieDevice[die].couldBeBusy) {
|
||||||
w25m_dieSelect(fdevice->busdev, die);
|
w25m_dieSelect(fdevice->io.handle.busdev, die);
|
||||||
if (!dieDevice[die].vTable->isReady(&dieDevice[die])) {
|
if (!dieDevice[die].vTable->isReady(&dieDevice[die])) {
|
||||||
return false;
|
return false;
|
||||||
}
|
}
|
||||||
|
@ -115,8 +115,9 @@ bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID)
|
||||||
dieCount = 2;
|
dieCount = 2;
|
||||||
|
|
||||||
for (int die = 0 ; die < dieCount ; die++) {
|
for (int die = 0 ; die < dieCount ; die++) {
|
||||||
w25m_dieSelect(fdevice->busdev, die);
|
w25m_dieSelect(fdevice->io.handle.busdev, die);
|
||||||
dieDevice[die].busdev = fdevice->busdev;
|
dieDevice[die].io.handle.busdev = fdevice->io.handle.busdev;
|
||||||
|
dieDevice[die].io.mode = fdevice->io.mode;
|
||||||
m25p16_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256);
|
m25p16_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -147,7 +148,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
||||||
{
|
{
|
||||||
int dieNumber = address / dieSize;
|
int dieNumber = address / dieSize;
|
||||||
|
|
||||||
w25m_dieSelect(fdevice->busdev, dieNumber);
|
w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
|
||||||
|
|
||||||
dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize);
|
dieDevice[dieNumber].vTable->eraseSector(&dieDevice[dieNumber], address % dieSize);
|
||||||
}
|
}
|
||||||
|
@ -155,7 +156,7 @@ void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
||||||
void w25m_eraseCompletely(flashDevice_t *fdevice)
|
void w25m_eraseCompletely(flashDevice_t *fdevice)
|
||||||
{
|
{
|
||||||
for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) {
|
for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) {
|
||||||
w25m_dieSelect(fdevice->busdev, dieNumber);
|
w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
|
||||||
dieDevice[dieNumber].vTable->eraseCompletely(&dieDevice[dieNumber]);
|
dieDevice[dieNumber].vTable->eraseCompletely(&dieDevice[dieNumber]);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -168,7 +169,7 @@ void w25m_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
|
||||||
UNUSED(fdevice);
|
UNUSED(fdevice);
|
||||||
|
|
||||||
currentWriteDie = address / dieSize;
|
currentWriteDie = address / dieSize;
|
||||||
w25m_dieSelect(fdevice->busdev, currentWriteDie);
|
w25m_dieSelect(fdevice->io.handle.busdev, currentWriteDie);
|
||||||
currentWriteAddress = address % dieSize;
|
currentWriteAddress = address % dieSize;
|
||||||
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], currentWriteAddress);
|
dieDevice[currentWriteDie].vTable->pageProgramBegin(&dieDevice[currentWriteDie], currentWriteAddress);
|
||||||
}
|
}
|
||||||
|
@ -210,7 +211,7 @@ int w25m_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, in
|
||||||
uint32_t dieAddress = address % dieSize;
|
uint32_t dieAddress = address % dieSize;
|
||||||
tlen = MIN(dieAddress + rlen, dieSize) - dieAddress;
|
tlen = MIN(dieAddress + rlen, dieSize) - dieAddress;
|
||||||
|
|
||||||
w25m_dieSelect(fdevice->busdev, dieNumber);
|
w25m_dieSelect(fdevice->io.handle.busdev, dieNumber);
|
||||||
|
|
||||||
rbytes = dieDevice[dieNumber].vTable->readBytes(&dieDevice[dieNumber], dieAddress, buffer, tlen);
|
rbytes = dieDevice[dieNumber].vTable->readBytes(&dieDevice[dieNumber], dieAddress, buffer, tlen);
|
||||||
|
|
||||||
|
|
927
src/main/drivers/flash_w25n01g.c
Normal file
927
src/main/drivers/flash_w25n01g.c
Normal file
|
@ -0,0 +1,927 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* Author: jflyper
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_W25N01G
|
||||||
|
|
||||||
|
#include "flash.h"
|
||||||
|
#include "flash_impl.h"
|
||||||
|
#include "flash_w25n01g.h"
|
||||||
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_quadspi.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
#include "drivers/time.h"
|
||||||
|
|
||||||
|
//#define FLASH_W25N01G_DPRINTF
|
||||||
|
|
||||||
|
#ifdef FLASH_W25N01G_DPRINTF
|
||||||
|
#include "common/printf.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
serialPort_t *debugSerialPort = NULL;
|
||||||
|
#define DPRINTF_SERIAL_PORT SERIAL_PORT_USART3
|
||||||
|
#define DPRINTF(x) tfp_printf x
|
||||||
|
#else
|
||||||
|
#define DPRINTF(x)
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// JEDEC ID
|
||||||
|
#define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21
|
||||||
|
|
||||||
|
// Device size parameters
|
||||||
|
#define W25N01G_PAGE_SIZE 2048
|
||||||
|
#define W25N01G_PAGES_PER_BLOCK 64
|
||||||
|
#define W25N01G_BLOCKS_PER_DIE 1024
|
||||||
|
|
||||||
|
// BB replacement area
|
||||||
|
#define W25N01G_BB_MARKER_BLOCKS 1
|
||||||
|
#define W25N01G_BB_REPLACEMENT_BLOCKS 20
|
||||||
|
#define W25N01G_BB_MANAGEMENT_BLOCKS (W25N01G_BB_REPLACEMENT_BLOCKS + W25N01G_BB_MARKER_BLOCKS)
|
||||||
|
// blocks are zero-based index
|
||||||
|
#define W25N01G_BB_REPLACEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_REPLACEMENT_BLOCKS)
|
||||||
|
#define W25N01G_BB_MANAGEMENT_START_BLOCK (W25N01G_BLOCKS_PER_DIE - W25N01G_BB_MANAGEMENT_BLOCKS)
|
||||||
|
#define W25N01G_BB_MARKER_BLOCK (W25N01G_BB_REPLACEMENT_START_BLOCK - W25N01G_BB_MARKER_BLOCKS)
|
||||||
|
|
||||||
|
// Instructions
|
||||||
|
|
||||||
|
#define W25N01G_INSTRUCTION_RDID 0x9F
|
||||||
|
#define W25N01G_INSTRUCTION_DEVICE_RESET 0xFF
|
||||||
|
#define W25N01G_INSTRUCTION_READ_STATUS_REG 0x05
|
||||||
|
#define W25N01G_INSTRUCTION_READ_STATUS_ALTERNATE_REG 0x0F
|
||||||
|
#define W25N01G_INSTRUCTION_WRITE_STATUS_REG 0x01
|
||||||
|
#define W25N01G_INSTRUCTION_WRITE_STATUS_ALTERNATE_REG 0x1F
|
||||||
|
#define W25N01G_INSTRUCTION_WRITE_ENABLE 0x06
|
||||||
|
#define W25N01G_INSTRUCTION_DIE_SELECT 0xC2
|
||||||
|
#define W25N01G_INSTRUCTION_BLOCK_ERASE 0xD8
|
||||||
|
#define W25N01G_INSTRUCTION_READ_BBM_LUT 0xA5
|
||||||
|
#define W25N01G_INSTRUCTION_BB_MANAGEMENT 0xA1
|
||||||
|
#define W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD 0x02
|
||||||
|
#define W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD 0x84
|
||||||
|
#define W25N01G_INSTRUCTION_PROGRAM_EXECUTE 0x10
|
||||||
|
#define W25N01G_INSTRUCTION_PAGE_DATA_READ 0x13
|
||||||
|
#define W25N01G_INSTRUCTION_READ_DATA 0x03
|
||||||
|
#define W25N01G_INSTRUCTION_FAST_READ 0x1B
|
||||||
|
#define W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT 0x6B
|
||||||
|
|
||||||
|
// Configu/status register addresses
|
||||||
|
#define W25N01G_PROT_REG 0xA0
|
||||||
|
#define W25N01G_CONF_REG 0xB0
|
||||||
|
#define W25N01G_STAT_REG 0xC0
|
||||||
|
|
||||||
|
// Bits in config/status register 2 (W25N01G_CONF_REG)
|
||||||
|
#define W25N01G_CONFIG_ECC_ENABLE (1 << 4)
|
||||||
|
#define W25N01G_CONFIG_BUFFER_READ_MODE (1 << 3)
|
||||||
|
|
||||||
|
// Bits in config/status register 3 (W25N01G_STATREG)
|
||||||
|
#define W25N01G_STATUS_BBM_LUT_FULL (1 << 6)
|
||||||
|
#define W25N01G_STATUS_FLAG_ECC_POS 4
|
||||||
|
#define W25N01G_STATUS_FLAG_ECC_MASK ((1 << 5)|(1 << 4))
|
||||||
|
#define W25N01G_STATUS_FLAG_ECC(status) (((status) & W25N01G_STATUS_FLAG_ECC_MASK) >> 4)
|
||||||
|
#define W25N01G_STATUS_PROGRAM_FAIL (1 << 3)
|
||||||
|
#define W25N01G_STATUS_ERASE_FAIL (1 << 2)
|
||||||
|
#define W25N01G_STATUS_FLAG_WRITE_ENABLED (1 << 1)
|
||||||
|
#define W25N01G_STATUS_FLAG_BUSY (1 << 0)
|
||||||
|
|
||||||
|
#define W25N01G_BBLUT_TABLE_ENTRY_COUNT 20
|
||||||
|
#define W25N01G_BBLUT_TABLE_ENTRY_SIZE 4 // in bytes
|
||||||
|
|
||||||
|
// Bits in LBA for BB LUT
|
||||||
|
#define W25N01G_BBLUT_STATUS_ENABLED (1 << 15)
|
||||||
|
#define W25N01G_BBLUT_STATUS_INVALID (1 << 14)
|
||||||
|
#define W25N01G_BBLUT_STATUS_MASK (W25N01G_BBLUT_STATUS_ENABLED | W25N01G_BBLUT_STATUS_INVALID)
|
||||||
|
|
||||||
|
// Some useful defs and macros
|
||||||
|
#define W25N01G_LINEAR_TO_COLUMN(laddr) ((laddr) % W25N01G_PAGE_SIZE)
|
||||||
|
#define W25N01G_LINEAR_TO_PAGE(laddr) ((laddr) / W25N01G_PAGE_SIZE)
|
||||||
|
#define W25N01G_LINEAR_TO_BLOCK(laddr) (W25N01G_LINEAR_TO_PAGE(laddr) / W25N01G_PAGES_PER_BLOCK)
|
||||||
|
#define W25N01G_BLOCK_TO_PAGE(block) ((block) * W25N01G_PAGES_PER_BLOCK)
|
||||||
|
#define W25N01G_BLOCK_TO_LINEAR(block) (W25N01G_BLOCK_TO_PAGE(block) * W25N01G_PAGE_SIZE)
|
||||||
|
|
||||||
|
// The timeout values (2ms minimum to avoid 1 tick advance in consecutive calls to millis).
|
||||||
|
#define W25N01G_TIMEOUT_PAGE_READ_MS 2 // tREmax = 60us (ECC enabled)
|
||||||
|
#define W25N01G_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us
|
||||||
|
#define W25N01G_TIMEOUT_BLOCK_ERASE_MS 15 // tBEmax = 10ms
|
||||||
|
#define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms
|
||||||
|
|
||||||
|
// Sizes (in bits)
|
||||||
|
#define W28N01G_STATUS_REGISTER_SIZE 8
|
||||||
|
#define W28N01G_STATUS_PAGE_ADDRESS_SIZE 16
|
||||||
|
#define W28N01G_STATUS_COLUMN_ADDRESS_SIZE 16
|
||||||
|
|
||||||
|
typedef struct bblut_s {
|
||||||
|
uint16_t pba;
|
||||||
|
uint16_t lba;
|
||||||
|
} bblut_t;
|
||||||
|
|
||||||
|
// These will be gone
|
||||||
|
|
||||||
|
#define DISABLE(busdev) IOHi((busdev)->busdev_u.spi.csnPin); __NOP()
|
||||||
|
#define ENABLE(busdev) __NOP(); IOLo((busdev)->busdev_u.spi.csnPin)
|
||||||
|
|
||||||
|
// XXX remove - add a forward declaration to keep git diff small while this is work-in-progress.
|
||||||
|
bool w25n01g_waitForReady(flashDevice_t *fdevice, uint32_t timeoutMillis);
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Send the given command byte to the device.
|
||||||
|
*/
|
||||||
|
static void w25n01g_performOneByteCommand(flashDeviceIO_t *io, uint8_t command)
|
||||||
|
{
|
||||||
|
if (io->mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = io->handle.busdev;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransferByte(busdev->busdev_u.spi.instance, command);
|
||||||
|
DISABLE(busdev);
|
||||||
|
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (io->mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
|
||||||
|
quadSpiTransmit1LINE(quadSpi, command, 0, NULL, 0);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t command, uint32_t pageAddress)
|
||||||
|
{
|
||||||
|
if (io->mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = io->handle.busdev;
|
||||||
|
|
||||||
|
const uint8_t cmd[] = { command, 0, (pageAddress >> 8) & 0xff, (pageAddress >> 0) & 0xff};
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
DISABLE(busdev);
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (io->mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
|
||||||
|
|
||||||
|
quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W28N01G_STATUS_PAGE_ADDRESS_SIZE + 8);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg)
|
||||||
|
{
|
||||||
|
if (io->mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = io->handle.busdev;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
const uint8_t cmd[3] = { W25N01G_INSTRUCTION_READ_STATUS_REG, reg, 0 };
|
||||||
|
uint8_t in[3];
|
||||||
|
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, in, sizeof(cmd));
|
||||||
|
DISABLE(busdev);
|
||||||
|
|
||||||
|
return in[2];
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (io->mode == FLASHIO_QUADSPI) {
|
||||||
|
|
||||||
|
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
|
||||||
|
|
||||||
|
uint8_t in[1];
|
||||||
|
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, in, sizeof(in));
|
||||||
|
|
||||||
|
return in[0];
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data)
|
||||||
|
{
|
||||||
|
if (io->mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = io->handle.busdev;
|
||||||
|
const uint8_t cmd[3] = { W25N01G_INSTRUCTION_WRITE_STATUS_REG, reg, data };
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
DISABLE(busdev);
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (io->mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = io->handle.quadSpi;
|
||||||
|
|
||||||
|
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, &data, 1);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
static void w25n01g_deviceReset(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
flashDeviceIO_t *io = &fdevice->io;
|
||||||
|
|
||||||
|
w25n01g_performOneByteCommand(io, W25N01G_INSTRUCTION_DEVICE_RESET);
|
||||||
|
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_RESET_MS);
|
||||||
|
|
||||||
|
// Protection for upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on; to protect bad block replacement area
|
||||||
|
// DON'T DO THIS. This will prevent writes through the bblut as well.
|
||||||
|
// w25n01g_writeRegister(busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1));
|
||||||
|
|
||||||
|
uint8_t value = (0 << 3)|(0 << 2); // No protection
|
||||||
|
|
||||||
|
if (io->mode == FLASHIO_SPI) {
|
||||||
|
value |= (1 << 1); // WP-E on
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (io->mode == FLASHIO_QUADSPI) {
|
||||||
|
value |= (0 << 1); // WP-E off, WP-E prevents use of IO2
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
w25n01g_writeRegister(io, W25N01G_PROT_REG, value);
|
||||||
|
|
||||||
|
// Buffered read mode (BUF = 1), ECC enabled (ECC = 1)
|
||||||
|
w25n01g_writeRegister(io, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE|W25N01G_CONFIG_BUFFER_READ_MODE);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool w25n01g_isReady(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
// XXX Study device busy behavior and reinstate couldBeBusy facility.
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
// If couldBeBusy is false, don't bother to poll the flash chip for its status
|
||||||
|
fdevice->couldBeBusy = fdevice->couldBeBusy && ((w25n01g_readRegister(fdevice->handle.busdev, W25N01G_STAT_REG) & W25N01G_STATUS_FLAG_BUSY) != 0);
|
||||||
|
|
||||||
|
return !couldBeBusy;
|
||||||
|
#else
|
||||||
|
uint8_t status = w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG);
|
||||||
|
|
||||||
|
if (status & W25N01G_STATUS_PROGRAM_FAIL) {
|
||||||
|
DPRINTF(("*** PROGRAM_FAIL\r\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
if (status & W25N01G_STATUS_ERASE_FAIL) {
|
||||||
|
DPRINTF(("*** ERASE_FAIL\r\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t eccCode;
|
||||||
|
if ((eccCode = W25N01G_STATUS_FLAG_ECC(status))) {
|
||||||
|
DPRINTF(("*** ECC %x\r\n", eccCode));
|
||||||
|
}
|
||||||
|
|
||||||
|
return ((status & W25N01G_STATUS_FLAG_BUSY) == 0);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
bool w25n01g_waitForReady(flashDevice_t *fdevice, uint32_t timeoutMillis)
|
||||||
|
{
|
||||||
|
uint32_t time = millis();
|
||||||
|
while (!w25n01g_isReady(fdevice)) {
|
||||||
|
if (millis() - time > timeoutMillis) {
|
||||||
|
DPRINTF(("*** TIMEOUT %d\r\n", timeoutMillis));
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* The flash requires this write enable command to be sent before commands that would cause
|
||||||
|
* a write like program and erase.
|
||||||
|
*/
|
||||||
|
static void w25n01g_writeEnable(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
w25n01g_performOneByteCommand(&fdevice->io, W25N01G_INSTRUCTION_WRITE_ENABLE);
|
||||||
|
|
||||||
|
// Assume that we're about to do some writing, so the device is just about to become busy
|
||||||
|
fdevice->couldBeBusy = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read chip identification and geometry information (into global `geometry`).
|
||||||
|
*
|
||||||
|
* Returns true if we get valid ident, false if something bad happened like there is no M25P16.
|
||||||
|
*/
|
||||||
|
const flashVTable_t w25n01g_vTable;
|
||||||
|
|
||||||
|
static void w25n01g_deviceInit(flashDevice_t *flashdev);
|
||||||
|
|
||||||
|
bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID)
|
||||||
|
{
|
||||||
|
#ifdef FLASH_W25N01G_DPRINTF
|
||||||
|
// Setup debugSerialPort
|
||||||
|
debugSerialPort = openSerialPort(DPRINTF_SERIAL_PORT, FUNCTION_NONE, NULL, NULL, 115200, MODE_RXTX, 0);
|
||||||
|
|
||||||
|
if (debugSerialPort) {
|
||||||
|
setPrintfSerialPort(debugSerialPort);
|
||||||
|
DPRINTF(("debug print init: OK\r\n"));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
switch (chipID) {
|
||||||
|
case JEDEC_ID_WINBOND_W25N01GV:
|
||||||
|
fdevice->geometry.sectors = 1024; // Blocks
|
||||||
|
fdevice->geometry.pagesPerSector = 64; // Pages/Blocks
|
||||||
|
fdevice->geometry.pageSize = 2048;
|
||||||
|
break;
|
||||||
|
|
||||||
|
default:
|
||||||
|
// Unsupported chip
|
||||||
|
fdevice->geometry.sectors = 0;
|
||||||
|
fdevice->geometry.pagesPerSector = 0;
|
||||||
|
|
||||||
|
fdevice->geometry.sectorSize = 0;
|
||||||
|
fdevice->geometry.totalSize = 0;
|
||||||
|
return false;
|
||||||
|
}
|
||||||
|
|
||||||
|
fdevice->geometry.flashType = FLASH_TYPE_NAND;
|
||||||
|
fdevice->geometry.sectorSize = fdevice->geometry.pagesPerSector * fdevice->geometry.pageSize;
|
||||||
|
fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors;
|
||||||
|
|
||||||
|
flashPartitionSet(FLASH_PARTITION_TYPE_BADBLOCK_MANAGEMENT,
|
||||||
|
W25N01G_BB_MANAGEMENT_START_BLOCK,
|
||||||
|
W25N01G_BB_MANAGEMENT_START_BLOCK + W25N01G_BB_MANAGEMENT_BLOCKS - 1);
|
||||||
|
|
||||||
|
fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be
|
||||||
|
|
||||||
|
w25n01g_deviceReset(fdevice);
|
||||||
|
|
||||||
|
// Upper 4MB (32 blocks * 128KB/block) will be used for bad block replacement area.
|
||||||
|
|
||||||
|
// Blocks in this area are only written through bad block LUT,
|
||||||
|
// and factory written bad block marker in unused blocks are retained.
|
||||||
|
|
||||||
|
// When a replacement block is required,
|
||||||
|
// (1) "Read BB LUT" command is used to obtain the last block mapped,
|
||||||
|
// (2) blocks after the last block is scanned for a good block,
|
||||||
|
// (3) the first good block is used for replacement, and the BB LUT is updated.
|
||||||
|
|
||||||
|
// There are only 20 BB LUT entries, and there are 32 replacement blocks.
|
||||||
|
// There will be a least chance of running out of replacement blocks.
|
||||||
|
// If it ever run out, the device becomes unusable.
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
// Protection to upper 1/32 (BP[3:0] = 0101, TB=0), WP-E on
|
||||||
|
//w25n01g_writeRegister(fdevice->handle.busdev, W25N01G_PROT_REG, (5 << 3)|(0 << 2)|(1 << 1));
|
||||||
|
|
||||||
|
// No protection, WP-E on
|
||||||
|
w25n01g_writeRegister(fdevice->handle, W25N01G_PROT_REG, (0 << 3)|(0 << 2)|(1 << 1));
|
||||||
|
|
||||||
|
// Continuous mode (BUF = 0), ECC enabled (ECC = 1)
|
||||||
|
w25n01g_writeRegister(fdevice->handle, W25N01G_CONF_REG, W25N01G_CONFIG_ECC_ENABLE);
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if 0
|
||||||
|
// XXX Should be gone in production
|
||||||
|
uint8_t sr1, sr2, sr3;
|
||||||
|
sr1 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_PROT_REG);
|
||||||
|
sr2 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_CONF_REG);
|
||||||
|
sr3 = w25n01g_readRegister(fdevice->handle.busdev, W25N01G_STAT_REG);
|
||||||
|
|
||||||
|
debug[1] = sr1;
|
||||||
|
debug[2] = sr2;
|
||||||
|
debug[3] = sr3;
|
||||||
|
|
||||||
|
DPRINTF(("Detect: PROT 0x%x CONF 0x%x STAT 0x%x\r\n", sr1 & 0xff, sr2 & 0xff, sr3 & 0xff));
|
||||||
|
#endif
|
||||||
|
|
||||||
|
w25n01g_deviceInit(fdevice);
|
||||||
|
|
||||||
|
fdevice->vTable = &w25n01g_vTable;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Erase a sector full of bytes to all 1's at the given byte offset in the flash chip.
|
||||||
|
*/
|
||||||
|
void w25n01g_eraseSector(flashDevice_t *fdevice, uint32_t address)
|
||||||
|
{
|
||||||
|
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_BLOCK_ERASE_MS);
|
||||||
|
|
||||||
|
w25n01g_writeEnable(fdevice);
|
||||||
|
|
||||||
|
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_BLOCK_ERASE, W25N01G_LINEAR_TO_PAGE(address));
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// W25N01G does not support full chip erase.
|
||||||
|
// Call eraseSector repeatedly.
|
||||||
|
|
||||||
|
void w25n01g_eraseCompletely(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
for (uint32_t block = 0; block < fdevice->geometry.sectors; block++) {
|
||||||
|
w25n01g_eraseSector(fdevice, W25N01G_BLOCK_TO_LINEAR(block));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
|
||||||
|
//DPRINTF((" load WaitForReady\r\n"));
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
|
||||||
|
//DPRINTF((" load Issuing command\r\n"));
|
||||||
|
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
const uint8_t cmd[] = { W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, data, NULL, length);
|
||||||
|
DISABLE(busdev);
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
//DPRINTF((" load Done\r\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t columnAddress, const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
const uint8_t cmd[] = { W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, columnAddress >> 8, columnAddress & 0xff };
|
||||||
|
|
||||||
|
//DPRINTF((" random WaitForReady\r\n"));
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
|
||||||
|
//DPRINTF((" random Issuing command\r\n"));
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, data, NULL, length);
|
||||||
|
DISABLE(busdev);
|
||||||
|
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
//DPRINTF((" random Done\r\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_programExecute(flashDevice_t *fdevice, uint32_t pageAddress)
|
||||||
|
{
|
||||||
|
//DPRINTF((" execute WaitForReady\r\n"));
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
|
||||||
|
//DPRINTF((" execute Issuing command\r\n"));
|
||||||
|
|
||||||
|
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PROGRAM_EXECUTE, pageAddress);
|
||||||
|
|
||||||
|
//DPRINTF((" execute Done\r\n"));
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// Writes are done in three steps:
|
||||||
|
// (1) Load internal data buffer with data to write
|
||||||
|
// - We use "Random Load Program Data", as "Load Program Data" resets unused data bytes in the buffer to 0xff.
|
||||||
|
// - Each "Random Load Program Data" instruction must be accompanied by at least a single data.
|
||||||
|
// - Each "Random Load Program Data" instruction terminates at the rising of CS.
|
||||||
|
// (2) Enable write
|
||||||
|
// (3) Issue "Execute Program"
|
||||||
|
//
|
||||||
|
|
||||||
|
/*
|
||||||
|
flashfs page program behavior
|
||||||
|
- Single program never crosses page boundary.
|
||||||
|
- Except for this characteristic, it program arbitral size.
|
||||||
|
- Write address is, naturally, not a page boundary.
|
||||||
|
|
||||||
|
To cope with this behavior.
|
||||||
|
|
||||||
|
pageProgramBegin:
|
||||||
|
If buffer is dirty and programLoadAddress != address, then the last page is a partial write;
|
||||||
|
issue PAGE_PROGRAM_EXECUTE to flash buffer contents, clear dirty and record the address as programLoadAddress and programStartAddress.
|
||||||
|
Else do nothing.
|
||||||
|
|
||||||
|
pageProgramContinue:
|
||||||
|
Mark buffer as dirty.
|
||||||
|
If programLoadAddress is on page boundary, then issue PROGRAM_LOAD_DATA, else issue RANDOM_PROGRAM_LOAD_DATA.
|
||||||
|
Update programLoadAddress.
|
||||||
|
Optionally observe the programLoadAddress, and if it's on page boundary, issue PAGE_PROGRAM_EXECUTE.
|
||||||
|
|
||||||
|
pageProgramFinish:
|
||||||
|
Observe programLoadAddress. If it's on page boundary, issue PAGE_PROGRAM_EXECUTE and clear dirty, else just return.
|
||||||
|
If pageProgramContinue observes the page boundary, then do nothing(?).
|
||||||
|
*/
|
||||||
|
|
||||||
|
static uint32_t programStartAddress;
|
||||||
|
static uint32_t programLoadAddress;
|
||||||
|
bool bufferDirty = false;
|
||||||
|
bool isProgramming = false;
|
||||||
|
|
||||||
|
#define DEBUG_PAGE_PROGRAM
|
||||||
|
|
||||||
|
//#define PAGEPROG_DPRINTF(x) DPRINTF(x)
|
||||||
|
#define PAGEPROG_DPRINTF(x)
|
||||||
|
|
||||||
|
void w25n01g_pageProgramBegin(flashDevice_t *fdevice, uint32_t address)
|
||||||
|
{
|
||||||
|
PAGEPROG_DPRINTF(("pageProgramBegin: address 0x%x\r\n", address));
|
||||||
|
|
||||||
|
if (bufferDirty) {
|
||||||
|
if (address != programLoadAddress) {
|
||||||
|
PAGEPROG_DPRINTF((" Buffer dirty and address != programLoadAddress (0x%x), flushing\r\n", programLoadAddress));
|
||||||
|
PAGEPROG_DPRINTF((" Wait for ready\r\n"));
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
|
||||||
|
isProgramming = false;
|
||||||
|
|
||||||
|
PAGEPROG_DPRINTF((" Write enable\r\n"));
|
||||||
|
w25n01g_writeEnable(fdevice);
|
||||||
|
|
||||||
|
PAGEPROG_DPRINTF((" PROGRAM_EXECUTE PA 0x%x\r\n", W25N01G_LINEAR_TO_PAGE(programStartAddress)));
|
||||||
|
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress));
|
||||||
|
|
||||||
|
bufferDirty = false;
|
||||||
|
isProgramming = true;
|
||||||
|
} else {
|
||||||
|
PAGEPROG_DPRINTF((" Continuation\r\n"));
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
PAGEPROG_DPRINTF((" Fresh page\r\n"));
|
||||||
|
programStartAddress = programLoadAddress = address;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void w25n01g_pageProgramContinue(flashDevice_t *fdevice, const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
PAGEPROG_DPRINTF(("pageProgramContinue: length 0x%x (programLoadAddress 0x%x)\r\n", length, programLoadAddress));
|
||||||
|
|
||||||
|
// Check for page boundary overrun
|
||||||
|
|
||||||
|
if (W25N01G_LINEAR_TO_PAGE(programLoadAddress + length - 1) != W25N01G_LINEAR_TO_PAGE(programStartAddress)) {
|
||||||
|
PAGEPROG_DPRINTF((" **** PAGE BOUNDARY OVERRUN **** (page 0x%x)\r\n", W25N01G_LINEAR_TO_PAGE(programLoadAddress)));
|
||||||
|
}
|
||||||
|
|
||||||
|
PAGEPROG_DPRINTF((" Wait for ready\r\n"));
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
|
||||||
|
PAGEPROG_DPRINTF((" Write enable\r\n"));
|
||||||
|
w25n01g_writeEnable(fdevice);
|
||||||
|
|
||||||
|
isProgramming = false;
|
||||||
|
|
||||||
|
if (!bufferDirty) {
|
||||||
|
PAGEPROG_DPRINTF((" DATA_LOAD CA 0x%x length 0x%x\r\n", W25N01G_LINEAR_TO_COLUMN(programLoadAddress), length));
|
||||||
|
w25n01g_programDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), data, length);
|
||||||
|
} else {
|
||||||
|
PAGEPROG_DPRINTF((" RANDOM_DATA_LOAD CA 0x%x length 0x%x\r\n", W25N01G_LINEAR_TO_COLUMN(programLoadAddress), length));
|
||||||
|
w25n01g_randomProgramDataLoad(fdevice, W25N01G_LINEAR_TO_COLUMN(programLoadAddress), data, length);
|
||||||
|
}
|
||||||
|
|
||||||
|
// XXX Test if write enable is reset after each data loading.
|
||||||
|
|
||||||
|
bufferDirty = true;
|
||||||
|
programLoadAddress += length;
|
||||||
|
}
|
||||||
|
|
||||||
|
static uint32_t currentPage = UINT32_MAX;
|
||||||
|
|
||||||
|
void w25n01g_pageProgramFinish(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
PAGEPROG_DPRINTF(("pageProgramFinish: (loaded 0x%x bytes)\r\n", programLoadAddress - programStartAddress));
|
||||||
|
|
||||||
|
if (bufferDirty && W25N01G_LINEAR_TO_COLUMN(programLoadAddress) == 0) {
|
||||||
|
|
||||||
|
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
|
||||||
|
|
||||||
|
PAGEPROG_DPRINTF((" PROGRAM_EXECUTE PA 0x%x\r\n", W25N01G_LINEAR_TO_PAGE(programStartAddress)));
|
||||||
|
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress));
|
||||||
|
|
||||||
|
bufferDirty = false;
|
||||||
|
isProgramming = true;
|
||||||
|
|
||||||
|
programStartAddress = programLoadAddress;
|
||||||
|
} else {
|
||||||
|
PAGEPROG_DPRINTF((" Ignoring\r\n"));
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Write bytes to a flash page. Address must not cross a page boundary.
|
||||||
|
*
|
||||||
|
* Bits can only be set to zero, not from zero back to one again. In order to set bits to 1, use the erase command.
|
||||||
|
*
|
||||||
|
* Length must be smaller than the page size.
|
||||||
|
*
|
||||||
|
* This will wait for the flash to become ready before writing begins.
|
||||||
|
*
|
||||||
|
* Datasheet indicates typical programming time is 0.8ms for 256 bytes, 0.2ms for 64 bytes, 0.05ms for 16 bytes.
|
||||||
|
* (Although the maximum possible write time is noted as 5ms).
|
||||||
|
*
|
||||||
|
* If you want to write multiple buffers (whose sum of sizes is still not more than the page size) then you can
|
||||||
|
* break this operation up into one beginProgram call, one or more continueProgram calls, and one finishProgram call.
|
||||||
|
*/
|
||||||
|
|
||||||
|
void w25n01g_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, int length)
|
||||||
|
{
|
||||||
|
w25n01g_pageProgramBegin(fdevice, address);
|
||||||
|
w25n01g_pageProgramContinue(fdevice, data, length);
|
||||||
|
w25n01g_pageProgramFinish(fdevice);
|
||||||
|
}
|
||||||
|
|
||||||
|
void w25n01g_flush(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
PAGEPROG_DPRINTF(("close:\r\n"));
|
||||||
|
|
||||||
|
if (bufferDirty) {
|
||||||
|
PAGEPROG_DPRINTF((" Buffer is partially loaded (0x%x bytes)\r\n", programLoadAddress - programStartAddress));
|
||||||
|
PAGEPROG_DPRINTF((" PROGRAM_EXECUTE PA 0x%x\r\n", W25N01G_LINEAR_TO_PAGE(programStartAddress)));
|
||||||
|
|
||||||
|
currentPage = W25N01G_LINEAR_TO_PAGE(programStartAddress); // reset page to the page being written
|
||||||
|
|
||||||
|
w25n01g_programExecute(fdevice, W25N01G_LINEAR_TO_PAGE(programStartAddress));
|
||||||
|
|
||||||
|
bufferDirty = false;
|
||||||
|
isProgramming = true;
|
||||||
|
} else {
|
||||||
|
PAGEPROG_DPRINTF((" Buffer is clean\r\n"));
|
||||||
|
isProgramming = false;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
void w25n01g_addError(uint32_t address, uint8_t code)
|
||||||
|
{
|
||||||
|
UNUSED(address);
|
||||||
|
UNUSED(code);
|
||||||
|
DPRINTF(("addError: PA %x BA %x code %d\r\n", W25N01G_LINEAR_TO_PAGE(address), W25N01G_LINEAR_TO_BLOCK(address), code));
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Read `length` bytes into the provided `buffer` from the flash starting from the given `address` (which need not lie
|
||||||
|
* on a page boundary).
|
||||||
|
*
|
||||||
|
* Waits up to W25N01G_TIMEOUT_PAGE_READ_MS milliseconds for the flash to become ready before reading.
|
||||||
|
*
|
||||||
|
* The number of bytes actually read is returned, which can be zero if an error or timeout occurred.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Continuous read mode (BUF = 0):
|
||||||
|
// (1) "Page Data Read" command is executed for the page pointed by address
|
||||||
|
// (2) "Read Data" command is executed for bytes not requested and data are discarded
|
||||||
|
// (3) "Read Data" command is executed and data are stored directly into caller's buffer
|
||||||
|
//
|
||||||
|
// Buffered read mode (BUF = 1), non-read ahead
|
||||||
|
// (1) If currentBufferPage != requested page, then issue PAGE_DATA_READ on requested page.
|
||||||
|
// (2) Compute transferLength as smaller of remaining length and requested length.
|
||||||
|
// (3) Issue READ_DATA on column address.
|
||||||
|
// (4) Return transferLength.
|
||||||
|
|
||||||
|
//#define READBYTES_DPRINTF DPRINTF
|
||||||
|
#define READBYTES_DPRINTF(x)
|
||||||
|
|
||||||
|
int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
|
||||||
|
{
|
||||||
|
READBYTES_DPRINTF(("readBytes: address 0x%x length %d\r\n", address, length));
|
||||||
|
|
||||||
|
uint32_t targetPage = W25N01G_LINEAR_TO_PAGE(address);
|
||||||
|
|
||||||
|
if (currentPage != targetPage) {
|
||||||
|
READBYTES_DPRINTF(("readBytes: PAGE_DATA_READ page 0x%x\r\n", targetPage));
|
||||||
|
|
||||||
|
|
||||||
|
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
currentPage = UINT32_MAX;
|
||||||
|
|
||||||
|
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, targetPage);
|
||||||
|
|
||||||
|
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
currentPage = targetPage;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t column = W25N01G_LINEAR_TO_COLUMN(address);
|
||||||
|
uint16_t transferLength;
|
||||||
|
|
||||||
|
if (length > W25N01G_PAGE_SIZE - column) {
|
||||||
|
transferLength = W25N01G_PAGE_SIZE - column;
|
||||||
|
} else {
|
||||||
|
transferLength = length;
|
||||||
|
}
|
||||||
|
|
||||||
|
READBYTES_DPRINTF(("readBytes: READ_DATA column 0x%x transferLength 0x%x\r\n", column, transferLength));
|
||||||
|
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
|
||||||
|
uint8_t cmd[4];
|
||||||
|
cmd[0] = W25N01G_INSTRUCTION_READ_DATA;
|
||||||
|
cmd[1] = (column >> 8) & 0xff;
|
||||||
|
cmd[2] = (column >> 0) & 0xff;
|
||||||
|
cmd[3] = 0;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, NULL, buffer, length);
|
||||||
|
DISABLE(busdev);
|
||||||
|
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
//quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
|
||||||
|
quadSpiReceiveWithAddress4LINES(quadSpi, W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// XXX Don't need this?
|
||||||
|
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
// Check ECC
|
||||||
|
|
||||||
|
uint8_t statReg = w25n01g_readRegister(&fdevice->io, W25N01G_STAT_REG);
|
||||||
|
uint8_t eccCode = W25N01G_STATUS_FLAG_ECC(statReg);
|
||||||
|
|
||||||
|
switch (eccCode) {
|
||||||
|
case 0: // Successful read, no ECC correction
|
||||||
|
break;
|
||||||
|
case 1: // Successful read with ECC correction
|
||||||
|
case 2: // Uncorrectable ECC in a single page
|
||||||
|
case 3: // Uncorrectable ECC in multiple pages
|
||||||
|
w25n01g_addError(address, eccCode);
|
||||||
|
w25n01g_deviceReset(fdevice);
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
READBYTES_DPRINTF(("readBytes: transfered 0x%x bytes\r\n", transferLength));
|
||||||
|
|
||||||
|
return transferLength;
|
||||||
|
}
|
||||||
|
|
||||||
|
int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, int length)
|
||||||
|
{
|
||||||
|
|
||||||
|
w25n01g_performCommandWithPageAddress(&fdevice->io, W25N01G_INSTRUCTION_PAGE_DATA_READ, W25N01G_LINEAR_TO_PAGE(address));
|
||||||
|
|
||||||
|
if (!w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_READ_MS)) {
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t column = 2048;
|
||||||
|
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
|
||||||
|
uint8_t cmd[4];
|
||||||
|
cmd[0] = W25N01G_INSTRUCTION_READ_DATA;
|
||||||
|
cmd[1] = (column >> 8) & 0xff;
|
||||||
|
cmd[2] = (column >> 0) & 0xff;
|
||||||
|
cmd[3] = 0;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, NULL, buffer, length);
|
||||||
|
DISABLE(busdev);
|
||||||
|
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
return length;
|
||||||
|
}
|
||||||
|
|
||||||
|
/**
|
||||||
|
* Fetch information about the detected flash chip layout.
|
||||||
|
*
|
||||||
|
* Can be called before calling w25n01g_init() (the result would have totalSize = 0).
|
||||||
|
*/
|
||||||
|
const flashGeometry_t* w25n01g_getGeometry(flashDevice_t *fdevice)
|
||||||
|
{
|
||||||
|
return &fdevice->geometry;
|
||||||
|
}
|
||||||
|
|
||||||
|
const flashVTable_t w25n01g_vTable = {
|
||||||
|
.isReady = w25n01g_isReady,
|
||||||
|
.waitForReady = w25n01g_waitForReady,
|
||||||
|
.eraseSector = w25n01g_eraseSector,
|
||||||
|
.eraseCompletely = w25n01g_eraseCompletely,
|
||||||
|
.pageProgramBegin = w25n01g_pageProgramBegin,
|
||||||
|
.pageProgramContinue = w25n01g_pageProgramContinue,
|
||||||
|
.pageProgramFinish = w25n01g_pageProgramFinish,
|
||||||
|
.pageProgram = w25n01g_pageProgram,
|
||||||
|
.flush = w25n01g_flush,
|
||||||
|
.readBytes = w25n01g_readBytes,
|
||||||
|
.getGeometry = w25n01g_getGeometry,
|
||||||
|
};
|
||||||
|
|
||||||
|
void w25n01g_readBBLUT(flashDevice_t *fdevice, bblut_t *bblut, int lutsize)
|
||||||
|
{
|
||||||
|
|
||||||
|
uint8_t in[4];
|
||||||
|
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
|
||||||
|
uint8_t cmd[4];
|
||||||
|
|
||||||
|
cmd[0] = W25N01G_INSTRUCTION_READ_BBM_LUT;
|
||||||
|
cmd[1] = 0;
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, 2);
|
||||||
|
|
||||||
|
for (int i = 0 ; i < lutsize ; i++) {
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, NULL, in, 4);
|
||||||
|
bblut[i].pba = (in[0] << 16)|in[1];
|
||||||
|
bblut[i].lba = (in[2] << 16)|in[3];
|
||||||
|
}
|
||||||
|
|
||||||
|
DISABLE(busdev);
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
// Note: Using HAL QuadSPI there doesn't appear to be a way to send 2 bytes, then blocks of 4 bytes, while keeping the CS line LOW
|
||||||
|
// thus, we have to read the entire BBLUT in one go and process the result.
|
||||||
|
|
||||||
|
uint8_t bblutBuffer[W25N01G_BBLUT_TABLE_ENTRY_COUNT * W25N01G_BBLUT_TABLE_ENTRY_SIZE];
|
||||||
|
quadSpiReceive1LINE(quadSpi, W25N01G_INSTRUCTION_READ_BBM_LUT, 8, bblutBuffer, sizeof(bblutBuffer));
|
||||||
|
|
||||||
|
for (int i = 0, offset = 0 ; i < lutsize ; i++, offset += 4) {
|
||||||
|
if (i < W25N01G_BBLUT_TABLE_ENTRY_COUNT) {
|
||||||
|
bblut[i].pba = (in[offset + 0] << 16)|in[offset + 1];
|
||||||
|
bblut[i].lba = (in[offset + 2] << 16)|in[offset + 3];
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
|
void w25n01g_writeBBLUT(flashDevice_t *fdevice, uint16_t lba, uint16_t pba)
|
||||||
|
{
|
||||||
|
if (fdevice->io.mode == FLASHIO_SPI) {
|
||||||
|
busDevice_t *busdev = fdevice->io.handle.busdev;
|
||||||
|
|
||||||
|
uint8_t cmd[5] = { W25N01G_INSTRUCTION_BB_MANAGEMENT, lba >> 8, lba, pba >> 8, pba };
|
||||||
|
|
||||||
|
ENABLE(busdev);
|
||||||
|
spiTransfer(busdev->busdev_u.spi.instance, cmd, NULL, sizeof(cmd));
|
||||||
|
DISABLE(busdev);
|
||||||
|
}
|
||||||
|
#ifdef USE_QUADSPI
|
||||||
|
else if (fdevice->io.mode == FLASHIO_QUADSPI) {
|
||||||
|
QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi;
|
||||||
|
|
||||||
|
uint8_t data[4] = { lba >> 8, lba, pba >> 8, pba };
|
||||||
|
quadSpiInstructionWithData1LINE(quadSpi, W25N01G_INSTRUCTION_BB_MANAGEMENT, 0, data, sizeof(data));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
w25n01g_waitForReady(fdevice, W25N01G_TIMEOUT_PAGE_PROGRAM_MS);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void w25n01g_deviceInit(flashDevice_t *flashdev)
|
||||||
|
{
|
||||||
|
UNUSED(flashdev);
|
||||||
|
}
|
||||||
|
#endif
|
25
src/main/drivers/flash_w25n01g.h
Normal file
25
src/main/drivers/flash_w25n01g.h
Normal file
|
@ -0,0 +1,25 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
|
* Author: jflyper
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID);
|
|
@ -41,6 +41,7 @@
|
||||||
#include "fc/rc.h"
|
#include "fc/rc.h"
|
||||||
#include "fc/rc_adjustments.h"
|
#include "fc/rc_adjustments.h"
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
#include "flight/failsafe.h"
|
#include "flight/failsafe.h"
|
||||||
#include "flight/imu.h"
|
#include "flight/imu.h"
|
||||||
|
@ -72,6 +73,8 @@
|
||||||
|
|
||||||
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
|
static bool configIsDirty; /* someone indicated that the config is modified and it is not yet saved */
|
||||||
|
|
||||||
|
static bool rebootRequired = false; // set if a config change requires a reboot to take effect
|
||||||
|
|
||||||
pidProfile_t *currentPidProfile;
|
pidProfile_t *currentPidProfile;
|
||||||
|
|
||||||
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
#ifndef RX_SPI_DEFAULT_PROTOCOL
|
||||||
|
@ -742,3 +745,14 @@ bool isSystemConfigured(void)
|
||||||
return true;
|
return true;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setRebootRequired(void)
|
||||||
|
{
|
||||||
|
rebootRequired = true;
|
||||||
|
setArmingDisabled(ARMING_DISABLED_REBOOT_REQUIRED);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool getRebootRequired(void)
|
||||||
|
{
|
||||||
|
return rebootRequired;
|
||||||
|
}
|
||||||
|
|
|
@ -55,6 +55,7 @@ PG_DECLARE(systemConfig_t, systemConfig);
|
||||||
struct pidProfile_s;
|
struct pidProfile_s;
|
||||||
extern struct pidProfile_s *currentPidProfile;
|
extern struct pidProfile_s *currentPidProfile;
|
||||||
|
|
||||||
|
|
||||||
void initEEPROM(void);
|
void initEEPROM(void);
|
||||||
void resetEEPROM(void);
|
void resetEEPROM(void);
|
||||||
bool readEEPROM(void);
|
bool readEEPROM(void);
|
||||||
|
@ -86,3 +87,5 @@ void targetConfiguration(void);
|
||||||
void targetValidateConfiguration(void);
|
void targetValidateConfiguration(void);
|
||||||
|
|
||||||
bool isSystemConfigured(void);
|
bool isSystemConfigured(void);
|
||||||
|
void setRebootRequired(void);
|
||||||
|
bool getRebootRequired(void);
|
||||||
|
|
|
@ -27,6 +27,7 @@
|
||||||
typedef enum {
|
typedef enum {
|
||||||
RATES_TYPE_BETAFLIGHT = 0,
|
RATES_TYPE_BETAFLIGHT = 0,
|
||||||
RATES_TYPE_RACEFLIGHT,
|
RATES_TYPE_RACEFLIGHT,
|
||||||
|
RATES_TYPE_KISS,
|
||||||
} ratesType_e;
|
} ratesType_e;
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
|
|
@ -716,11 +716,9 @@ void init(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef USE_FLASH_CHIP
|
#ifdef USE_FLASH_CHIP
|
||||||
bool haveFlash = flashInit(flashConfig());
|
flashInit(flashConfig());
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
if (haveFlash) {
|
flashfsInit();
|
||||||
flashfsInit();
|
|
||||||
}
|
|
||||||
#endif
|
#endif
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -148,6 +148,17 @@ float applyRaceFlightRates(const int axis, float rcCommandf, const float rcComma
|
||||||
return angleRate;
|
return angleRate;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
float applyKissRates(const int axis, float rcCommandf, const float rcCommandfAbs)
|
||||||
|
{
|
||||||
|
const float rcCurvef = currentControlRateProfile->rcExpo[axis] / 100.0f;
|
||||||
|
|
||||||
|
float kissRpyUseRates = 1.0f / (constrainf(1.0f - (rcCommandfAbs * (currentControlRateProfile->rates[axis] / 100.0f)), 0.01f, 1.00f));
|
||||||
|
float kissRcCommandf = (power3(rcCommandf) * rcCurvef + rcCommandf * (1 - rcCurvef)) * (currentControlRateProfile->rcRates[axis] / 1000.0f);
|
||||||
|
float kissAngle = constrainf(((2000.0f * kissRpyUseRates) * kissRcCommandf), -SETPOINT_RATE_LIMIT, SETPOINT_RATE_LIMIT);
|
||||||
|
|
||||||
|
return kissAngle;
|
||||||
|
}
|
||||||
|
|
||||||
static void calculateSetpointRate(int axis)
|
static void calculateSetpointRate(int axis)
|
||||||
{
|
{
|
||||||
float angleRate;
|
float angleRate;
|
||||||
|
@ -286,10 +297,10 @@ FAST_CODE uint8_t processRcInterpolation(void)
|
||||||
#ifdef USE_RC_SMOOTHING_FILTER
|
#ifdef USE_RC_SMOOTHING_FILTER
|
||||||
// Determine a cutoff frequency based on filter type and the calculated
|
// Determine a cutoff frequency based on filter type and the calculated
|
||||||
// average rx frame time
|
// average rx frame time
|
||||||
FAST_CODE_NOINLINE int calcRcSmoothingCutoff(int avgRxFrameTimeUs, bool pt1)
|
FAST_CODE_NOINLINE int calcRcSmoothingCutoff(int avgRxFrameTimeUs, bool pt1, uint8_t autoSmoothnessFactor)
|
||||||
{
|
{
|
||||||
if (avgRxFrameTimeUs > 0) {
|
if (avgRxFrameTimeUs > 0) {
|
||||||
const float cutoffFactor = (100 - rxConfig()->rc_smoothing_auto_factor) / 100.0f;
|
const float cutoffFactor = (100 - autoSmoothnessFactor) / 100.0f;
|
||||||
float cutoff = (1 / (avgRxFrameTimeUs * 1e-6f)) / 2; // calculate the nyquist frequency
|
float cutoff = (1 / (avgRxFrameTimeUs * 1e-6f)) / 2; // calculate the nyquist frequency
|
||||||
cutoff = cutoff * cutoffFactor;
|
cutoff = cutoff * cutoffFactor;
|
||||||
|
|
||||||
|
@ -316,15 +327,15 @@ FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothi
|
||||||
const float dT = targetPidLooptime * 1e-6f;
|
const float dT = targetPidLooptime * 1e-6f;
|
||||||
uint16_t oldCutoff = smoothingData->inputCutoffFrequency;
|
uint16_t oldCutoff = smoothingData->inputCutoffFrequency;
|
||||||
|
|
||||||
if (rxConfig()->rc_smoothing_input_cutoff == 0) {
|
if (smoothingData->inputCutoffSetting == 0) {
|
||||||
smoothingData->inputCutoffFrequency = calcRcSmoothingCutoff(smoothingData->averageFrameTimeUs, (rxConfig()->rc_smoothing_input_type == RC_SMOOTHING_INPUT_PT1));
|
smoothingData->inputCutoffFrequency = calcRcSmoothingCutoff(smoothingData->averageFrameTimeUs, (smoothingData->inputFilterType == RC_SMOOTHING_INPUT_PT1), smoothingData->autoSmoothnessFactor);
|
||||||
}
|
}
|
||||||
|
|
||||||
// initialize or update the input filter
|
// initialize or update the input filter
|
||||||
if ((smoothingData->inputCutoffFrequency != oldCutoff) || !smoothingData->filterInitialized) {
|
if ((smoothingData->inputCutoffFrequency != oldCutoff) || !smoothingData->filterInitialized) {
|
||||||
for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < PRIMARY_CHANNEL_COUNT; i++) {
|
||||||
if ((1 << i) & interpolationChannels) { // only update channels specified by rc_interp_ch
|
if ((1 << i) & interpolationChannels) { // only update channels specified by rc_interp_ch
|
||||||
switch (rxConfig()->rc_smoothing_input_type) {
|
switch (smoothingData->inputFilterType) {
|
||||||
|
|
||||||
case RC_SMOOTHING_INPUT_PT1:
|
case RC_SMOOTHING_INPUT_PT1:
|
||||||
if (!smoothingData->filterInitialized) {
|
if (!smoothingData->filterInitialized) {
|
||||||
|
@ -349,12 +360,12 @@ FAST_CODE_NOINLINE void rcSmoothingSetFilterCutoffs(rcSmoothingFilter_t *smoothi
|
||||||
|
|
||||||
// update or initialize the derivative filter
|
// update or initialize the derivative filter
|
||||||
oldCutoff = smoothingData->derivativeCutoffFrequency;
|
oldCutoff = smoothingData->derivativeCutoffFrequency;
|
||||||
if ((rxConfig()->rc_smoothing_derivative_cutoff == 0) && (rxConfig()->rc_smoothing_derivative_type != RC_SMOOTHING_DERIVATIVE_OFF)) {
|
if ((smoothingData->derivativeCutoffSetting == 0) && (smoothingData->derivativeFilterType != RC_SMOOTHING_DERIVATIVE_OFF)) {
|
||||||
smoothingData->derivativeCutoffFrequency = calcRcSmoothingCutoff(smoothingData->averageFrameTimeUs, (rxConfig()->rc_smoothing_derivative_type == RC_SMOOTHING_DERIVATIVE_PT1));
|
smoothingData->derivativeCutoffFrequency = calcRcSmoothingCutoff(smoothingData->averageFrameTimeUs, (smoothingData->derivativeFilterType == RC_SMOOTHING_DERIVATIVE_PT1), smoothingData->autoSmoothnessFactor);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (!smoothingData->filterInitialized) {
|
if (!smoothingData->filterInitialized) {
|
||||||
pidInitSetpointDerivativeLpf(smoothingData->derivativeCutoffFrequency, rxConfig()->rc_smoothing_debug_axis, rxConfig()->rc_smoothing_derivative_type);
|
pidInitSetpointDerivativeLpf(smoothingData->derivativeCutoffFrequency, smoothingData->debugAxis, smoothingData->derivativeFilterType);
|
||||||
} else if (smoothingData->derivativeCutoffFrequency != oldCutoff) {
|
} else if (smoothingData->derivativeCutoffFrequency != oldCutoff) {
|
||||||
pidUpdateSetpointDerivativeLpf(smoothingData->derivativeCutoffFrequency);
|
pidUpdateSetpointDerivativeLpf(smoothingData->derivativeCutoffFrequency);
|
||||||
}
|
}
|
||||||
|
@ -395,13 +406,13 @@ FAST_CODE_NOINLINE bool rcSmoothingAutoCalculate(void)
|
||||||
bool ret = false;
|
bool ret = false;
|
||||||
|
|
||||||
// if the input cutoff is 0 (auto) then we need to calculate cutoffs
|
// if the input cutoff is 0 (auto) then we need to calculate cutoffs
|
||||||
if (rxConfig()->rc_smoothing_input_cutoff == 0) {
|
if (rcSmoothingData.inputCutoffSetting == 0) {
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
|
|
||||||
// if the derivative type isn't OFF and the cutoff is 0 then we need to calculate
|
// if the derivative type isn't OFF and the cutoff is 0 then we need to calculate
|
||||||
if (rxConfig()->rc_smoothing_derivative_type != RC_SMOOTHING_DERIVATIVE_OFF) {
|
if (rcSmoothingData.derivativeFilterType != RC_SMOOTHING_DERIVATIVE_OFF) {
|
||||||
if (rxConfig()->rc_smoothing_derivative_cutoff == 0) {
|
if (rcSmoothingData.derivativeCutoffSetting == 0) {
|
||||||
ret = true;
|
ret = true;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -421,12 +432,18 @@ FAST_CODE uint8_t processRcSmoothingFilter(void)
|
||||||
initialized = true;
|
initialized = true;
|
||||||
rcSmoothingData.filterInitialized = false;
|
rcSmoothingData.filterInitialized = false;
|
||||||
rcSmoothingData.averageFrameTimeUs = 0;
|
rcSmoothingData.averageFrameTimeUs = 0;
|
||||||
|
rcSmoothingData.autoSmoothnessFactor = rxConfig()->rc_smoothing_auto_factor;
|
||||||
|
rcSmoothingData.debugAxis = rxConfig()->rc_smoothing_debug_axis;
|
||||||
|
rcSmoothingData.inputFilterType = rxConfig()->rc_smoothing_input_type;
|
||||||
|
rcSmoothingData.inputCutoffSetting = rxConfig()->rc_smoothing_input_cutoff;
|
||||||
|
rcSmoothingData.derivativeFilterType = rxConfig()->rc_smoothing_derivative_type;
|
||||||
|
rcSmoothingData.derivativeCutoffSetting = rxConfig()->rc_smoothing_derivative_cutoff;
|
||||||
rcSmoothingResetAccumulation(&rcSmoothingData);
|
rcSmoothingResetAccumulation(&rcSmoothingData);
|
||||||
|
|
||||||
rcSmoothingData.inputCutoffFrequency = rxConfig()->rc_smoothing_input_cutoff;
|
rcSmoothingData.inputCutoffFrequency = rcSmoothingData.inputCutoffSetting;
|
||||||
|
|
||||||
if (rxConfig()->rc_smoothing_derivative_type != RC_SMOOTHING_DERIVATIVE_OFF) {
|
if (rcSmoothingData.derivativeFilterType != RC_SMOOTHING_DERIVATIVE_OFF) {
|
||||||
rcSmoothingData.derivativeCutoffFrequency = rxConfig()->rc_smoothing_derivative_cutoff;
|
rcSmoothingData.derivativeCutoffFrequency = rcSmoothingData.derivativeCutoffSetting;
|
||||||
}
|
}
|
||||||
|
|
||||||
calculateCutoffs = rcSmoothingAutoCalculate();
|
calculateCutoffs = rcSmoothingAutoCalculate();
|
||||||
|
@ -511,7 +528,7 @@ FAST_CODE uint8_t processRcSmoothingFilter(void)
|
||||||
if (rcSmoothingData.filterInitialized && (debugMode == DEBUG_RC_SMOOTHING)) {
|
if (rcSmoothingData.filterInitialized && (debugMode == DEBUG_RC_SMOOTHING)) {
|
||||||
// after training has completed then log the raw rc channel and the calculated
|
// after training has completed then log the raw rc channel and the calculated
|
||||||
// average rx frame rate that was used to calculate the automatic filter cutoffs
|
// average rx frame rate that was used to calculate the automatic filter cutoffs
|
||||||
DEBUG_SET(DEBUG_RC_SMOOTHING, 0, lrintf(lastRxData[rxConfig()->rc_smoothing_debug_axis]));
|
DEBUG_SET(DEBUG_RC_SMOOTHING, 0, lrintf(lastRxData[rcSmoothingData.debugAxis]));
|
||||||
DEBUG_SET(DEBUG_RC_SMOOTHING, 3, rcSmoothingData.averageFrameTimeUs);
|
DEBUG_SET(DEBUG_RC_SMOOTHING, 3, rcSmoothingData.averageFrameTimeUs);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -519,7 +536,7 @@ FAST_CODE uint8_t processRcSmoothingFilter(void)
|
||||||
for (updatedChannel = 0; updatedChannel < PRIMARY_CHANNEL_COUNT; updatedChannel++) {
|
for (updatedChannel = 0; updatedChannel < PRIMARY_CHANNEL_COUNT; updatedChannel++) {
|
||||||
if ((1 << updatedChannel) & interpolationChannels) { // only smooth selected channels base on the rc_interp_ch value
|
if ((1 << updatedChannel) & interpolationChannels) { // only smooth selected channels base on the rc_interp_ch value
|
||||||
if (rcSmoothingData.filterInitialized) {
|
if (rcSmoothingData.filterInitialized) {
|
||||||
switch (rxConfig()->rc_smoothing_input_type) {
|
switch (rcSmoothingData.inputFilterType) {
|
||||||
case RC_SMOOTHING_INPUT_PT1:
|
case RC_SMOOTHING_INPUT_PT1:
|
||||||
rcCommand[updatedChannel] = pt1FilterApply((pt1Filter_t*) &rcSmoothingData.filter[updatedChannel], lastRxData[updatedChannel]);
|
rcCommand[updatedChannel] = pt1FilterApply((pt1Filter_t*) &rcSmoothingData.filter[updatedChannel], lastRxData[updatedChannel]);
|
||||||
break;
|
break;
|
||||||
|
@ -711,6 +728,10 @@ void initRcProcessing(void)
|
||||||
case RATES_TYPE_RACEFLIGHT:
|
case RATES_TYPE_RACEFLIGHT:
|
||||||
applyRates = applyRaceFlightRates;
|
applyRates = applyRaceFlightRates;
|
||||||
|
|
||||||
|
break;
|
||||||
|
case RATES_TYPE_KISS:
|
||||||
|
applyRates = applyKissRates;
|
||||||
|
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -749,18 +770,9 @@ bool rcSmoothingIsEnabled(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_RC_SMOOTHING_FILTER
|
#ifdef USE_RC_SMOOTHING_FILTER
|
||||||
int rcSmoothingGetValue(int whichValue)
|
rcSmoothingFilter_t *getRcSmoothingData(void)
|
||||||
{
|
{
|
||||||
switch (whichValue) {
|
return &rcSmoothingData;
|
||||||
case RC_SMOOTHING_VALUE_INPUT_ACTIVE:
|
|
||||||
return rcSmoothingData.inputCutoffFrequency;
|
|
||||||
case RC_SMOOTHING_VALUE_DERIVATIVE_ACTIVE:
|
|
||||||
return rcSmoothingData.derivativeCutoffFrequency;
|
|
||||||
case RC_SMOOTHING_VALUE_AVERAGE_FRAME:
|
|
||||||
return rcSmoothingData.averageFrameTimeUs;
|
|
||||||
default:
|
|
||||||
return 0;
|
|
||||||
}
|
|
||||||
}
|
}
|
||||||
|
|
||||||
bool rcSmoothingInitializationComplete(void) {
|
bool rcSmoothingInitializationComplete(void) {
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
INTERPOLATION_CHANNELS_RP,
|
INTERPOLATION_CHANNELS_RP,
|
||||||
INTERPOLATION_CHANNELS_RPY,
|
INTERPOLATION_CHANNELS_RPY,
|
||||||
|
@ -40,6 +42,6 @@ void resetYawAxis(void);
|
||||||
void initRcProcessing(void);
|
void initRcProcessing(void);
|
||||||
bool isMotorsReversed(void);
|
bool isMotorsReversed(void);
|
||||||
bool rcSmoothingIsEnabled(void);
|
bool rcSmoothingIsEnabled(void);
|
||||||
int rcSmoothingGetValue(int whichValue);
|
rcSmoothingFilter_t *getRcSmoothingData(void);
|
||||||
bool rcSmoothingAutoCalculate(void);
|
bool rcSmoothingAutoCalculate(void);
|
||||||
bool rcSmoothingInitializationComplete(void);
|
bool rcSmoothingInitializationComplete(void);
|
||||||
|
|
|
@ -77,12 +77,6 @@ typedef enum {
|
||||||
RC_SMOOTHING_DERIVATIVE_BIQUAD
|
RC_SMOOTHING_DERIVATIVE_BIQUAD
|
||||||
} rcSmoothingDerivativeFilter_e;
|
} rcSmoothingDerivativeFilter_e;
|
||||||
|
|
||||||
typedef enum {
|
|
||||||
RC_SMOOTHING_VALUE_INPUT_ACTIVE,
|
|
||||||
RC_SMOOTHING_VALUE_DERIVATIVE_ACTIVE,
|
|
||||||
RC_SMOOTHING_VALUE_AVERAGE_FRAME
|
|
||||||
} rcSmoothingInfoType_e;
|
|
||||||
|
|
||||||
#define ROL_LO (1 << (2 * ROLL))
|
#define ROL_LO (1 << (2 * ROLL))
|
||||||
#define ROL_CE (3 << (2 * ROLL))
|
#define ROL_CE (3 << (2 * ROLL))
|
||||||
#define ROL_HI (2 << (2 * ROLL))
|
#define ROL_HI (2 << (2 * ROLL))
|
||||||
|
@ -125,10 +119,16 @@ typedef union rcSmoothingFilterTypes_u {
|
||||||
typedef struct rcSmoothingFilter_s {
|
typedef struct rcSmoothingFilter_s {
|
||||||
bool filterInitialized;
|
bool filterInitialized;
|
||||||
rcSmoothingFilterTypes_t filter[4];
|
rcSmoothingFilterTypes_t filter[4];
|
||||||
|
rcSmoothingInputFilter_e inputFilterType;
|
||||||
|
uint8_t inputCutoffSetting;
|
||||||
uint16_t inputCutoffFrequency;
|
uint16_t inputCutoffFrequency;
|
||||||
|
rcSmoothingDerivativeFilter_e derivativeFilterType;
|
||||||
|
uint8_t derivativeCutoffSetting;
|
||||||
uint16_t derivativeCutoffFrequency;
|
uint16_t derivativeCutoffFrequency;
|
||||||
int averageFrameTimeUs;
|
int averageFrameTimeUs;
|
||||||
rcSmoothingFilterTraining_t training;
|
rcSmoothingFilterTraining_t training;
|
||||||
|
uint8_t debugAxis;
|
||||||
|
uint8_t autoSmoothnessFactor;
|
||||||
} rcSmoothingFilter_t;
|
} rcSmoothingFilter_t;
|
||||||
|
|
||||||
typedef struct rcControlsConfig_s {
|
typedef struct rcControlsConfig_s {
|
||||||
|
|
|
@ -53,8 +53,9 @@ const char *armingDisableFlagNames[]= {
|
||||||
"MSP",
|
"MSP",
|
||||||
"PARALYZE",
|
"PARALYZE",
|
||||||
"GPS",
|
"GPS",
|
||||||
"RESCUE SW",
|
"RESCUE_SW",
|
||||||
"RPMFILTER",
|
"RPMFILTER",
|
||||||
|
"REBOOT_REQD",
|
||||||
"ARMSWITCH",
|
"ARMSWITCH",
|
||||||
};
|
};
|
||||||
|
|
||||||
|
|
|
@ -61,7 +61,8 @@ typedef enum {
|
||||||
ARMING_DISABLED_GPS = (1 << 18),
|
ARMING_DISABLED_GPS = (1 << 18),
|
||||||
ARMING_DISABLED_RESC = (1 << 19),
|
ARMING_DISABLED_RESC = (1 << 19),
|
||||||
ARMING_DISABLED_RPMFILTER = (1 << 20),
|
ARMING_DISABLED_RPMFILTER = (1 << 20),
|
||||||
ARMING_DISABLED_ARM_SWITCH = (1 << 21), // Needs to be the last element, since it's always activated if one of the others is active when arming
|
ARMING_DISABLED_REBOOT_REQUIRED = (1 << 21),
|
||||||
|
ARMING_DISABLED_ARM_SWITCH = (1 << 22), // Needs to be the last element, since it's always activated if one of the others is active when arming
|
||||||
} armingDisableFlags_e;
|
} armingDisableFlags_e;
|
||||||
|
|
||||||
#define ARMING_DISABLE_FLAGS_COUNT (LOG2(ARMING_DISABLED_ARM_SWITCH) + 1)
|
#define ARMING_DISABLE_FLAGS_COUNT (LOG2(ARMING_DISABLED_ARM_SWITCH) + 1)
|
||||||
|
|
|
@ -116,6 +116,12 @@ typedef struct {
|
||||||
bool isAvailable;
|
bool isAvailable;
|
||||||
} rescueState_s;
|
} rescueState_s;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
MAX_ALT,
|
||||||
|
FIXED_ALT,
|
||||||
|
CURRENT_ALT
|
||||||
|
} altitudeMode_e;
|
||||||
|
|
||||||
#define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate
|
#define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate
|
||||||
#define GPS_RESCUE_RATE_SCALE_DEGREES 45 // Scale the commanded yaw rate when the error is less then this angle
|
#define GPS_RESCUE_RATE_SCALE_DEGREES 45 // Scale the commanded yaw rate when the error is less then this angle
|
||||||
#define GPS_RESCUE_SLOWDOWN_DISTANCE_M 200 // distance from home to start decreasing speed
|
#define GPS_RESCUE_SLOWDOWN_DISTANCE_M 200 // distance from home to start decreasing speed
|
||||||
|
@ -150,6 +156,7 @@ PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig,
|
||||||
.useMag = GPS_RESCUE_USE_MAG,
|
.useMag = GPS_RESCUE_USE_MAG,
|
||||||
.targetLandingAltitudeM = 5,
|
.targetLandingAltitudeM = 5,
|
||||||
.targetLandingDistanceM = 10,
|
.targetLandingDistanceM = 10,
|
||||||
|
.altitudeMode = MAX_ALT,
|
||||||
);
|
);
|
||||||
|
|
||||||
static uint16_t rescueThrottle;
|
static uint16_t rescueThrottle;
|
||||||
|
@ -165,6 +172,7 @@ bool magForceDisable = false;
|
||||||
static bool newGPSData = false;
|
static bool newGPSData = false;
|
||||||
|
|
||||||
rescueState_s rescueState;
|
rescueState_s rescueState;
|
||||||
|
altitudeMode_e altitudeMode;
|
||||||
|
|
||||||
/*
|
/*
|
||||||
If we have new GPS data, update home heading
|
If we have new GPS data, update home heading
|
||||||
|
@ -486,6 +494,7 @@ void updateGPSRescueState(void)
|
||||||
static float_t lineSlope;
|
static float_t lineSlope;
|
||||||
static float_t lineOffsetM;
|
static float_t lineOffsetM;
|
||||||
static int32_t newSpeed;
|
static int32_t newSpeed;
|
||||||
|
static uint32_t newAltitude;
|
||||||
|
|
||||||
if (!FLIGHT_MODE(GPS_RESCUE_MODE)) {
|
if (!FLIGHT_MODE(GPS_RESCUE_MODE)) {
|
||||||
rescueStop();
|
rescueStop();
|
||||||
|
@ -536,6 +545,18 @@ void updateGPSRescueState(void)
|
||||||
newDescentDistanceM = gpsRescueConfig()->descentDistanceM;
|
newDescentDistanceM = gpsRescueConfig()->descentDistanceM;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
switch (altitudeMode) {
|
||||||
|
case MAX_ALT:
|
||||||
|
newAltitude = MAX(gpsRescueConfig()->initialAltitudeM * 100, rescueState.sensor.maxAltitudeCm + 1500);
|
||||||
|
break;
|
||||||
|
case FIXED_ALT:
|
||||||
|
newAltitude = gpsRescueConfig()->initialAltitudeM * 100;
|
||||||
|
break;
|
||||||
|
case CURRENT_ALT:
|
||||||
|
newAltitude = rescueState.sensor.currentAltitudeCm;
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
//Calculate angular coefficient and offset for equation of line from 2 points needed for RESCUE_LANDING_APPROACH
|
//Calculate angular coefficient and offset for equation of line from 2 points needed for RESCUE_LANDING_APPROACH
|
||||||
lineSlope = ((float)gpsRescueConfig()->initialAltitudeM - gpsRescueConfig()->targetLandingAltitudeM) / (newDescentDistanceM - gpsRescueConfig()->targetLandingDistanceM);
|
lineSlope = ((float)gpsRescueConfig()->initialAltitudeM - gpsRescueConfig()->targetLandingAltitudeM) / (newDescentDistanceM - gpsRescueConfig()->targetLandingDistanceM);
|
||||||
lineOffsetM = gpsRescueConfig()->initialAltitudeM - lineSlope * newDescentDistanceM;
|
lineOffsetM = gpsRescueConfig()->initialAltitudeM - lineSlope * newDescentDistanceM;
|
||||||
|
@ -549,7 +570,7 @@ void updateGPSRescueState(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
rescueState.intent.targetGroundspeed = 500;
|
rescueState.intent.targetGroundspeed = 500;
|
||||||
rescueState.intent.targetAltitudeCm = MAX(gpsRescueConfig()->initialAltitudeM * 100, rescueState.sensor.maxAltitudeCm + 1500);
|
rescueState.intent.targetAltitudeCm = newAltitude;
|
||||||
rescueState.intent.crosstrack = true;
|
rescueState.intent.crosstrack = true;
|
||||||
rescueState.intent.minAngleDeg = 10;
|
rescueState.intent.minAngleDeg = 10;
|
||||||
rescueState.intent.maxAngleDeg = 15;
|
rescueState.intent.maxAngleDeg = 15;
|
||||||
|
@ -562,7 +583,7 @@ void updateGPSRescueState(void)
|
||||||
// We can assume at this point that we are at or above our RTH height, so we need to try and point to home and tilt while maintaining alt
|
// We can assume at this point that we are at or above our RTH height, so we need to try and point to home and tilt while maintaining alt
|
||||||
// Is our altitude way off? We should probably kick back to phase RESCUE_ATTAIN_ALT
|
// Is our altitude way off? We should probably kick back to phase RESCUE_ATTAIN_ALT
|
||||||
rescueState.intent.targetGroundspeed = gpsRescueConfig()->rescueGroundspeed;
|
rescueState.intent.targetGroundspeed = gpsRescueConfig()->rescueGroundspeed;
|
||||||
rescueState.intent.targetAltitudeCm = MAX(gpsRescueConfig()->initialAltitudeM * 100, rescueState.sensor.maxAltitudeCm + 1500);
|
rescueState.intent.targetAltitudeCm = newAltitude;
|
||||||
rescueState.intent.crosstrack = true;
|
rescueState.intent.crosstrack = true;
|
||||||
rescueState.intent.minAngleDeg = 15;
|
rescueState.intent.minAngleDeg = 15;
|
||||||
rescueState.intent.maxAngleDeg = gpsRescueConfig()->angle;
|
rescueState.intent.maxAngleDeg = gpsRescueConfig()->angle;
|
||||||
|
|
|
@ -39,6 +39,7 @@ typedef struct gpsRescue_s {
|
||||||
uint8_t useMag;
|
uint8_t useMag;
|
||||||
uint16_t targetLandingAltitudeM; //meters
|
uint16_t targetLandingAltitudeM; //meters
|
||||||
uint16_t targetLandingDistanceM; //meters
|
uint16_t targetLandingDistanceM; //meters
|
||||||
|
uint8_t altitudeMode;
|
||||||
} gpsRescueConfig_t;
|
} gpsRescueConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
|
PG_DECLARE(gpsRescueConfig_t, gpsRescueConfig);
|
||||||
|
|
|
@ -185,11 +185,11 @@ void resetPidProfile(pidProfile_t *pidProfile)
|
||||||
// overridden and the static lowpass 1 is disabled. We can't set this
|
// overridden and the static lowpass 1 is disabled. We can't set this
|
||||||
// value to 0 otherwise Configurator versions 10.4 and earlier will also
|
// value to 0 otherwise Configurator versions 10.4 and earlier will also
|
||||||
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
|
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
|
||||||
.dterm_lowpass2_hz = 100, // second Dterm LPF ON by default
|
.dterm_lowpass2_hz = 150, // second Dterm LPF ON by default
|
||||||
.dterm_filter_type = FILTER_BIQUAD,
|
.dterm_filter_type = FILTER_BIQUAD,
|
||||||
.dterm_filter2_type = FILTER_PT1,
|
.dterm_filter2_type = FILTER_PT1,
|
||||||
.dyn_lpf_dterm_min_hz = 150,
|
.dyn_lpf_dterm_min_hz = 70,
|
||||||
.dyn_lpf_dterm_max_hz = 250,
|
.dyn_lpf_dterm_max_hz = 170,
|
||||||
.launchControlMode = LAUNCH_CONTROL_MODE_NORMAL,
|
.launchControlMode = LAUNCH_CONTROL_MODE_NORMAL,
|
||||||
.launchControlThrottlePercent = 20,
|
.launchControlThrottlePercent = 20,
|
||||||
.launchControlAngleLimit = 0,
|
.launchControlAngleLimit = 0,
|
||||||
|
|
|
@ -58,7 +58,7 @@
|
||||||
#define ONLY_EXPOSE_FOR_TESTING static
|
#define ONLY_EXPOSE_FOR_TESTING static
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define AFATFS_NUM_CACHE_SECTORS 8
|
#define AFATFS_NUM_CACHE_SECTORS 10
|
||||||
|
|
||||||
// FAT filesystems are allowed to differ from these parameters, but we choose not to support those weird filesystems:
|
// FAT filesystems are allowed to differ from these parameters, but we choose not to support those weird filesystems:
|
||||||
#define AFATFS_SECTOR_SIZE 512
|
#define AFATFS_SECTOR_SIZE 512
|
||||||
|
|
|
@ -1,18 +1,21 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
|
@ -1,18 +1,21 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
|
@ -38,10 +38,15 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "common/printf.h"
|
||||||
#include "drivers/flash.h"
|
#include "drivers/flash.h"
|
||||||
|
|
||||||
#include "io/flashfs.h"
|
#include "io/flashfs.h"
|
||||||
|
|
||||||
|
static const flashPartition_t *flashPartition = NULL;
|
||||||
|
static const flashGeometry_t *flashGeometry = NULL;
|
||||||
|
static uint32_t flashfsSize = 0;
|
||||||
|
|
||||||
static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
|
static uint8_t flashWriteBuffer[FLASHFS_WRITE_BUFFER_SIZE];
|
||||||
|
|
||||||
/* The position of our head and tail in the circular flash write buffer.
|
/* The position of our head and tail in the circular flash write buffer.
|
||||||
|
@ -73,7 +78,10 @@ static void flashfsSetTailAddress(uint32_t address)
|
||||||
|
|
||||||
void flashfsEraseCompletely(void)
|
void flashfsEraseCompletely(void)
|
||||||
{
|
{
|
||||||
flashEraseCompletely();
|
for (flashSector_t sectorIndex = flashPartition->startSector; sectorIndex <= flashPartition->endSector; sectorIndex++) {
|
||||||
|
uint32_t sectorAddress = sectorIndex * flashGeometry->sectorSize;
|
||||||
|
flashEraseSector(sectorAddress);
|
||||||
|
}
|
||||||
|
|
||||||
flashfsClearBuffer();
|
flashfsClearBuffer();
|
||||||
|
|
||||||
|
@ -86,24 +94,23 @@ void flashfsEraseCompletely(void)
|
||||||
*/
|
*/
|
||||||
void flashfsEraseRange(uint32_t start, uint32_t end)
|
void flashfsEraseRange(uint32_t start, uint32_t end)
|
||||||
{
|
{
|
||||||
const flashGeometry_t *geometry = flashGetGeometry();
|
if (flashGeometry->sectorSize <= 0)
|
||||||
|
|
||||||
if (geometry->sectorSize <= 0)
|
|
||||||
return;
|
return;
|
||||||
|
|
||||||
// Round the start down to a sector boundary
|
// Round the start down to a sector boundary
|
||||||
int startSector = start / geometry->sectorSize;
|
int startSector = start / flashGeometry->sectorSize;
|
||||||
|
|
||||||
// And the end upward
|
// And the end upward
|
||||||
int endSector = end / geometry->sectorSize;
|
int endSector = end / flashGeometry->sectorSize;
|
||||||
int endRemainder = end % geometry->sectorSize;
|
int endRemainder = end % flashGeometry->sectorSize;
|
||||||
|
|
||||||
if (endRemainder > 0) {
|
if (endRemainder > 0) {
|
||||||
endSector++;
|
endSector++;
|
||||||
}
|
}
|
||||||
|
|
||||||
for (int i = startSector; i < endSector; i++) {
|
for (int sectorIndex = startSector; sectorIndex < endSector; sectorIndex++) {
|
||||||
flashEraseSector(i * geometry->sectorSize);
|
uint32_t sectorAddress = sectorIndex * flashGeometry->sectorSize;
|
||||||
|
flashEraseSector(sectorAddress);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -119,12 +126,12 @@ bool flashfsIsReady(void)
|
||||||
|
|
||||||
bool flashfsIsSupported(void)
|
bool flashfsIsSupported(void)
|
||||||
{
|
{
|
||||||
return flashfsGetSize() > 0;
|
return flashfsSize > 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t flashfsGetSize(void)
|
uint32_t flashfsGetSize(void)
|
||||||
{
|
{
|
||||||
return flashGetGeometry()->totalSize;
|
return flashfsSize;
|
||||||
}
|
}
|
||||||
|
|
||||||
static uint32_t flashfsTransmitBufferUsed(void)
|
static uint32_t flashfsTransmitBufferUsed(void)
|
||||||
|
@ -151,11 +158,6 @@ uint32_t flashfsGetWriteBufferFreeSpace(void)
|
||||||
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
|
return flashfsGetWriteBufferSize() - flashfsTransmitBufferUsed();
|
||||||
}
|
}
|
||||||
|
|
||||||
const flashGeometry_t* flashfsGetGeometry(void)
|
|
||||||
{
|
|
||||||
return flashGetGeometry();
|
|
||||||
}
|
|
||||||
|
|
||||||
/**
|
/**
|
||||||
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
|
* Write the given buffers to flash sequentially at the current tail address, advancing the tail address after
|
||||||
* each write.
|
* each write.
|
||||||
|
@ -191,7 +193,7 @@ static uint32_t flashfsWriteBuffers(uint8_t const **buffers, uint32_t *bufferSiz
|
||||||
|
|
||||||
uint32_t bytesTotalRemaining = bytesTotal;
|
uint32_t bytesTotalRemaining = bytesTotal;
|
||||||
|
|
||||||
uint16_t pageSize = flashfsGetGeometry()->pageSize;
|
uint16_t pageSize = flashGeometry->pageSize;
|
||||||
|
|
||||||
while (bytesTotalRemaining > 0) {
|
while (bytesTotalRemaining > 0) {
|
||||||
uint32_t bytesTotalThisIteration;
|
uint32_t bytesTotalThisIteration;
|
||||||
|
@ -481,9 +483,9 @@ int flashfsReadAbs(uint32_t address, uint8_t *buffer, unsigned int len)
|
||||||
int bytesRead;
|
int bytesRead;
|
||||||
|
|
||||||
// Did caller try to read past the end of the volume?
|
// Did caller try to read past the end of the volume?
|
||||||
if (address + len > flashfsGetSize()) {
|
if (address + len > flashfsSize) {
|
||||||
// Truncate their request
|
// Truncate their request
|
||||||
len = flashfsGetSize() - address;
|
len = flashfsSize - address;
|
||||||
}
|
}
|
||||||
|
|
||||||
// Since the read could overlap data in our dirty buffers, force a sync to clear those first
|
// Since the read could overlap data in our dirty buffers, force a sync to clear those first
|
||||||
|
@ -527,7 +529,7 @@ int flashfsIdentifyStartOfFreeSpace(void)
|
||||||
} testBuffer;
|
} testBuffer;
|
||||||
|
|
||||||
int left = 0; // Smallest block index in the search region
|
int left = 0; // Smallest block index in the search region
|
||||||
int right = flashfsGetSize() / FREE_BLOCK_SIZE; // One past the largest block index in the search region
|
int right = flashfsSize / FREE_BLOCK_SIZE; // One past the largest block index in the search region
|
||||||
int mid;
|
int mid;
|
||||||
int result = right;
|
int result = right;
|
||||||
int i;
|
int i;
|
||||||
|
@ -570,12 +572,12 @@ int flashfsIdentifyStartOfFreeSpace(void)
|
||||||
*/
|
*/
|
||||||
bool flashfsIsEOF(void)
|
bool flashfsIsEOF(void)
|
||||||
{
|
{
|
||||||
return tailAddress >= flashfsGetSize();
|
return tailAddress >= flashfsSize;
|
||||||
}
|
}
|
||||||
|
|
||||||
void flashfsClose(void)
|
void flashfsClose(void)
|
||||||
{
|
{
|
||||||
switch(flashfsGetGeometry()->flashType) {
|
switch(flashGeometry->flashType) {
|
||||||
case FLASH_TYPE_NOR:
|
case FLASH_TYPE_NOR:
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -583,7 +585,7 @@ void flashfsClose(void)
|
||||||
flashFlush();
|
flashFlush();
|
||||||
|
|
||||||
// Advance tailAddress to next page boundary.
|
// Advance tailAddress to next page boundary.
|
||||||
uint32_t pageSize = flashfsGetGeometry()->pageSize;
|
uint32_t pageSize = flashGeometry->pageSize;
|
||||||
flashfsSetTailAddress((tailAddress + pageSize - 1) & ~(pageSize - 1));
|
flashfsSetTailAddress((tailAddress + pageSize - 1) & ~(pageSize - 1));
|
||||||
|
|
||||||
break;
|
break;
|
||||||
|
@ -595,9 +597,58 @@ void flashfsClose(void)
|
||||||
*/
|
*/
|
||||||
void flashfsInit(void)
|
void flashfsInit(void)
|
||||||
{
|
{
|
||||||
// If we have a flash chip present at all
|
flashfsSize = 0;
|
||||||
if (flashfsGetSize() > 0) {
|
|
||||||
// Start the file pointer off at the beginning of free space so caller can start writing immediately
|
flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
|
||||||
flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
|
flashGeometry = flashGetGeometry();
|
||||||
|
|
||||||
|
if (!flashPartition) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
flashfsSize = FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize;
|
||||||
|
|
||||||
|
// Start the file pointer off at the beginning of free space so caller can start writing immediately
|
||||||
|
flashfsSeekAbs(flashfsIdentifyStartOfFreeSpace());
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef USE_FLASH_TOOLS
|
||||||
|
bool flashfsVerifyEntireFlash(void)
|
||||||
|
{
|
||||||
|
flashfsEraseCompletely();
|
||||||
|
flashfsInit();
|
||||||
|
|
||||||
|
uint32_t address = 0;
|
||||||
|
flashfsSeekAbs(address);
|
||||||
|
|
||||||
|
const int bufferSize = 32;
|
||||||
|
char buffer[bufferSize + 1];
|
||||||
|
|
||||||
|
const uint32_t testLimit = flashfsGetSize();
|
||||||
|
|
||||||
|
for (address = 0; address < testLimit; address += bufferSize) {
|
||||||
|
tfp_sprintf(buffer, "%08x >> **0123456789ABCDEF**", address);
|
||||||
|
flashfsWrite((uint8_t*)buffer, strlen(buffer), true);
|
||||||
|
}
|
||||||
|
flashfsFlushSync();
|
||||||
|
flashfsClose();
|
||||||
|
|
||||||
|
char expectedBuffer[bufferSize + 1];
|
||||||
|
|
||||||
|
flashfsSeekAbs(0);
|
||||||
|
|
||||||
|
int verificationFailures = 0;
|
||||||
|
for (address = 0; address < testLimit; address += bufferSize) {
|
||||||
|
tfp_sprintf(expectedBuffer, "%08x >> **0123456789ABCDEF**", address);
|
||||||
|
|
||||||
|
memset(buffer, 0, sizeof(buffer));
|
||||||
|
int bytesRead = flashfsReadAbs(address, (uint8_t *)buffer, bufferSize);
|
||||||
|
|
||||||
|
int result = strncmp(buffer, expectedBuffer, bufferSize);
|
||||||
|
if (result != 0 || bytesRead != bufferSize) {
|
||||||
|
verificationFailures++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return verificationFailures == 0;
|
||||||
|
}
|
||||||
|
#endif // USE_FLASH_TOOLS
|
||||||
|
|
|
@ -54,3 +54,6 @@ bool flashfsIsSupported(void);
|
||||||
|
|
||||||
bool flashfsIsReady(void);
|
bool flashfsIsReady(void);
|
||||||
bool flashfsIsEOF(void);
|
bool flashfsIsEOF(void);
|
||||||
|
|
||||||
|
bool flashfsVerifyEntireFlash(void);
|
||||||
|
|
||||||
|
|
|
@ -1,20 +1,22 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
*/
|
*
|
||||||
/*
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*
|
||||||
* Author: Chris Hockuba (https://github.com/conkerkh)
|
* Author: Chris Hockuba (https://github.com/conkerkh)
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
|
|
@ -1,21 +1,23 @@
|
||||||
/*
|
/*
|
||||||
* This file is part of Cleanflight.
|
* This file is part of Cleanflight and Betaflight.
|
||||||
*
|
*
|
||||||
* Cleanflight is free software: you can redistribute it and/or modify
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
* it under the terms of the GNU General Public License as published by
|
* this software and/or modify this software under the terms of the
|
||||||
* the Free Software Foundation, either version 3 of the License, or
|
* GNU General Public License as published by the Free Software
|
||||||
* (at your option) any later version.
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
*
|
*
|
||||||
* Cleanflight is distributed in the hope that it will be useful,
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
* GNU General Public License for more details.
|
* See the GNU General Public License for more details.
|
||||||
*
|
*
|
||||||
* You should have received a copy of the GNU General Public License
|
* You should have received a copy of the GNU General Public License
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
*
|
*
|
||||||
* Author: jflyper (https://github.com/jflyper)
|
* Author: jflyper (https://github.com/jflyper)
|
||||||
*
|
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
|
@ -241,6 +241,14 @@ static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr
|
||||||
}
|
}
|
||||||
#endif //USE_SERIAL_4WAY_BLHELI_INTERFACE
|
#endif //USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
|
||||||
|
static void configRebootUpdateCheckU8(uint8_t *parm, uint8_t value)
|
||||||
|
{
|
||||||
|
if (*parm != value) {
|
||||||
|
setRebootRequired();
|
||||||
|
}
|
||||||
|
*parm = value;
|
||||||
|
}
|
||||||
|
|
||||||
static void mspRebootFn(serialPort_t *serialPort)
|
static void mspRebootFn(serialPort_t *serialPort)
|
||||||
{
|
{
|
||||||
UNUSED(serialPort);
|
UNUSED(serialPort);
|
||||||
|
@ -337,10 +345,12 @@ static void serializeDataflashSummaryReply(sbuf_t *dst)
|
||||||
if (flashfsIsSupported()) {
|
if (flashfsIsSupported()) {
|
||||||
uint8_t flags = MSP_FLASHFS_FLAG_SUPPORTED;
|
uint8_t flags = MSP_FLASHFS_FLAG_SUPPORTED;
|
||||||
flags |= (flashfsIsReady() ? MSP_FLASHFS_FLAG_READY : 0);
|
flags |= (flashfsIsReady() ? MSP_FLASHFS_FLAG_READY : 0);
|
||||||
const flashGeometry_t *geometry = flashfsGetGeometry();
|
|
||||||
|
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
|
||||||
|
|
||||||
sbufWriteU8(dst, flags);
|
sbufWriteU8(dst, flags);
|
||||||
sbufWriteU32(dst, geometry->sectors);
|
sbufWriteU32(dst, FLASH_PARTITION_SECTOR_COUNT(flashPartition));
|
||||||
sbufWriteU32(dst, geometry->totalSize);
|
sbufWriteU32(dst, flashfsGetSize());
|
||||||
sbufWriteU32(dst, flashfsGetOffset()); // Effectively the current number of bytes stored on the volume
|
sbufWriteU32(dst, flashfsGetOffset()); // Effectively the current number of bytes stored on the volume
|
||||||
} else
|
} else
|
||||||
#endif
|
#endif
|
||||||
|
@ -860,6 +870,10 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
|
||||||
// 4 bytes, flags
|
// 4 bytes, flags
|
||||||
const uint32_t armingDisableFlags = getArmingDisableFlags();
|
const uint32_t armingDisableFlags = getArmingDisableFlags();
|
||||||
sbufWriteU32(dst, armingDisableFlags);
|
sbufWriteU32(dst, armingDisableFlags);
|
||||||
|
|
||||||
|
// config state flags - bits to indicate the state of the configuration, reboot required, etc.
|
||||||
|
// other flags can be added as needed
|
||||||
|
sbufWriteU8(dst, (getRebootRequired() << 0));
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
|
||||||
|
@ -2342,7 +2356,7 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
case MSP_DATAFLASH_ERASE:
|
case MSP_DATAFLASH_ERASE:
|
||||||
flashfsEraseCompletely();
|
flashfsEraseCompletely();
|
||||||
flashfsInit();
|
|
||||||
break;
|
break;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -2431,11 +2445,11 @@ static mspResult_e mspProcessInCommand(uint8_t cmdMSP, sbuf_t *src)
|
||||||
// Added in MSP API 1.40
|
// Added in MSP API 1.40
|
||||||
rxConfigMutable()->rcInterpolationChannels = sbufReadU8(src);
|
rxConfigMutable()->rcInterpolationChannels = sbufReadU8(src);
|
||||||
#if defined(USE_RC_SMOOTHING_FILTER)
|
#if defined(USE_RC_SMOOTHING_FILTER)
|
||||||
rxConfigMutable()->rc_smoothing_type = sbufReadU8(src);
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_type, sbufReadU8(src));
|
||||||
rxConfigMutable()->rc_smoothing_input_cutoff = sbufReadU8(src);
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_input_cutoff, sbufReadU8(src));
|
||||||
rxConfigMutable()->rc_smoothing_derivative_cutoff = sbufReadU8(src);
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_derivative_cutoff, sbufReadU8(src));
|
||||||
rxConfigMutable()->rc_smoothing_input_type = sbufReadU8(src);
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_input_type, sbufReadU8(src));
|
||||||
rxConfigMutable()->rc_smoothing_derivative_type = sbufReadU8(src);
|
configRebootUpdateCheckU8(&rxConfigMutable()->rc_smoothing_derivative_type, sbufReadU8(src));
|
||||||
#else
|
#else
|
||||||
sbufReadU8(src);
|
sbufReadU8(src);
|
||||||
sbufReadU8(src);
|
sbufReadU8(src);
|
||||||
|
|
|
@ -345,7 +345,7 @@ static void osdResetStats(void)
|
||||||
stats.max_g_force = 0;
|
stats.max_g_force = 0;
|
||||||
stats.max_esc_temp = 0;
|
stats.max_esc_temp = 0;
|
||||||
stats.max_esc_rpm = 0;
|
stats.max_esc_rpm = 0;
|
||||||
stats.min_link_quality = 99; // percent
|
stats.min_link_quality = (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) ? 300 : 99; // CRSF : percent
|
||||||
}
|
}
|
||||||
|
|
||||||
static void osdUpdateStats(void)
|
static void osdUpdateStats(void)
|
||||||
|
@ -436,8 +436,11 @@ static void osdGetBlackboxStatusString(char * buff)
|
||||||
#ifdef USE_FLASHFS
|
#ifdef USE_FLASHFS
|
||||||
case BLACKBOX_DEVICE_FLASH:
|
case BLACKBOX_DEVICE_FLASH:
|
||||||
if (storageDeviceIsWorking) {
|
if (storageDeviceIsWorking) {
|
||||||
const flashGeometry_t *geometry = flashfsGetGeometry();
|
|
||||||
storageTotal = geometry->totalSize / 1024;
|
const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FLASHFS);
|
||||||
|
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||||
|
|
||||||
|
storageTotal = ((FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGeometry->sectorSize) / 1024);
|
||||||
storageUsed = flashfsGetOffset() / 1024;
|
storageUsed = flashfsGetOffset() / 1024;
|
||||||
}
|
}
|
||||||
break;
|
break;
|
||||||
|
@ -614,7 +617,7 @@ static uint8_t osdShowStats(uint16_t endBatteryVoltage, int statsRowCount)
|
||||||
|
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
if (osdStatGetState(OSD_STAT_MIN_LINK_QUALITY)) {
|
if (osdStatGetState(OSD_STAT_MIN_LINK_QUALITY)) {
|
||||||
itoa(stats.min_link_quality, buff, 10);
|
tfp_sprintf(buff, "%d", stats.min_link_quality);
|
||||||
strcat(buff, "%");
|
strcat(buff, "%");
|
||||||
osdDisplayStatisticLabel(top++, "MIN LINK", buff);
|
osdDisplayStatisticLabel(top++, "MIN LINK", buff);
|
||||||
}
|
}
|
||||||
|
|
|
@ -195,6 +195,7 @@ typedef enum {
|
||||||
typedef enum {
|
typedef enum {
|
||||||
OSD_TIMER_PREC_SECOND,
|
OSD_TIMER_PREC_SECOND,
|
||||||
OSD_TIMER_PREC_HUNDREDTHS,
|
OSD_TIMER_PREC_HUNDREDTHS,
|
||||||
|
OSD_TIMER_PREC_TENTHS,
|
||||||
OSD_TIMER_PREC_COUNT
|
OSD_TIMER_PREC_COUNT
|
||||||
} osd_timer_precision_e;
|
} osd_timer_precision_e;
|
||||||
|
|
||||||
|
@ -251,8 +252,8 @@ typedef struct osdConfig_s {
|
||||||
uint8_t ahInvert; // invert the artificial horizon
|
uint8_t ahInvert; // invert the artificial horizon
|
||||||
uint8_t osdProfileIndex;
|
uint8_t osdProfileIndex;
|
||||||
uint8_t overlay_radio_mode;
|
uint8_t overlay_radio_mode;
|
||||||
uint8_t link_quality_alarm;
|
|
||||||
char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1];
|
char profile[OSD_PROFILE_COUNT][OSD_PROFILE_NAME_LENGTH + 1];
|
||||||
|
uint16_t link_quality_alarm;
|
||||||
} osdConfig_t;
|
} osdConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(osdConfig_t, osdConfig);
|
PG_DECLARE(osdConfig_t, osdConfig);
|
||||||
|
@ -268,7 +269,7 @@ typedef struct statistic_s {
|
||||||
float max_g_force;
|
float max_g_force;
|
||||||
int16_t max_esc_temp;
|
int16_t max_esc_temp;
|
||||||
int32_t max_esc_rpm;
|
int32_t max_esc_rpm;
|
||||||
uint8_t min_link_quality;
|
uint16_t min_link_quality;
|
||||||
} statistic_t;
|
} statistic_t;
|
||||||
|
|
||||||
extern timeUs_t resumeRefreshAt;
|
extern timeUs_t resumeRefreshAt;
|
||||||
|
|
|
@ -286,6 +286,12 @@ void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time)
|
||||||
tfp_sprintf(buff, "%02d:%02d.%02d", minutes, seconds, hundredths);
|
tfp_sprintf(buff, "%02d:%02d.%02d", minutes, seconds, hundredths);
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
case OSD_TIMER_PREC_TENTHS:
|
||||||
|
{
|
||||||
|
const int tenths = (time / 100000) % 10;
|
||||||
|
tfp_sprintf(buff, "%02d:%02d.%01d", minutes, seconds, tenths);
|
||||||
|
break;
|
||||||
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -850,13 +856,17 @@ static void osdElementHorizonSidebars(osdElementParms_t *element)
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
static void osdElementLinkQuality(osdElementParms_t *element)
|
static void osdElementLinkQuality(osdElementParms_t *element)
|
||||||
{
|
{
|
||||||
// change range to 0-9 (two sig. fig. adds little extra value, also reduces screen estate)
|
uint16_t osdLinkQuality = 0;
|
||||||
uint8_t osdLinkQuality = rxGetLinkQuality() * 10 / LINK_QUALITY_MAX_VALUE;
|
if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) { // 0-300
|
||||||
if (osdLinkQuality >= 10) {
|
osdLinkQuality = rxGetLinkQuality() / 3.41;
|
||||||
osdLinkQuality = 9;
|
tfp_sprintf(element->buff, "%3d", osdLinkQuality);
|
||||||
|
} else { // 0-9
|
||||||
|
osdLinkQuality = rxGetLinkQuality() * 10 / LINK_QUALITY_MAX_VALUE;
|
||||||
|
if (osdLinkQuality >= 10) {
|
||||||
|
osdLinkQuality = 9;
|
||||||
|
}
|
||||||
|
tfp_sprintf(element->buff, "%1d", osdLinkQuality);
|
||||||
}
|
}
|
||||||
|
|
||||||
tfp_sprintf(element->buff, "%1d", osdLinkQuality);
|
|
||||||
}
|
}
|
||||||
#endif // USE_RX_LINK_QUALITY_INFO
|
#endif // USE_RX_LINK_QUALITY_INFO
|
||||||
|
|
||||||
|
|
|
@ -26,6 +26,7 @@
|
||||||
#ifdef USE_FLASH_CHIP
|
#ifdef USE_FLASH_CHIP
|
||||||
|
|
||||||
#include "drivers/bus_spi.h"
|
#include "drivers/bus_spi.h"
|
||||||
|
#include "drivers/bus_quadspi.h"
|
||||||
#include "drivers/io.h"
|
#include "drivers/io.h"
|
||||||
|
|
||||||
#include "pg/pg.h"
|
#include "pg/pg.h"
|
||||||
|
@ -33,11 +34,20 @@
|
||||||
|
|
||||||
#include "flash.h"
|
#include "flash.h"
|
||||||
|
|
||||||
|
#ifndef FLASH_CS_PIN
|
||||||
|
#define FLASH_CS_PIN NONE
|
||||||
|
#endif
|
||||||
|
|
||||||
PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0);
|
||||||
|
|
||||||
void pgResetFn_flashConfig(flashConfig_t *flashConfig)
|
void pgResetFn_flashConfig(flashConfig_t *flashConfig)
|
||||||
{
|
{
|
||||||
flashConfig->csTag = IO_TAG(FLASH_CS_PIN);
|
flashConfig->csTag = IO_TAG(FLASH_CS_PIN);
|
||||||
|
#if defined(USE_SPI) && defined(FLASH_SPI_INSTANCE)
|
||||||
flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(FLASH_SPI_INSTANCE));
|
flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(FLASH_SPI_INSTANCE));
|
||||||
|
#endif
|
||||||
|
#if defined(USE_QUADSPI) && defined(FLASH_QUADSPI_INSTANCE)
|
||||||
|
flashConfig->quadSpiDevice = QUADSPI_DEV_TO_CFG(quadSpiDeviceByInstance(FLASH_QUADSPI_INSTANCE));
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -29,6 +29,7 @@
|
||||||
typedef struct flashConfig_s {
|
typedef struct flashConfig_s {
|
||||||
ioTag_t csTag;
|
ioTag_t csTag;
|
||||||
uint8_t spiDevice;
|
uint8_t spiDevice;
|
||||||
|
uint8_t quadSpiDevice;
|
||||||
} flashConfig_t;
|
} flashConfig_t;
|
||||||
|
|
||||||
PG_DECLARE(flashConfig_t, flashConfig);
|
PG_DECLARE(flashConfig_t, flashConfig);
|
||||||
|
|
|
@ -146,5 +146,6 @@
|
||||||
|
|
||||||
#include "target/common_pre.h"
|
#include "target/common_pre.h"
|
||||||
#include "target.h"
|
#include "target.h"
|
||||||
|
#include "target/common_deprecated_post.h"
|
||||||
#include "target/common_post.h"
|
#include "target/common_post.h"
|
||||||
#include "target/common_defaults_post.h"
|
#include "target/common_defaults_post.h"
|
||||||
|
|
|
@ -149,6 +149,11 @@ typedef struct crsfPayloadLinkstatistics_s {
|
||||||
|
|
||||||
static timeUs_t lastLinkStatisticsFrameUs;
|
static timeUs_t lastLinkStatisticsFrameUs;
|
||||||
|
|
||||||
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
|
STATIC_UNIT_TESTED uint16_t scaleCrsfLq(uint16_t lqvalue) {
|
||||||
|
return (lqvalue % 100) ? ((lqvalue * 3.41) + 1) : (lqvalue * 3.41);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, timeUs_t currentTimeUs)
|
static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr, timeUs_t currentTimeUs)
|
||||||
{
|
{
|
||||||
const crsfLinkStatistics_t stats = *statsPtr;
|
const crsfLinkStatistics_t stats = *statsPtr;
|
||||||
|
@ -159,6 +164,12 @@ static void handleCrsfLinkStatisticsFrame(const crsfLinkStatistics_t* statsPtr,
|
||||||
setRssi(rssiPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF);
|
setRssi(rssiPercentScaled, RSSI_SOURCE_RX_PROTOCOL_CRSF);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
|
if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
|
||||||
|
setLinkQualityDirect(scaleCrsfLq((stats.rf_Mode * 100) + stats.uplink_Link_quality));
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
switch (debugMode) {
|
switch (debugMode) {
|
||||||
case DEBUG_CRSF_LINK_STATISTICS_UPLINK:
|
case DEBUG_CRSF_LINK_STATISTICS_UPLINK:
|
||||||
DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 0, stats.uplink_RSSI_1);
|
DEBUG_SET(DEBUG_CRSF_LINK_STATISTICS_UPLINK, 0, stats.uplink_RSSI_1);
|
||||||
|
@ -188,6 +199,11 @@ static void crsfCheckRssi(uint32_t currentTimeUs) {
|
||||||
if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
|
if (rssiSource == RSSI_SOURCE_RX_PROTOCOL_CRSF) {
|
||||||
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF);
|
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL_CRSF);
|
||||||
}
|
}
|
||||||
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
|
if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) {
|
||||||
|
setLinkQualityDirect(0);
|
||||||
|
}
|
||||||
|
#endif
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
@ -377,6 +393,11 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
|
||||||
if (rssiSource == RSSI_SOURCE_NONE) {
|
if (rssiSource == RSSI_SOURCE_NONE) {
|
||||||
rssiSource = RSSI_SOURCE_RX_PROTOCOL_CRSF;
|
rssiSource = RSSI_SOURCE_RX_PROTOCOL_CRSF;
|
||||||
}
|
}
|
||||||
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
|
if (linkQualitySource == LQ_SOURCE_NONE) {
|
||||||
|
linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
return serialPort != NULL;
|
return serialPort != NULL;
|
||||||
}
|
}
|
||||||
|
|
|
@ -77,7 +77,7 @@ static timeUs_t lastMspRssiUpdateUs = 0;
|
||||||
static pt1Filter_t frameErrFilter;
|
static pt1Filter_t frameErrFilter;
|
||||||
|
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
static uint8_t linkQuality = 0;
|
static uint16_t linkQuality = 0;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
|
#define MSP_RSSI_TIMEOUT_US 1500000 // 1.5 sec
|
||||||
|
@ -86,6 +86,7 @@ static uint8_t linkQuality = 0;
|
||||||
#define RSSI_OFFSET_SCALING (1024 / 100.0f)
|
#define RSSI_OFFSET_SCALING (1024 / 100.0f)
|
||||||
|
|
||||||
rssiSource_e rssiSource;
|
rssiSource_e rssiSource;
|
||||||
|
linkQualitySource_e linkQualitySource;
|
||||||
|
|
||||||
static bool rxDataProcessingRequired = false;
|
static bool rxDataProcessingRequired = false;
|
||||||
static bool auxiliaryProcessingRequired = false;
|
static bool auxiliaryProcessingRequired = false;
|
||||||
|
@ -358,11 +359,11 @@ void resumeRxPwmPpmSignal(void)
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
#define LINK_QUALITY_SAMPLE_COUNT 16
|
#define LINK_QUALITY_SAMPLE_COUNT 16
|
||||||
|
|
||||||
static uint8_t updateLinkQualitySamples(uint8_t value)
|
STATIC_UNIT_TESTED uint16_t updateLinkQualitySamples(uint16_t value)
|
||||||
{
|
{
|
||||||
static uint8_t samples[LINK_QUALITY_SAMPLE_COUNT];
|
static uint16_t samples[LINK_QUALITY_SAMPLE_COUNT];
|
||||||
static uint8_t sampleIndex = 0;
|
static uint8_t sampleIndex = 0;
|
||||||
static unsigned sum = 0;
|
static uint16_t sum = 0;
|
||||||
|
|
||||||
sum += value - samples[sampleIndex];
|
sum += value - samples[sampleIndex];
|
||||||
samples[sampleIndex] = value;
|
samples[sampleIndex] = value;
|
||||||
|
@ -374,8 +375,10 @@ static uint8_t updateLinkQualitySamples(uint8_t value)
|
||||||
static void setLinkQuality(bool validFrame, timeDelta_t currentDeltaTime)
|
static void setLinkQuality(bool validFrame, timeDelta_t currentDeltaTime)
|
||||||
{
|
{
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
// calculate new sample mean
|
if (linkQualitySource != LQ_SOURCE_RX_PROTOCOL_CRSF) {
|
||||||
linkQuality = updateLinkQualitySamples(validFrame ? LINK_QUALITY_MAX_VALUE : 0);
|
// calculate new sample mean
|
||||||
|
linkQuality = updateLinkQualitySamples(validFrame ? LINK_QUALITY_MAX_VALUE : 0);
|
||||||
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
if (rssiSource == RSSI_SOURCE_FRAME_ERRORS) {
|
if (rssiSource == RSSI_SOURCE_FRAME_ERRORS) {
|
||||||
|
@ -396,6 +399,15 @@ static void setLinkQuality(bool validFrame, timeDelta_t currentDeltaTime)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
void setLinkQualityDirect(uint16_t linkqualityValue)
|
||||||
|
{
|
||||||
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
|
linkQuality = linkqualityValue;
|
||||||
|
#else
|
||||||
|
UNUSED(linkqualityValue);
|
||||||
|
#endif
|
||||||
|
}
|
||||||
|
|
||||||
bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
|
bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
|
||||||
{
|
{
|
||||||
bool signalReceived = false;
|
bool signalReceived = false;
|
||||||
|
@ -746,14 +758,14 @@ uint8_t getRssiPercent(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
#ifdef USE_RX_LINK_QUALITY_INFO
|
#ifdef USE_RX_LINK_QUALITY_INFO
|
||||||
uint8_t rxGetLinkQuality(void)
|
uint16_t rxGetLinkQuality(void)
|
||||||
{
|
{
|
||||||
return linkQuality;
|
return linkQuality;
|
||||||
}
|
}
|
||||||
|
|
||||||
uint8_t rxGetLinkQualityPercent(void)
|
uint16_t rxGetLinkQualityPercent(void)
|
||||||
{
|
{
|
||||||
return scaleRange(rxGetLinkQuality(), 0, LINK_QUALITY_MAX_VALUE, 0, 100);
|
return (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) ? (linkQuality / 3.41) : scaleRange(linkQuality, 0, LINK_QUALITY_MAX_VALUE, 0, 100);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -148,6 +148,13 @@ typedef enum {
|
||||||
|
|
||||||
extern rssiSource_e rssiSource;
|
extern rssiSource_e rssiSource;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
LQ_SOURCE_NONE = 0,
|
||||||
|
LQ_SOURCE_RX_PROTOCOL_CRSF,
|
||||||
|
} linkQualitySource_e;
|
||||||
|
|
||||||
|
extern linkQualitySource_e linkQualitySource;
|
||||||
|
|
||||||
extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
|
extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
|
||||||
|
|
||||||
void rxInit(void);
|
void rxInit(void);
|
||||||
|
@ -170,10 +177,11 @@ uint16_t getRssi(void);
|
||||||
uint8_t getRssiPercent(void);
|
uint8_t getRssiPercent(void);
|
||||||
bool isRssiConfigured(void);
|
bool isRssiConfigured(void);
|
||||||
|
|
||||||
#define LINK_QUALITY_MAX_VALUE 255
|
#define LINK_QUALITY_MAX_VALUE 1023
|
||||||
|
|
||||||
uint8_t rxGetLinkQuality(void);
|
uint16_t rxGetLinkQuality(void);
|
||||||
uint8_t rxGetLinkQualityPercent(void);
|
void setLinkQualityDirect(uint16_t linkqualityValue);
|
||||||
|
uint16_t rxGetLinkQualityPercent(void);
|
||||||
|
|
||||||
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);
|
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRangeConfig);
|
||||||
|
|
||||||
|
|
|
@ -204,13 +204,13 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
|
||||||
gyroConfig->gyroMovementCalibrationThreshold = 48;
|
gyroConfig->gyroMovementCalibrationThreshold = 48;
|
||||||
gyroConfig->gyro_sync_denom = GYRO_SYNC_DENOM_DEFAULT;
|
gyroConfig->gyro_sync_denom = GYRO_SYNC_DENOM_DEFAULT;
|
||||||
gyroConfig->gyro_hardware_lpf = GYRO_HARDWARE_LPF_NORMAL;
|
gyroConfig->gyro_hardware_lpf = GYRO_HARDWARE_LPF_NORMAL;
|
||||||
gyroConfig->gyro_lowpass_type = FILTER_BIQUAD;
|
gyroConfig->gyro_lowpass_type = FILTER_PT1;
|
||||||
gyroConfig->gyro_lowpass_hz = 150; // NOTE: dynamic lpf is enabled by default so this setting is actually
|
gyroConfig->gyro_lowpass_hz = 150; // NOTE: dynamic lpf is enabled by default so this setting is actually
|
||||||
// overridden and the static lowpass 1 is disabled. We can't set this
|
// overridden and the static lowpass 1 is disabled. We can't set this
|
||||||
// value to 0 otherwise Configurator versions 10.4 and earlier will also
|
// value to 0 otherwise Configurator versions 10.4 and earlier will also
|
||||||
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
|
// reset the lowpass filter type to PT1 overriding the desired BIQUAD setting.
|
||||||
gyroConfig->gyro_lowpass2_type = FILTER_PT1;
|
gyroConfig->gyro_lowpass2_type = FILTER_PT1;
|
||||||
gyroConfig->gyro_lowpass2_hz = 150;
|
gyroConfig->gyro_lowpass2_hz = 250;
|
||||||
gyroConfig->gyro_high_fsr = false;
|
gyroConfig->gyro_high_fsr = false;
|
||||||
gyroConfig->gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT;
|
gyroConfig->gyro_to_use = GYRO_CONFIG_USE_GYRO_DEFAULT;
|
||||||
gyroConfig->gyro_soft_notch_hz_1 = 0;
|
gyroConfig->gyro_soft_notch_hz_1 = 0;
|
||||||
|
@ -221,8 +221,8 @@ void pgResetFn_gyroConfig(gyroConfig_t *gyroConfig)
|
||||||
gyroConfig->gyro_offset_yaw = 0;
|
gyroConfig->gyro_offset_yaw = 0;
|
||||||
gyroConfig->yaw_spin_recovery = true;
|
gyroConfig->yaw_spin_recovery = true;
|
||||||
gyroConfig->yaw_spin_threshold = 1950;
|
gyroConfig->yaw_spin_threshold = 1950;
|
||||||
gyroConfig->dyn_lpf_gyro_min_hz = 150;
|
gyroConfig->dyn_lpf_gyro_min_hz = 200;
|
||||||
gyroConfig->dyn_lpf_gyro_max_hz = 450;
|
gyroConfig->dyn_lpf_gyro_max_hz = 500;
|
||||||
gyroConfig->dyn_notch_range = DYN_NOTCH_RANGE_AUTO;
|
gyroConfig->dyn_notch_range = DYN_NOTCH_RANGE_AUTO;
|
||||||
gyroConfig->dyn_notch_width_percent = 8;
|
gyroConfig->dyn_notch_width_percent = 8;
|
||||||
gyroConfig->dyn_notch_q = 120;
|
gyroConfig->dyn_notch_q = 120;
|
||||||
|
|
|
@ -49,8 +49,6 @@
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
|
|
||||||
#define GYRO_1_SPI_INSTANCE SPI1
|
#define GYRO_1_SPI_INSTANCE SPI1
|
||||||
#define GYRO_1_CS_PIN PA4
|
#define GYRO_1_CS_PIN PA4
|
||||||
#define GYRO_1_EXTI_PIN NONE
|
#define GYRO_1_EXTI_PIN NONE
|
||||||
|
|
42
src/main/target/AIRBOTF7/target.c
Normal file
42
src/main/target/AIRBOTF7/target.c
Normal file
|
@ -0,0 +1,42 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
#include "drivers/timer_def.h"
|
||||||
|
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
DEF_TIM(TIM2, CH1, PA15, TIM_USE_LED, 0, 0), // ONBOARD LED
|
||||||
|
|
||||||
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_ANY, 0, 0), // CAM CONTROL
|
||||||
|
|
||||||
|
// MOTORS
|
||||||
|
|
||||||
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), //S1
|
||||||
|
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), //S2
|
||||||
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 0), //S3
|
||||||
|
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), //S4
|
||||||
|
|
||||||
|
};
|
154
src/main/target/AIRBOTF7/target.h
Normal file
154
src/main/target/AIRBOTF7/target.h
Normal file
|
@ -0,0 +1,154 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "ABF7"
|
||||||
|
#define USBD_PRODUCT_STRING "Airbot-F7"
|
||||||
|
|
||||||
|
#define LED0_PIN PB12
|
||||||
|
|
||||||
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PB0
|
||||||
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
|
// *************** Gyro & ACC **********************
|
||||||
|
#define USE_SPI
|
||||||
|
#define USE_SPI_DEVICE_3
|
||||||
|
|
||||||
|
#define SPI3_SCK_PIN PB3
|
||||||
|
#define SPI3_MISO_PIN PB4
|
||||||
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
#define SPI3_NSS_PIN PD2
|
||||||
|
|
||||||
|
#define USE_GYRO
|
||||||
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
|
#define GYRO_1_SPI_INSTANCE SPI3
|
||||||
|
#define GYRO_1_CS_PIN SPI3_NSS_PIN
|
||||||
|
#define GYRO_1_ALIGN CW90_DEG
|
||||||
|
#define GYRO_1_EXTI_PIN NONE
|
||||||
|
|
||||||
|
|
||||||
|
#define GYRO_2_SPI_INSTANCE SPI1
|
||||||
|
#define GYRO_2_CS_PIN PC4
|
||||||
|
#define GYRO_2_EXTI_PIN NONE
|
||||||
|
#define GYRO_2_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
#define USE_ACC
|
||||||
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
|
// *************** OSD **************************
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_2
|
||||||
|
#define SPI2_SCK_PIN PB13
|
||||||
|
#define SPI2_MISO_PIN PB14
|
||||||
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
|
#define USE_MAX7456
|
||||||
|
#define MAX7456_SPI_INSTANCE SPI2
|
||||||
|
#define MAX7456_SPI_CS_PIN PC15
|
||||||
|
|
||||||
|
|
||||||
|
// *************** FLASH *****************************
|
||||||
|
#define USE_SPI_DEVICE_1
|
||||||
|
#define SPI1_SCK_PIN PA5
|
||||||
|
#define SPI1_MISO_PIN PA6
|
||||||
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_FLASHFS
|
||||||
|
#define USE_FLASH_M25P16
|
||||||
|
#define FLASH_CS_PIN PA3
|
||||||
|
#define FLASH_SPI_INSTANCE SPI1
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
|
||||||
|
// *************** UART *****************************
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_USB_DETECT
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_UART1
|
||||||
|
#define UART1_RX_PIN PA10
|
||||||
|
#define UART1_TX_PIN PA9
|
||||||
|
|
||||||
|
#define USE_UART2
|
||||||
|
#define UART2_TX_PIN PA2
|
||||||
|
|
||||||
|
#define USE_UART3
|
||||||
|
#define UART3_RX_PIN PC11
|
||||||
|
#define UART3_TX_PIN PC10
|
||||||
|
|
||||||
|
#define USE_UART4
|
||||||
|
#define UART4_RX_PIN PA1
|
||||||
|
#define UART4_TX_PIN PA0
|
||||||
|
|
||||||
|
#define USE_UART5
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
|
||||||
|
#define USE_UART6
|
||||||
|
#define UART6_RX_PIN PC7
|
||||||
|
#define UART6_TX_PIN PC6
|
||||||
|
|
||||||
|
|
||||||
|
#define USE_SOFTSERIAL1
|
||||||
|
|
||||||
|
#define SERIAL_PORT_COUNT 8
|
||||||
|
|
||||||
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||||
|
|
||||||
|
// *************** CAM *****************************
|
||||||
|
|
||||||
|
#define CAMERA_CONTROL_PIN PA8
|
||||||
|
|
||||||
|
// *************** I2C *****************************
|
||||||
|
|
||||||
|
#define USE_I2C
|
||||||
|
#define USE_I2C_DEVICE_1
|
||||||
|
#define I2C1_SCL PB8
|
||||||
|
#define I2C1_SDA PB9
|
||||||
|
|
||||||
|
// *************** ADC *****************************
|
||||||
|
#define USE_ADC
|
||||||
|
#define ADC3_DMA_STREAM DMA2_Stream0
|
||||||
|
#define VBAT_ADC_PIN PC0
|
||||||
|
#define CURRENT_METER_ADC_PIN PC2
|
||||||
|
#define RSSI_ADC_PIN PC1
|
||||||
|
|
||||||
|
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL | FEATURE_AIRMODE)
|
||||||
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||||
|
#define CURRENT_METER_SCALE_DEFAULT 179
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
|
||||||
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
#define TARGET_IO_PORTD 0xffff
|
||||||
|
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 6
|
||||||
|
#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(4)|TIM_N(8))
|
9
src/main/target/AIRBOTF7/target.mk
Normal file
9
src/main/target/AIRBOTF7/target.mk
Normal file
|
@ -0,0 +1,9 @@
|
||||||
|
F7X2RE_TARGETS += $(TARGET)
|
||||||
|
FEATURES += VCP ONBOARDFLASH
|
||||||
|
|
||||||
|
TARGET_SRC = \
|
||||||
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
|
drivers/accgyro/accgyro_mpu6500.c \
|
||||||
|
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||||
|
drivers/accgyro/accgyro_spi_icm20689.c \
|
||||||
|
drivers/max7456.c
|
|
@ -30,7 +30,6 @@
|
||||||
#define BEEPER_PIN PC13
|
#define BEEPER_PIN PC13
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_GYRO_EXTI
|
#define USE_GYRO_EXTI
|
||||||
#define GYRO_1_EXTI_PIN PB10
|
#define GYRO_1_EXTI_PIN PB10
|
||||||
|
|
|
@ -24,8 +24,6 @@
|
||||||
|
|
||||||
#define USBD_PRODUCT_STRING "EXF722DUAL"
|
#define USBD_PRODUCT_STRING "EXF722DUAL"
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
||||||
#define LED0_PIN PC4
|
#define LED0_PIN PC4
|
||||||
|
|
|
@ -148,7 +148,6 @@
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
||||||
/*-------------ESCs----------------*/
|
/*-------------ESCs----------------*/
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PB0 // (HARDWARE=0)
|
#define ESCSERIAL_TIMER_TX_PIN PB0 // (HARDWARE=0)
|
||||||
/*---------------------------------*/
|
/*---------------------------------*/
|
||||||
|
|
|
@ -31,7 +31,6 @@
|
||||||
#define BEEPER_PIN PC14
|
#define BEEPER_PIN PC14
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_GYRO_EXTI
|
#define USE_GYRO_EXTI
|
||||||
#define GYRO_1_EXTI_PIN PC3
|
#define GYRO_1_EXTI_PIN PC3
|
||||||
|
@ -53,13 +52,9 @@
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
|
|
||||||
#define ACC_MPU6000_1_ALIGN CW270_DEG
|
#define GYRO_1_ALIGN CW270_DEG
|
||||||
#define GYRO_MPU6000_1_ALIGN CW270_DEG
|
|
||||||
#define GYRO_1_ALIGN GYRO_MPU6000_1_ALIGN
|
|
||||||
|
|
||||||
#define ACC_ICM20689_2_ALIGN CW270_DEG
|
#define GYRO_2_ALIGN CW270_DEG
|
||||||
#define GYRO_ICM20689_2_ALIGN CW270_DEG
|
|
||||||
#define GYRO_2_ALIGN GYRO_ICM20689_2_ALIGN
|
|
||||||
|
|
||||||
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_2
|
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_2
|
||||||
|
|
||||||
|
|
|
@ -30,7 +30,6 @@
|
||||||
#define BEEPER_PIN PA4
|
#define BEEPER_PIN PA4
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_GYRO_EXTI
|
#define USE_GYRO_EXTI
|
||||||
#define GYRO_1_EXTI_PIN PC4
|
#define GYRO_1_EXTI_PIN PC4
|
||||||
|
|
|
@ -36,5 +36,6 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S4_OUT - DMA1_ST1_CH3
|
DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S4_OUT - DMA1_ST1_CH3
|
||||||
|
|
||||||
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH6
|
DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0 ), // LED_STRIP - DMA1_ST2_CH6
|
||||||
|
DEF_TIM(TIM11, CH1, PB9, TIM_USE_CAMERA_CONTROL, 0, 0), // CAM_CTL
|
||||||
|
|
||||||
};
|
};
|
||||||
|
|
|
@ -153,5 +153,5 @@
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
#define TARGET_IO_PORTD (BIT(2))
|
#define TARGET_IO_PORTD (BIT(2))
|
||||||
|
|
||||||
#define USABLE_TIMER_CHANNEL_COUNT 6
|
#define USABLE_TIMER_CHANNEL_COUNT 7
|
||||||
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) )
|
#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(11) )
|
||||||
|
|
|
@ -33,7 +33,6 @@
|
||||||
#define BEEPER_PIN PC15
|
#define BEEPER_PIN PC15
|
||||||
#define BEEPER_INVERTED
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
#define USE_DUAL_GYRO
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_GYRO_EXTI
|
#define USE_GYRO_EXTI
|
||||||
#define GYRO_1_EXTI_PIN PC4
|
#define GYRO_1_EXTI_PIN PC4
|
||||||
|
@ -56,13 +55,9 @@
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define USE_ACC_SPI_ICM20689
|
#define USE_ACC_SPI_ICM20689
|
||||||
|
|
||||||
#define ACC_ICM20689_1_ALIGN CW90_DEG
|
#define GYRO_1_ALIGN CW90_DEG
|
||||||
#define GYRO_ICM20689_1_ALIGN CW90_DEG
|
|
||||||
#define GYRO_1_ALIGN GYRO_ICM20689_1_ALIGN
|
|
||||||
|
|
||||||
#define ACC_MPU6000_2_ALIGN CW90_DEG
|
#define GYRO_2_ALIGN CW90_DEG
|
||||||
#define GYRO_MPU6000_2_ALIGN CW90_DEG
|
|
||||||
#define GYRO_2_ALIGN GYRO_MPU6000_2_ALIGN
|
|
||||||
|
|
||||||
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
|
#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1
|
||||||
|
|
||||||
|
@ -154,7 +149,6 @@
|
||||||
#define USE_LED_STRIP
|
#define USE_LED_STRIP
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
#define USE_PINIO
|
#define USE_PINIO
|
||||||
#define PINIO1_PIN PC14 // VTX power switcher
|
#define PINIO1_PIN PC14 // VTX power switcher
|
||||||
|
|
|
@ -55,7 +55,6 @@
|
||||||
|
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_1_ALIGN CW180_DEG
|
|
||||||
|
|
||||||
// ******* SERIAL ********
|
// ******* SERIAL ********
|
||||||
|
|
||||||
|
|
|
@ -42,7 +42,6 @@
|
||||||
#define SPI1_MISO_PIN PA6
|
#define SPI1_MISO_PIN PA6
|
||||||
#define SPI1_MOSI_PIN PA7
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
#define USE_EXTI
|
#define USE_EXTI
|
||||||
#define USE_GYRO_EXTI
|
#define USE_GYRO_EXTI
|
||||||
#define GYRO_1_EXTI_PIN PC4
|
#define GYRO_1_EXTI_PIN PC4
|
||||||
|
|
|
@ -61,8 +61,6 @@
|
||||||
#define USE_GYRO_SPI_MPU6000
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
|
|
||||||
#if defined(OMNIBUSF4V6)
|
#if defined(OMNIBUSF4V6)
|
||||||
#define GYRO_1_CS_PIN PA4 // Onboard IMU
|
#define GYRO_1_CS_PIN PA4 // Onboard IMU
|
||||||
#define GYRO_1_SPI_INSTANCE SPI1
|
#define GYRO_1_SPI_INSTANCE SPI1
|
||||||
|
|
|
@ -41,15 +41,22 @@
|
||||||
|
|
||||||
#define USE_GYRO
|
#define USE_GYRO
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
#define USE_GYRO_SPI_MPU6000
|
||||||
#define GYRO_1_CS_PIN PD2
|
|
||||||
#define GYRO_1_SPI_INSTANCE SPI3
|
|
||||||
|
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
|
||||||
|
#define GYRO_1_CS_PIN PD2
|
||||||
|
#define GYRO_1_SPI_INSTANCE SPI3
|
||||||
|
#define GYRO_1_EXTI_PIN NONE
|
||||||
#define GYRO_1_ALIGN CW0_DEG
|
#define GYRO_1_ALIGN CW0_DEG
|
||||||
|
|
||||||
|
#define GYRO_2_CS_PIN PC4
|
||||||
|
#define GYRO_2_SPI_INSTANCE SPI1
|
||||||
|
#define GYRO_2_EXTI_PIN NONE
|
||||||
|
#define GYRO_2_ALIGN CW0_DEG
|
||||||
|
|
||||||
// *************** OSD **************************
|
// *************** OSD **************************
|
||||||
|
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
@ -130,7 +137,6 @@
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PA3
|
#define ESCSERIAL_TIMER_TX_PIN PA3
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
|
@ -5,4 +5,5 @@ TARGET_SRC = \
|
||||||
drivers/accgyro/accgyro_spi_mpu6000.c \
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
drivers/accgyro/accgyro_mpu6500.c \
|
drivers/accgyro/accgyro_mpu6500.c \
|
||||||
drivers/accgyro/accgyro_spi_mpu6500.c \
|
drivers/accgyro/accgyro_spi_mpu6500.c \
|
||||||
|
drivers/accgyro/accgyro_spi_icm20689.c \
|
||||||
drivers/max7456.c
|
drivers/max7456.c
|
||||||
|
|
|
@ -44,7 +44,6 @@
|
||||||
//GYRO & ACC--------------------------------
|
//GYRO & ACC--------------------------------
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
#define USE_GYRO
|
#define USE_GYRO
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
// ICM-20608-G
|
// ICM-20608-G
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define USE_GYRO_SPI_MPU6500
|
#define USE_GYRO_SPI_MPU6500
|
||||||
|
|
|
@ -49,7 +49,6 @@
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
|
|
||||||
#define GYRO_1_ALIGN CW0_DEG
|
#define GYRO_1_ALIGN CW0_DEG
|
||||||
#define ACC_1_ALIGN CW0_DEG
|
|
||||||
|
|
||||||
// *************** OSD **************************
|
// *************** OSD **************************
|
||||||
|
|
||||||
|
@ -131,7 +130,6 @@
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PA3
|
#define ESCSERIAL_TIMER_TX_PIN PA3
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
|
@ -129,10 +129,6 @@
|
||||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
|
||||||
|
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
#define TARGET_IO_PORTC 0xffff
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
|
|
@ -31,7 +31,6 @@
|
||||||
|
|
||||||
#define TEST_SOUND // for factory testing audio output
|
#define TEST_SOUND // for factory testing audio output
|
||||||
|
|
||||||
#define USE_MULTI_GYRO
|
|
||||||
//#define DEBUG_MODE DEBUG_DUAL_GYRO_DIFF
|
//#define DEBUG_MODE DEBUG_DUAL_GYRO_DIFF
|
||||||
|
|
||||||
#define ENABLE_DSHOT_DMAR true
|
#define ENABLE_DSHOT_DMAR true
|
||||||
|
|
|
@ -62,7 +62,6 @@
|
||||||
|
|
||||||
#define USE_ACC_MPU6000
|
#define USE_ACC_MPU6000
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define ACC_1_ALIGN CW180_DEG_FLIP
|
|
||||||
|
|
||||||
// *************** I2C ***************
|
// *************** I2C ***************
|
||||||
#define USE_I2C
|
#define USE_I2C
|
||||||
|
|
|
@ -70,7 +70,6 @@
|
||||||
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
|
||||||
#warning Missing channel for F4/F7 spec dma 1 stream 4; DMA_OPT assumed as 0
|
#warning Missing channel for F4/F7 spec dma 1 stream 4; DMA_OPT assumed as 0
|
||||||
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel unknown
|
#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel unknown
|
||||||
#define SDCARD_DMA_CHANNEL DMA_Channel_0
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#define USE_VCP
|
#define USE_VCP
|
||||||
|
|
41
src/main/target/VGOODRCF4/target.c
Normal file
41
src/main/target/VGOODRCF4/target.c
Normal file
|
@ -0,0 +1,41 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
#include "drivers/io.h"
|
||||||
|
|
||||||
|
#include "drivers/dma.h"
|
||||||
|
#include "drivers/timer.h"
|
||||||
|
#include "drivers/timer_def.h"
|
||||||
|
|
||||||
|
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||||
|
DEF_TIM(TIM8, CH2, PC7, TIM_USE_PPM, 0, 0), // PPM
|
||||||
|
|
||||||
|
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MOTOR, 0, 0), // S1
|
||||||
|
DEF_TIM(TIM1, CH4, PA10, TIM_USE_MOTOR, 0, 0), // S2
|
||||||
|
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // S3
|
||||||
|
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // S4
|
||||||
|
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 0), // S5
|
||||||
|
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR | TIM_USE_CAMERA_CONTROL, 0, 0), // S6 | TIM_USE_CAMERA_CONTROL
|
||||||
|
|
||||||
|
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 1), //LED_STRIP
|
||||||
|
};
|
186
src/main/target/VGOODRCF4/target.h
Normal file
186
src/main/target/VGOODRCF4/target.h
Normal file
|
@ -0,0 +1,186 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
//#define USE_TARGET_CONFIG
|
||||||
|
#define TARGET_BOARD_IDENTIFIER "VGF4"
|
||||||
|
#define TARGET_MANUFACTURER_IDENTIFIER "VGRC"
|
||||||
|
#define USBD_PRODUCT_STRING "VGOODRCF4"
|
||||||
|
|
||||||
|
#define LED0_PIN PC14
|
||||||
|
#define LED1_PIN PC15
|
||||||
|
|
||||||
|
#define USE_BEEPER
|
||||||
|
#define BEEPER_PIN PC13
|
||||||
|
#define BEEPER_INVERTED
|
||||||
|
|
||||||
|
//#define ENABLE_DSHOT_DMAR true//debug for checking
|
||||||
|
|
||||||
|
#define GYRO_1_ALIGN CW180_DEG
|
||||||
|
|
||||||
|
#define USE_EXTI
|
||||||
|
#define USE_GYRO_EXTI
|
||||||
|
#define GYRO_1_EXTI_PIN PC3
|
||||||
|
|
||||||
|
#define USE_MPU_DATA_READY_SIGNAL
|
||||||
|
//#define ENSURE_MPU_DATA_READY_IS_LOW
|
||||||
|
|
||||||
|
#define USE_ACC
|
||||||
|
#define USE_ACC_SPI_MPU6000
|
||||||
|
#define USE_GYRO
|
||||||
|
#define USE_GYRO_SPI_MPU6000
|
||||||
|
|
||||||
|
#define GYRO_1_CS_PIN PA15
|
||||||
|
#define GYRO_1_SPI_INSTANCE SPI3
|
||||||
|
|
||||||
|
//-------------------------------------SPI2 FLASH------------------------------
|
||||||
|
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||||
|
#define USE_FLASHFS
|
||||||
|
#define USE_FLASH_M25P16
|
||||||
|
#define USE_FLASH_W25M512
|
||||||
|
#define FLASH_CS_PIN PB12
|
||||||
|
#define FLASH_SPI_INSTANCE SPI2
|
||||||
|
|
||||||
|
//-------------------------------------SPI1 OSD--------------------------------
|
||||||
|
#define USE_OSD
|
||||||
|
#define USE_MAX7456
|
||||||
|
#define MAX7456_SPI_INSTANCE SPI1
|
||||||
|
#define MAX7456_SPI_CS_PIN PA4
|
||||||
|
#define MAX7456_SPI_CLK (SPI_CLOCK_STANDARD)
|
||||||
|
#define MAX7456_RESTORE_CLK (SPI_CLOCK_FAST)
|
||||||
|
|
||||||
|
//-------------------------------------IIC2 BMP280------------------------------
|
||||||
|
#define USE_BARO
|
||||||
|
#define USE_BARO_BMP280
|
||||||
|
#define USE_BARO_MS5611
|
||||||
|
#define USE_BARO_BMP085
|
||||||
|
#define BARO_I2C_INSTANCE (I2CDEV_2)
|
||||||
|
#define DEFAULT_BARO_BMP280
|
||||||
|
|
||||||
|
//-------------------------------------IIC1 MAG5883------------------------------
|
||||||
|
#define MAG_I2C_INSTANCE (I2CDEV_1)
|
||||||
|
#define USE_MAG
|
||||||
|
#define USE_MAG_HMC5883
|
||||||
|
#define USE_MAG_QMC5883
|
||||||
|
#define USE_MAG_LIS3MDL
|
||||||
|
#define MAG_HMC5883_ALIGN CW90_DEG
|
||||||
|
|
||||||
|
//-------------------------------------USART-----------------------------------
|
||||||
|
#define USE_VCP
|
||||||
|
#define USE_USB_DETECT
|
||||||
|
#define USB_DETECT_PIN PC4
|
||||||
|
//usb-:pa11,usb+:pa12
|
||||||
|
|
||||||
|
#define USE_UART1
|
||||||
|
#define UART1_TX_PIN PB6
|
||||||
|
#define UART1_RX_PIN PB7
|
||||||
|
|
||||||
|
#define USE_UART2
|
||||||
|
#define UART2_TX_PIN PA2
|
||||||
|
#define UART2_RX_PIN PA3
|
||||||
|
|
||||||
|
#define USE_UART3
|
||||||
|
#define UART3_TX_PIN PC10
|
||||||
|
#define UART3_RX_PIN PC11
|
||||||
|
|
||||||
|
#define USE_UART4
|
||||||
|
#define UART4_TX_PIN PA0
|
||||||
|
#define UART4_RX_PIN PA1
|
||||||
|
|
||||||
|
#define USE_UART5
|
||||||
|
#define UART5_TX_PIN PC12
|
||||||
|
#define UART5_RX_PIN PD2
|
||||||
|
|
||||||
|
#define USE_UART6
|
||||||
|
#define UART6_TX_PIN PC6
|
||||||
|
#define UART6_RX_PIN PC7//RX(PPM/SBUS)
|
||||||
|
|
||||||
|
#define USE_SOFTSERIAL1
|
||||||
|
#define SOFTSERIAL1_RX_PIN PC5
|
||||||
|
#define SOFTSERIAL1_TX_PIN PB2
|
||||||
|
|
||||||
|
|
||||||
|
#define SERIAL_PORT_COUNT 8
|
||||||
|
|
||||||
|
//-------------------------------------ADC METERE------------------------------
|
||||||
|
#define USE_ADC
|
||||||
|
#define ADC_INSTANCE ADC2
|
||||||
|
#define ADC2_DMA_OPT 1
|
||||||
|
#define CURRENT_METER_ADC_PIN PC0
|
||||||
|
#define VBAT_ADC_PIN PC1
|
||||||
|
#define RSSI_ADC_PIN PC2
|
||||||
|
|
||||||
|
//---------------------------------VTX&&CAM------------------------------------
|
||||||
|
#define USE_PINIO
|
||||||
|
#define PINIO1_PIN PA13 // VTX power switcher
|
||||||
|
#define PINIO2_PIN PA14 // 2xCamera switcher
|
||||||
|
#define USE_PINIOBOX
|
||||||
|
|
||||||
|
//-------------------------------------SPI------------------------------------
|
||||||
|
#define USE_SPI
|
||||||
|
#define USE_SPI_DEVICE_3 //GYRO
|
||||||
|
#define SPI3_SCK_PIN PB3
|
||||||
|
#define SPI3_MISO_PIN PB4
|
||||||
|
#define SPI3_MOSI_PIN PB5
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_2 // FLASH
|
||||||
|
#define SPI2_SCK_PIN PB13
|
||||||
|
#define SPI2_MISO_PIN PB14
|
||||||
|
#define SPI2_MOSI_PIN PB15
|
||||||
|
|
||||||
|
#define USE_SPI_DEVICE_1 //OSD
|
||||||
|
#define SPI1_SCK_PIN PA5
|
||||||
|
#define SPI1_MISO_PIN PA6
|
||||||
|
#define SPI1_MOSI_PIN PA7
|
||||||
|
|
||||||
|
//-------------------------------------IIC------------------------------------
|
||||||
|
#define USE_I2C //MAG5883
|
||||||
|
#define USE_I2C_DEVICE_1
|
||||||
|
//#define I2C_DEVICE (I2CDEV_1)
|
||||||
|
#define I2C1_SCL PB8
|
||||||
|
#define I2C1_SDA PB9
|
||||||
|
|
||||||
|
#define USE_I2C //BMP280
|
||||||
|
#define USE_I2C_DEVICE_2
|
||||||
|
//#define I2C_DEVICE (I2CDEV_2)
|
||||||
|
#define I2C2_SCL PB10
|
||||||
|
#define I2C2_SDA PB11
|
||||||
|
|
||||||
|
//-------------------------------------FEATURES-------------------------------
|
||||||
|
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY )
|
||||||
|
|
||||||
|
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||||
|
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||||
|
#define SERIALRX_UART SERIAL_PORT_USART6
|
||||||
|
|
||||||
|
#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC
|
||||||
|
#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC
|
||||||
|
#define CURRENT_METER_SCALE_DEFAULT 179
|
||||||
|
|
||||||
|
#define USE_ESCSERIAL
|
||||||
|
|
||||||
|
//--------------------------------BOARD RESOURCES-----------------------------
|
||||||
|
#define TARGET_IO_PORTA 0xffff
|
||||||
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
#define TARGET_IO_PORTC 0xffff
|
||||||
|
#define TARGET_IO_PORTD 0x0007
|
||||||
|
|
||||||
|
#define USABLE_TIMER_CHANNEL_COUNT 8
|
||||||
|
#define USED_TIMERS (TIM_N(1)|TIM_N(3)|TIM_N(8))
|
14
src/main/target/VGOODRCF4/target.mk
Normal file
14
src/main/target/VGOODRCF4/target.mk
Normal file
|
@ -0,0 +1,14 @@
|
||||||
|
F405_TARGETS += $(TARGET)
|
||||||
|
FEATURES += VCP ONBOARDFLASH
|
||||||
|
|
||||||
|
TARGET_SRC = \
|
||||||
|
drivers/accgyro/accgyro_spi_icm20689.c \
|
||||||
|
drivers/accgyro/accgyro_spi_mpu6000.c \
|
||||||
|
drivers/barometer/barometer_bmp085.c \
|
||||||
|
drivers/barometer/barometer_bmp280.c \
|
||||||
|
drivers/barometer/barometer_ms5611.c \
|
||||||
|
drivers/compass/compass_ak8975.c \
|
||||||
|
drivers/compass/compass_hmc5883l.c \
|
||||||
|
drivers/compass/compass_qmc5883l.c \
|
||||||
|
drivers/compass/compass_lis3mdl.c \
|
||||||
|
drivers/max7456.c
|
|
@ -51,7 +51,6 @@
|
||||||
#define USE_ACC
|
#define USE_ACC
|
||||||
#define USE_ACC_SPI_MPU6000
|
#define USE_ACC_SPI_MPU6000
|
||||||
#define USE_ACC_SPI_MPU6500
|
#define USE_ACC_SPI_MPU6500
|
||||||
#define ACC_1_ALIGN CW180_DEG
|
|
||||||
|
|
||||||
// *************** Flash **************************
|
// *************** Flash **************************
|
||||||
#define USE_SPI_DEVICE_2
|
#define USE_SPI_DEVICE_2
|
||||||
|
@ -142,7 +141,6 @@
|
||||||
|
|
||||||
#define USE_ESCSERIAL
|
#define USE_ESCSERIAL
|
||||||
#define ESCSERIAL_TIMER_TX_PIN PA3
|
#define ESCSERIAL_TIMER_TX_PIN PA3
|
||||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
|
||||||
|
|
||||||
#define TARGET_IO_PORTA 0xffff
|
#define TARGET_IO_PORTA 0xffff
|
||||||
#define TARGET_IO_PORTB 0xffff
|
#define TARGET_IO_PORTB 0xffff
|
||||||
|
|
137
src/main/target/common_deprecated_post.h
Normal file
137
src/main/target/common_deprecated_post.h
Normal file
|
@ -0,0 +1,137 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight and Betaflight.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are free software. You can redistribute
|
||||||
|
* this software and/or modify this software under the terms of the
|
||||||
|
* GNU General Public License as published by the Free Software
|
||||||
|
* Foundation, either version 3 of the License, or (at your option)
|
||||||
|
* any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight and Betaflight are distributed in the hope that they
|
||||||
|
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||||
|
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||||
|
* See the GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with this software.
|
||||||
|
*
|
||||||
|
* If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Flag any deprecated defines with compile errors so they
|
||||||
|
// can be cleaned up and not further propagated.
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#ifdef ACC_1_ALIGN
|
||||||
|
#error "The ACC_1_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_2_ALIGN
|
||||||
|
#error "The ACC_2_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_ICM20689_ALIGN
|
||||||
|
#error "The ACC_ICM20689_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6000_1_ALIGN
|
||||||
|
#error "The ACC_MPU6000_1_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6000_2_ALIGN
|
||||||
|
#error "The ACC_MPU6000_2_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6000_ALIGN
|
||||||
|
#error "The ACC_MPU6000_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6500_1_ALIGN
|
||||||
|
#error "The ACC_MPU6500_1_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6500_2_ALIGN
|
||||||
|
#error "The ACC_MPU6500_2_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ACC_MPU6500_ALIGN
|
||||||
|
#error "The ACC_MPU6500_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_ICM20689_ALIGN
|
||||||
|
#error "The GYRO_ICM20689_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6000_1_ALIGN
|
||||||
|
#error "The GYRO_MPU6000_1_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6000_2_ALIGN
|
||||||
|
#error "The GYRO_MPU6000_2_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6000_ALIGN
|
||||||
|
#error "The GYRO_MPU6000_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6500_1_ALIGN
|
||||||
|
#error "The GYRO_MPU6500_1_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6500_2_ALIGN
|
||||||
|
#error "The GYRO_MPU6500_2_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef GYRO_MPU6500_ALIGN
|
||||||
|
#error "The GYRO_MPU6000_ALIGN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ICM20689_CS_PIN
|
||||||
|
#error "The ICM20689_CS_PIN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef ICM20689_SPI_INSTANCE
|
||||||
|
#error "The ICM20689_SPI_INSTANCE define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MPU_INT_EXTI
|
||||||
|
#error "The MPU_INT_EXTI define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MPU6000_CS_PIN
|
||||||
|
#error "The MPU6000_CS_PIN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MPU6000_SPI_INSTANCE
|
||||||
|
#error "The MPU6000_SPI_INSTANCE define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MPU6500_CS_PIN
|
||||||
|
#error "The MPU6500_CS_PIN define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef MPU6500_SPI_INSTANCE
|
||||||
|
#error "The MPU6500_SPI_INSTANCE define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef SDCARD_DMA_CHANNEL
|
||||||
|
#error "The SDCARD_DMA_CHANNEL define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER
|
||||||
|
#error "The SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER define should not be part of the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER
|
||||||
|
#error "The SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER define should not be part of the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_DUAL_GYRO
|
||||||
|
#error "The USE_DUAL_GYRO define has been deprecated - please remove from the target definition"
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||||
|
#error "The USE_SERIAL_4WAY_BLHELI_INTERFACE define should not be part of the target definition"
|
||||||
|
#endif
|
||||||
|
|
|
@ -181,9 +181,15 @@
|
||||||
#if defined(USE_FLASH_W25M512)
|
#if defined(USE_FLASH_W25M512)
|
||||||
#define USE_FLASH_W25M
|
#define USE_FLASH_W25M
|
||||||
#define USE_FLASH_M25P16
|
#define USE_FLASH_M25P16
|
||||||
|
#define USE_FLASH_W25M
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined(USE_FLASH_M25P16)
|
#if defined(USE_FLASH_W25M02G)
|
||||||
|
#define USE_FLASH_W25N01G
|
||||||
|
#define USE_FLASH_W25M
|
||||||
|
#endif
|
||||||
|
|
||||||
|
#if defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25N01G)
|
||||||
#define USE_FLASH_CHIP
|
#define USE_FLASH_CHIP
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -217,9 +223,13 @@
|
||||||
|
|
||||||
#ifdef USE_UNIFIED_TARGET
|
#ifdef USE_UNIFIED_TARGET
|
||||||
#define USE_CONFIGURATION_STATE
|
#define USE_CONFIGURATION_STATE
|
||||||
|
#endif
|
||||||
|
|
||||||
// Setup crystal frequency for backward compatibility
|
// Setup crystal frequency on F4 for backward compatibility
|
||||||
// Should be set to zero for generic targets and set with CLI variable set system_hse_value.
|
// Should be set to zero for generic targets to ensure USB is working
|
||||||
|
// when unconfigured for targets with non-standard crystal.
|
||||||
|
// Can be set at runtime with with CLI parameter 'system_hse_value'.
|
||||||
|
#if !defined(STM32F4) || defined(USE_UNIFIED_TARGET)
|
||||||
#define SYSTEM_HSE_VALUE 0
|
#define SYSTEM_HSE_VALUE 0
|
||||||
#else
|
#else
|
||||||
#ifdef TARGET_XTAL_MHZ
|
#ifdef TARGET_XTAL_MHZ
|
||||||
|
@ -227,7 +237,7 @@
|
||||||
#else
|
#else
|
||||||
#define SYSTEM_HSE_VALUE (HSE_VALUE/1000000U)
|
#define SYSTEM_HSE_VALUE (HSE_VALUE/1000000U)
|
||||||
#endif
|
#endif
|
||||||
#endif // USE_UNIFIED_TARGET
|
#endif // !STM32F4 || USE_UNIFIED_TARGET
|
||||||
|
|
||||||
// Number of pins that needs pre-init
|
// Number of pins that needs pre-init
|
||||||
#ifdef USE_SPI
|
#ifdef USE_SPI
|
||||||
|
|
|
@ -187,6 +187,29 @@ osd_unittest_DEFINES := \
|
||||||
USE_RTC_TIME= \
|
USE_RTC_TIME= \
|
||||||
USE_ADC_INTERNAL=
|
USE_ADC_INTERNAL=
|
||||||
|
|
||||||
|
link_quality_unittest_SRC := \
|
||||||
|
$(USER_DIR)/osd/osd.c \
|
||||||
|
$(USER_DIR)/osd/osd_elements.c \
|
||||||
|
$(USER_DIR)/common/typeconversion.c \
|
||||||
|
$(USER_DIR)/drivers/display.c \
|
||||||
|
$(USER_DIR)/drivers/serial.c \
|
||||||
|
$(USER_DIR)/common/crc.c \
|
||||||
|
$(USER_DIR)/common/maths.c \
|
||||||
|
$(USER_DIR)/common/printf.c \
|
||||||
|
$(USER_DIR)/common/streambuf.c \
|
||||||
|
$(USER_DIR)/common/time.c \
|
||||||
|
$(USER_DIR)/fc/runtime_config.c \
|
||||||
|
$(USER_DIR)/common/bitarray.c \
|
||||||
|
$(USER_DIR)/fc/rc_modes.c \
|
||||||
|
$(USER_DIR)/rx/rx.c \
|
||||||
|
$(USER_DIR)/pg/pg.c \
|
||||||
|
$(USER_DIR)/rx/crsf.c \
|
||||||
|
$(USER_DIR)/pg/rx.c
|
||||||
|
|
||||||
|
link_quality_unittest_DEFINES := \
|
||||||
|
USE_OSD= \
|
||||||
|
USE_CRSF_LINK_STATISTICS= \
|
||||||
|
USE_RX_LINK_QUALITY_INFO=
|
||||||
|
|
||||||
pg_unittest_SRC := \
|
pg_unittest_SRC := \
|
||||||
$(USER_DIR)/pg/pg.c
|
$(USER_DIR)/pg/pg.c
|
||||||
|
|
545
src/test/unit/link_quality_unittest.cc
Normal file
545
src/test/unit/link_quality_unittest.cc
Normal file
|
@ -0,0 +1,545 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdio.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
#include "platform.h"
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
|
#include "blackbox/blackbox.h"
|
||||||
|
#include "blackbox/blackbox_io.h"
|
||||||
|
|
||||||
|
#include "common/time.h"
|
||||||
|
#include "common/crc.h"
|
||||||
|
#include "common/utils.h"
|
||||||
|
#include "common/printf.h"
|
||||||
|
#include "common/streambuf.h"
|
||||||
|
|
||||||
|
#include "drivers/max7456_symbols.h"
|
||||||
|
#include "drivers/persistent.h"
|
||||||
|
#include "drivers/serial.h"
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/core.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/rc_modes.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/mixer.h"
|
||||||
|
#include "flight/pid.h"
|
||||||
|
#include "flight/imu.h"
|
||||||
|
|
||||||
|
#include "io/beeper.h"
|
||||||
|
#include "io/gps.h"
|
||||||
|
#include "io/serial.h"
|
||||||
|
|
||||||
|
#include "osd/osd.h"
|
||||||
|
#include "osd/osd_elements.h"
|
||||||
|
|
||||||
|
#include "pg/pg.h"
|
||||||
|
#include "pg/pg_ids.h"
|
||||||
|
#include "pg/rx.h"
|
||||||
|
|
||||||
|
#include "rx/rx.h"
|
||||||
|
|
||||||
|
#include "sensors/battery.h"
|
||||||
|
|
||||||
|
attitudeEulerAngles_t attitude;
|
||||||
|
pidProfile_t *currentPidProfile;
|
||||||
|
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
||||||
|
uint8_t GPS_numSat;
|
||||||
|
uint16_t GPS_distanceToHome;
|
||||||
|
int16_t GPS_directionToHome;
|
||||||
|
uint32_t GPS_distanceFlownInCm;
|
||||||
|
int32_t GPS_coord[2];
|
||||||
|
gpsSolutionData_t gpsSol;
|
||||||
|
float motor[8];
|
||||||
|
float motorOutputHigh = 2047;
|
||||||
|
float motorOutputLow = 1000;
|
||||||
|
acc_t acc;
|
||||||
|
float accAverage[XYZ_AXIS_COUNT];
|
||||||
|
|
||||||
|
PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
|
||||||
|
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
||||||
|
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
|
||||||
|
PG_REGISTER(pilotConfig_t, pilotConfig, PG_PILOT_CONFIG, 0);
|
||||||
|
PG_REGISTER(imuConfig_t, imuConfig, PG_IMU_CONFIG, 0);
|
||||||
|
|
||||||
|
timeUs_t simulationTime = 0;
|
||||||
|
|
||||||
|
void osdRefresh(timeUs_t currentTimeUs);
|
||||||
|
uint16_t updateLinkQualitySamples(uint16_t value);
|
||||||
|
uint16_t scaleCrsfLq(uint16_t lqvalue);
|
||||||
|
#define LINK_QUALITY_SAMPLE_COUNT 16
|
||||||
|
}
|
||||||
|
|
||||||
|
/* #define DEBUG_OSD */
|
||||||
|
|
||||||
|
#include "unittest_macros.h"
|
||||||
|
#include "unittest_displayport.h"
|
||||||
|
#include "gtest/gtest.h"
|
||||||
|
|
||||||
|
extern "C" {
|
||||||
|
PG_REGISTER(flight3DConfig_t, flight3DConfig, PG_MOTOR_3D_CONFIG, 0);
|
||||||
|
|
||||||
|
boxBitmask_t rcModeActivationMask;
|
||||||
|
int16_t debug[DEBUG16_VALUE_COUNT];
|
||||||
|
uint8_t debugMode = 0;
|
||||||
|
|
||||||
|
uint16_t updateLinkQualitySamples(uint16_t value);
|
||||||
|
|
||||||
|
extern uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range);
|
||||||
|
}
|
||||||
|
void setDefaultSimulationState()
|
||||||
|
{
|
||||||
|
|
||||||
|
setLinkQualityDirect(LINK_QUALITY_MAX_VALUE);
|
||||||
|
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
* Performs a test of the OSD actions on arming.
|
||||||
|
* (reused throughout the test suite)
|
||||||
|
*/
|
||||||
|
void doTestArm(bool testEmpty = true)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
// craft has been armed
|
||||||
|
ENABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
|
// when
|
||||||
|
// sufficient OSD updates have been called
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// arming alert displayed
|
||||||
|
displayPortTestBufferSubstring(12, 7, "ARMED");
|
||||||
|
|
||||||
|
// given
|
||||||
|
// armed alert times out (0.5 seconds)
|
||||||
|
simulationTime += 0.5e6;
|
||||||
|
|
||||||
|
// when
|
||||||
|
// sufficient OSD updates have been called
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// arming alert disappears
|
||||||
|
#ifdef DEBUG_OSD
|
||||||
|
displayPortTestPrint();
|
||||||
|
#endif
|
||||||
|
if (testEmpty) {
|
||||||
|
displayPortTestBufferIsEmpty();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Auxiliary function. Test is there're stats that must be shown
|
||||||
|
*/
|
||||||
|
bool isSomeStatEnabled(void) {
|
||||||
|
return (osdConfigMutable()->enabled_stats != 0);
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Performs a test of the OSD actions on disarming.
|
||||||
|
* (reused throughout the test suite)
|
||||||
|
*/
|
||||||
|
void doTestDisarm()
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
// craft is disarmed after having been armed
|
||||||
|
DISABLE_ARMING_FLAG(ARMED);
|
||||||
|
|
||||||
|
// when
|
||||||
|
// sufficient OSD updates have been called
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// post flight statistics displayed
|
||||||
|
if (isSomeStatEnabled()) {
|
||||||
|
displayPortTestBufferSubstring(2, 2, " --- STATS ---");
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
/*
|
||||||
|
* Tests initialisation of the OSD and the power on splash screen.
|
||||||
|
*/
|
||||||
|
TEST(LQTest, TestInit)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
// display port is initialised
|
||||||
|
displayPortTestInit();
|
||||||
|
|
||||||
|
// and
|
||||||
|
// default state values are set
|
||||||
|
setDefaultSimulationState();
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this battery configuration (used for battery voltage elements)
|
||||||
|
batteryConfigMutable()->vbatmincellvoltage = 330;
|
||||||
|
batteryConfigMutable()->vbatmaxcellvoltage = 430;
|
||||||
|
|
||||||
|
// when
|
||||||
|
// OSD is initialised
|
||||||
|
osdInit(&testDisplayPort);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// display buffer should contain splash screen
|
||||||
|
displayPortTestBufferSubstring(7, 8, "MENU:THR MID");
|
||||||
|
displayPortTestBufferSubstring(11, 9, "+ YAW LEFT");
|
||||||
|
displayPortTestBufferSubstring(11, 10, "+ PITCH UP");
|
||||||
|
|
||||||
|
// when
|
||||||
|
// splash screen timeout has elapsed
|
||||||
|
simulationTime += 4e6;
|
||||||
|
osdUpdate(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// display buffer should be empty
|
||||||
|
#ifdef DEBUG_OSD
|
||||||
|
displayPortTestPrint();
|
||||||
|
#endif
|
||||||
|
displayPortTestBufferIsEmpty();
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
* Tests the Tests the OSD_LINK_QUALITY element updateLinkQualitySamples default LQ_SOURCE_NONE
|
||||||
|
*/
|
||||||
|
TEST(LQTest, TestElement_LQ_SOURCE_NONE_SAMPLES)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
|
||||||
|
|
||||||
|
linkQualitySource = LQ_SOURCE_NONE;
|
||||||
|
|
||||||
|
osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
|
||||||
|
osdConfigMutable()->link_quality_alarm = 0;
|
||||||
|
|
||||||
|
osdAnalyzeActiveElements();
|
||||||
|
|
||||||
|
// when samples populated 100%
|
||||||
|
for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
|
||||||
|
setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
|
||||||
|
}
|
||||||
|
|
||||||
|
|
||||||
|
displayClearScreen(&testDisplayPort);
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
displayPortTestBufferSubstring(8, 1, "9");
|
||||||
|
|
||||||
|
// when updateLinkQualitySamples used 50% rounds to 4
|
||||||
|
for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
|
||||||
|
setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
|
||||||
|
setLinkQualityDirect(updateLinkQualitySamples(0));
|
||||||
|
}
|
||||||
|
|
||||||
|
displayClearScreen(&testDisplayPort);
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
displayPortTestBufferSubstring(8, 1, "4");
|
||||||
|
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
* Tests the Tests the OSD_LINK_QUALITY element values default LQ_SOURCE_NONE
|
||||||
|
*/
|
||||||
|
TEST(LQTest, TestElement_LQ_SOURCE_NONE_VALUES)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
|
||||||
|
|
||||||
|
linkQualitySource = LQ_SOURCE_NONE;
|
||||||
|
|
||||||
|
osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
|
||||||
|
osdConfigMutable()->link_quality_alarm = 0;
|
||||||
|
|
||||||
|
osdAnalyzeActiveElements();
|
||||||
|
// when LINK_QUALITY_MAX_VALUE to 1 by 10%
|
||||||
|
uint16_t testscale = 0;
|
||||||
|
for (int testdigit = 10; testdigit > 0; testdigit--) {
|
||||||
|
testscale = testdigit * 102.3;
|
||||||
|
setLinkQualityDirect(testscale);
|
||||||
|
displayClearScreen(&testDisplayPort);
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
#ifdef DEBUG_OSD
|
||||||
|
printf("%d %d\n",testscale, testdigit);
|
||||||
|
displayPortTestPrint();
|
||||||
|
#endif
|
||||||
|
// then
|
||||||
|
if (testdigit >= 10){
|
||||||
|
displayPortTestBufferSubstring(7, 1," 9");
|
||||||
|
}else{
|
||||||
|
displayPortTestBufferSubstring(7, 1," %1d", testdigit - 1);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
* Tests the OSD_LINK_QUALITY element LQ RX_PROTOCOL_CRSF.
|
||||||
|
*/
|
||||||
|
TEST(LQTest, TestElementLQ_PROTOCOL_CRSF_VALUES)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
|
||||||
|
|
||||||
|
osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
|
||||||
|
osdConfigMutable()->link_quality_alarm = 0;
|
||||||
|
|
||||||
|
osdAnalyzeActiveElements();
|
||||||
|
|
||||||
|
displayClearScreen(&testDisplayPort);
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// crsf setLinkQualityDirect 0-300;
|
||||||
|
|
||||||
|
for (uint16_t x = 0; x <= 300; x++) {
|
||||||
|
// when x scaled
|
||||||
|
setLinkQualityDirect(scaleCrsfLq(x));
|
||||||
|
// then rxGetLinkQuality Osd should be x
|
||||||
|
displayClearScreen(&testDisplayPort);
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
displayPortTestBufferSubstring(8, 1,"%3d", x);
|
||||||
|
|
||||||
|
}
|
||||||
|
}
|
||||||
|
/*
|
||||||
|
* Tests the LQ Alarms
|
||||||
|
*
|
||||||
|
*/
|
||||||
|
TEST(LQTest, TestLQAlarm)
|
||||||
|
{
|
||||||
|
// given
|
||||||
|
// default state is set
|
||||||
|
setDefaultSimulationState();
|
||||||
|
|
||||||
|
linkQualitySource = LQ_SOURCE_NONE;
|
||||||
|
|
||||||
|
// and
|
||||||
|
// the following OSD elements are visible
|
||||||
|
|
||||||
|
osdConfigMutable()->item_pos[OSD_LINK_QUALITY] = OSD_POS(8, 1) | OSD_PROFILE_1_FLAG;
|
||||||
|
|
||||||
|
// and
|
||||||
|
// this set of alarm values
|
||||||
|
|
||||||
|
osdConfigMutable()->link_quality_alarm = 80;
|
||||||
|
stateFlags |= GPS_FIX | GPS_FIX_HOME;
|
||||||
|
|
||||||
|
osdAnalyzeActiveElements();
|
||||||
|
|
||||||
|
// and
|
||||||
|
// using the metric unit system
|
||||||
|
osdConfigMutable()->units = OSD_UNIT_METRIC;
|
||||||
|
|
||||||
|
// when
|
||||||
|
// the craft is armed
|
||||||
|
doTestArm(false);
|
||||||
|
|
||||||
|
for (int x = 0; x < LINK_QUALITY_SAMPLE_COUNT; x++) {
|
||||||
|
setLinkQualityDirect(updateLinkQualitySamples(LINK_QUALITY_MAX_VALUE));
|
||||||
|
}
|
||||||
|
|
||||||
|
// then
|
||||||
|
// no elements should flash as all values are out of alarm range
|
||||||
|
for (int i = 0; i < 30; i++) {
|
||||||
|
// Check for visibility every 100ms, elements should always be visible
|
||||||
|
simulationTime += 0.1e6;
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
#ifdef DEBUG_OSD
|
||||||
|
printf("%d\n", i);
|
||||||
|
#endif
|
||||||
|
displayPortTestBufferSubstring(8, 1, "9");
|
||||||
|
|
||||||
|
}
|
||||||
|
|
||||||
|
setLinkQualityDirect(512);
|
||||||
|
simulationTime += 60e6;
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
// then
|
||||||
|
// elements showing values in alarm range should flash
|
||||||
|
for (int i = 0; i < 15; i++) {
|
||||||
|
// Blinking should happen at 5Hz
|
||||||
|
simulationTime += 0.2e6;
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
|
||||||
|
#ifdef DEBUG_OSD
|
||||||
|
printf("%d\n", i);
|
||||||
|
displayPortTestPrint();
|
||||||
|
#endif
|
||||||
|
if (i % 2 == 0) {
|
||||||
|
displayPortTestBufferSubstring(8, 1, "5");
|
||||||
|
} else {
|
||||||
|
displayPortTestBufferIsEmpty();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
doTestDisarm();
|
||||||
|
simulationTime += 60e6;
|
||||||
|
osdRefresh(simulationTime);
|
||||||
|
}
|
||||||
|
|
||||||
|
// STUBS
|
||||||
|
extern "C" {
|
||||||
|
|
||||||
|
uint32_t micros() {
|
||||||
|
return simulationTime;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t millis() {
|
||||||
|
return micros() / 1000;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool featureIsEnabled(uint32_t) { return true; }
|
||||||
|
void beeperConfirmationBeeps(uint8_t) {}
|
||||||
|
bool isBeeperOn() { return false; }
|
||||||
|
uint8_t getCurrentPidProfileIndex() { return 0; }
|
||||||
|
uint8_t getCurrentControlRateProfileIndex() { return 0; }
|
||||||
|
batteryState_e getBatteryState() { return BATTERY_OK; }
|
||||||
|
uint8_t getBatteryCellCount() { return 4; }
|
||||||
|
uint16_t getBatteryVoltage() { return 1680; }
|
||||||
|
uint16_t getBatteryAverageCellVoltage() { return 420; }
|
||||||
|
int32_t getAmperage() { return 0; }
|
||||||
|
int32_t getMAhDrawn() { return 0; }
|
||||||
|
int32_t getEstimatedAltitudeCm() { return 0; }
|
||||||
|
int32_t getEstimatedVario() { return 0; }
|
||||||
|
unsigned int blackboxGetLogNumber() { return 0; }
|
||||||
|
bool isBlackboxDeviceWorking() { return true; }
|
||||||
|
bool isBlackboxDeviceFull() { return false; }
|
||||||
|
serialPort_t *openSerialPort(serialPortIdentifier_e, serialPortFunction_e, serialReceiveCallbackPtr, void *, uint32_t, portMode_e, portOptions_e) {return NULL;}
|
||||||
|
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
|
||||||
|
bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return false;}
|
||||||
|
bool cmsDisplayPortRegister(displayPort_t *) { return false; }
|
||||||
|
uint16_t getCoreTemperatureCelsius(void) { return 0; }
|
||||||
|
bool isFlipOverAfterCrashActive(void) { return false; }
|
||||||
|
float pidItermAccelerator(void) { return 1.0; }
|
||||||
|
uint8_t getMotorCount(void){ return 4; }
|
||||||
|
bool areMotorsRunning(void){ return true; }
|
||||||
|
bool pidOsdAntiGravityActive(void) { return false; }
|
||||||
|
bool failsafeIsActive(void) { return false; }
|
||||||
|
bool gpsRescueIsConfigured(void) { return false; }
|
||||||
|
int8_t calculateThrottlePercent(void) { return 0; }
|
||||||
|
uint32_t persistentObjectRead(persistentObjectId_e) { return 0; }
|
||||||
|
void persistentObjectWrite(persistentObjectId_e, uint32_t) {}
|
||||||
|
void failsafeOnRxSuspend(uint32_t ) {}
|
||||||
|
void failsafeOnRxResume(void) {}
|
||||||
|
void featureDisable(uint32_t) { }
|
||||||
|
bool rxMspFrameComplete(void) { return false; }
|
||||||
|
bool isPPMDataBeingReceived(void) { return false; }
|
||||||
|
bool isPWMDataBeingReceived(void) { return false; }
|
||||||
|
void resetPPMDataReceivedState(void){ }
|
||||||
|
void failsafeOnValidDataReceived(void) { }
|
||||||
|
void failsafeOnValidDataFailed(void) { }
|
||||||
|
|
||||||
|
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(initialRxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback);
|
||||||
|
|
||||||
|
bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
|
||||||
|
{
|
||||||
|
UNUSED(rxConfig);
|
||||||
|
UNUSED(rxRuntimeConfig);
|
||||||
|
UNUSED(callback);
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
float pt1FilterGain(float f_cut, float dT)
|
||||||
|
{
|
||||||
|
UNUSED(f_cut);
|
||||||
|
UNUSED(dT);
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
void pt1FilterInit(pt1Filter_t *filter, float k)
|
||||||
|
{
|
||||||
|
UNUSED(filter);
|
||||||
|
UNUSED(k);
|
||||||
|
}
|
||||||
|
|
||||||
|
float pt1FilterApply(pt1Filter_t *filter, float input)
|
||||||
|
{
|
||||||
|
UNUSED(filter);
|
||||||
|
UNUSED(input);
|
||||||
|
return 0.0;
|
||||||
|
}
|
||||||
|
|
||||||
|
}
|
|
@ -81,6 +81,7 @@ extern "C" {
|
||||||
float motorOutputHigh = 2047;
|
float motorOutputHigh = 2047;
|
||||||
float motorOutputLow = 1000;
|
float motorOutputLow = 1000;
|
||||||
|
|
||||||
|
linkQualitySource_e linkQualitySource;
|
||||||
|
|
||||||
acc_t acc;
|
acc_t acc;
|
||||||
float accAverage[XYZ_AXIS_COUNT];
|
float accAverage[XYZ_AXIS_COUNT];
|
||||||
|
@ -414,6 +415,9 @@ TEST(OsdTest, TestStatsMetric)
|
||||||
// using metric unit system
|
// using metric unit system
|
||||||
osdConfigMutable()->units = OSD_UNIT_METRIC;
|
osdConfigMutable()->units = OSD_UNIT_METRIC;
|
||||||
|
|
||||||
|
// set timer 1 configuration to tenths precision
|
||||||
|
osdConfigMutable()->timers[OSD_TIMER_1] = OSD_TIMER(OSD_TIMER_SRC_TOTAL_ARMED, OSD_TIMER_PREC_TENTHS, 0);
|
||||||
|
|
||||||
// and
|
// and
|
||||||
// default state values are set
|
// default state values are set
|
||||||
setDefaultSimulationState();
|
setDefaultSimulationState();
|
||||||
|
@ -446,7 +450,7 @@ TEST(OsdTest, TestStatsMetric)
|
||||||
// statistics screen should display the following
|
// statistics screen should display the following
|
||||||
int row = 3;
|
int row = 3;
|
||||||
displayPortTestBufferSubstring(2, row++, "2017-11-19 10:12:");
|
displayPortTestBufferSubstring(2, row++, "2017-11-19 10:12:");
|
||||||
displayPortTestBufferSubstring(2, row++, "TOTAL ARM : 00:07.50");
|
displayPortTestBufferSubstring(2, row++, "TOTAL ARM : 00:07.5");
|
||||||
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:02");
|
displayPortTestBufferSubstring(2, row++, "LAST ARM : 00:02");
|
||||||
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 2.0%c", SYM_M);
|
displayPortTestBufferSubstring(2, row++, "MAX ALTITUDE : 2.0%c", SYM_M);
|
||||||
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 28");
|
displayPortTestBufferSubstring(2, row++, "MAX SPEED : 28");
|
||||||
|
@ -1096,7 +1100,7 @@ extern "C" {
|
||||||
|
|
||||||
uint8_t getRssiPercent(void) { return scaleRange(rssi, 0, RSSI_MAX_VALUE, 0, 100); }
|
uint8_t getRssiPercent(void) { return scaleRange(rssi, 0, RSSI_MAX_VALUE, 0, 100); }
|
||||||
|
|
||||||
uint8_t rxGetLinkQuality(void) { return LINK_QUALITY_MAX_VALUE; }
|
uint16_t rxGetLinkQuality(void) { return LINK_QUALITY_MAX_VALUE; }
|
||||||
|
|
||||||
uint16_t getCoreTemperatureCelsius(void) { return simulationCoreTemperature; }
|
uint16_t getCoreTemperatureCelsius(void) { return simulationCoreTemperature; }
|
||||||
|
|
||||||
|
|
82
unified_targets/configs/AIRBOTF7.config
Normal file
82
unified_targets/configs/AIRBOTF7.config
Normal file
|
@ -0,0 +1,82 @@
|
||||||
|
# Betaflight / STM32F7X2 (S7X2) 4.1.0 May 6 2019 / 18:09:02 (d3677b79a) MSP API: 1.42
|
||||||
|
|
||||||
|
board_name AIRBOTF7
|
||||||
|
manufacturer_id AIRB
|
||||||
|
|
||||||
|
# resources
|
||||||
|
resource BEEPER 1 B00
|
||||||
|
resource MOTOR 1 C08
|
||||||
|
resource MOTOR 2 B06
|
||||||
|
resource MOTOR 3 C09
|
||||||
|
resource MOTOR 4 B07
|
||||||
|
resource LED_STRIP 1 A15
|
||||||
|
resource SERIAL_TX 1 A09
|
||||||
|
resource SERIAL_TX 2 A02
|
||||||
|
resource SERIAL_TX 3 C10
|
||||||
|
resource SERIAL_TX 4 A00
|
||||||
|
resource SERIAL_TX 5 C12
|
||||||
|
resource SERIAL_TX 6 C06
|
||||||
|
resource SERIAL_RX 1 A10
|
||||||
|
resource SERIAL_RX 3 C11
|
||||||
|
resource SERIAL_RX 4 A01
|
||||||
|
resource SERIAL_RX 6 C07
|
||||||
|
resource I2C_SCL 1 B08
|
||||||
|
resource I2C_SDA 1 B09
|
||||||
|
resource LED 1 B12
|
||||||
|
resource SPI_SCK 1 A05
|
||||||
|
resource SPI_SCK 2 B13
|
||||||
|
resource SPI_SCK 3 B03
|
||||||
|
resource SPI_MISO 1 A06
|
||||||
|
resource SPI_MISO 2 B14
|
||||||
|
resource SPI_MISO 3 B04
|
||||||
|
resource SPI_MOSI 1 A07
|
||||||
|
resource SPI_MOSI 2 B15
|
||||||
|
resource SPI_MOSI 3 B05
|
||||||
|
resource ADC_BATT 1 C00
|
||||||
|
resource ADC_RSSI 1 C01
|
||||||
|
resource ADC_CURR 1 C02
|
||||||
|
resource FLASH_CS 1 A03
|
||||||
|
resource OSD_CS 1 C15
|
||||||
|
resource GYRO_CS 1 D02
|
||||||
|
resource GYRO_CS 2 C04
|
||||||
|
|
||||||
|
# timer
|
||||||
|
timer A15 0
|
||||||
|
timer A08 0
|
||||||
|
timer C08 1
|
||||||
|
timer B06 0
|
||||||
|
timer C09 1
|
||||||
|
timer B07 0
|
||||||
|
|
||||||
|
# dma
|
||||||
|
dma ADC 1 1
|
||||||
|
# ADC 1: DMA2 Stream 4 Channel 0
|
||||||
|
dma pin A15 0
|
||||||
|
# pin A15: DMA1 Stream 5 Channel 3
|
||||||
|
dma pin A08 0
|
||||||
|
# pin A08: DMA2 Stream 6 Channel 0
|
||||||
|
dma pin C08 0
|
||||||
|
# pin C08: DMA2 Stream 2 Channel 0
|
||||||
|
dma pin B06 0
|
||||||
|
# pin B06: DMA1 Stream 0 Channel 2
|
||||||
|
dma pin C09 0
|
||||||
|
# pin C09: DMA2 Stream 7 Channel 7
|
||||||
|
dma pin B07 0
|
||||||
|
# pin B07: DMA1 Stream 3 Channel 2
|
||||||
|
|
||||||
|
# master
|
||||||
|
set blackbox_device = SPIFLASH
|
||||||
|
set dshot_burst = ON
|
||||||
|
set current_meter = ADC
|
||||||
|
set battery_meter = ADC
|
||||||
|
set ibata_scale = 179
|
||||||
|
set beeper_inversion = ON
|
||||||
|
set beeper_od = OFF
|
||||||
|
set max7456_spi_bus = 2
|
||||||
|
set flash_spi_bus = 1
|
||||||
|
set gyro_1_bustype = SPI
|
||||||
|
set gyro_1_spibus = 3
|
||||||
|
set gyro_1_sensor_align = CW90
|
||||||
|
set gyro_2_bustype = SPI
|
||||||
|
set gyro_2_spibus = 1
|
||||||
|
set gyro_2_sensor_align = CW0
|
|
@ -83,7 +83,6 @@ dma pin B08 0 # pin B08: DMA1 Stream 7 Channel 2
|
||||||
dma pin B01 0 # pin B01: DMA1 Stream 2 Channel 5
|
dma pin B01 0 # pin B01: DMA1 Stream 2 Channel 5
|
||||||
|
|
||||||
# master
|
# master
|
||||||
set system_hse_mhz = 8
|
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
resource RX_BIND_PLUG 1 B02
|
resource RX_BIND_PLUG 1 B02
|
||||||
resource CAMERA_CONTROL 1 B03
|
resource CAMERA_CONTROL 1 B03
|
||||||
|
|
|
@ -141,7 +141,6 @@ set osd_ah_sbar_pos = 2254
|
||||||
set osd_ah_pos = 2126
|
set osd_ah_pos = 2126
|
||||||
set osd_compass_bar_pos = 106
|
set osd_compass_bar_pos = 106
|
||||||
set osd_warnings_pos = 2377
|
set osd_warnings_pos = 2377
|
||||||
set system_hse_mhz = 8
|
|
||||||
set vcd_video_system = NTSC
|
set vcd_video_system = NTSC
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
|
@ -150,4 +149,4 @@ set flash_spi_bus = 3
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
set gyro_1_spibus = 1
|
set gyro_1_spibus = 1
|
||||||
set gyro_1_sensor_align = CW0
|
set gyro_1_sensor_align = CW0
|
||||||
set gyro_2_spibus = 1
|
set gyro_2_spibus = 1
|
||||||
|
|
|
@ -120,7 +120,6 @@ set battery_meter = ADC
|
||||||
set ibata_scale = 170
|
set ibata_scale = 170
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set pinio_box = 40,41,255,255
|
set pinio_box = 40,41,255,255
|
||||||
|
@ -129,4 +128,4 @@ set gyro_1_bustype = SPI
|
||||||
set gyro_1_spibus = 1
|
set gyro_1_spibus = 1
|
||||||
set gyro_1_sensor_align = CW270FLIP
|
set gyro_1_sensor_align = CW270FLIP
|
||||||
set gyro_2_spibus = 1
|
set gyro_2_spibus = 1
|
||||||
set gyro_2_sensor_align = CW270
|
set gyro_2_sensor_align = CW270
|
||||||
|
|
|
@ -91,7 +91,6 @@ set current_meter = ADC
|
||||||
set battery_meter = ADC
|
set battery_meter = ADC
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 3
|
set max7456_spi_bus = 3
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set flash_spi_bus = 2
|
set flash_spi_bus = 2
|
||||||
|
|
98
unified_targets/configs/FURYF4OSD.config
Normal file
98
unified_targets/configs/FURYF4OSD.config
Normal file
|
@ -0,0 +1,98 @@
|
||||||
|
# Betaflight / STM32F405 (S405) 4.1.0 May 11 2019 / 13:09:51 (a8e9dd94e) MSP API: 1.42
|
||||||
|
|
||||||
|
board_name FURYF4OSD
|
||||||
|
manufacturer_id DIAT
|
||||||
|
|
||||||
|
# resources
|
||||||
|
resource BEEPER 1 A08
|
||||||
|
resource MOTOR 1 A03
|
||||||
|
resource MOTOR 2 B00
|
||||||
|
resource MOTOR 3 B01
|
||||||
|
resource MOTOR 4 A02
|
||||||
|
resource PPM 1 C09
|
||||||
|
resource LED_STRIP 1 A00
|
||||||
|
resource SERIAL_TX 1 A09
|
||||||
|
resource SERIAL_TX 3 B10
|
||||||
|
resource SERIAL_TX 6 C06
|
||||||
|
resource SERIAL_RX 1 A10
|
||||||
|
resource SERIAL_RX 3 B11
|
||||||
|
resource SERIAL_RX 6 C07
|
||||||
|
resource INVERTER 1 C00
|
||||||
|
resource I2C_SCL 1 B06
|
||||||
|
resource I2C_SDA 1 B07
|
||||||
|
resource LED 1 B05
|
||||||
|
resource LED 2 B04
|
||||||
|
resource SPI_SCK 1 A05
|
||||||
|
resource SPI_SCK 2 B13
|
||||||
|
resource SPI_SCK 3 C10
|
||||||
|
resource SPI_MISO 1 A06
|
||||||
|
resource SPI_MISO 2 B14
|
||||||
|
resource SPI_MISO 3 C11
|
||||||
|
resource SPI_MOSI 1 A07
|
||||||
|
resource SPI_MOSI 2 B15
|
||||||
|
resource SPI_MOSI 3 C12
|
||||||
|
resource ESCSERIAL 1 C09
|
||||||
|
resource CAMERA_CONTROL 1 B09
|
||||||
|
resource ADC_BATT 1 C01
|
||||||
|
resource ADC_RSSI 1 C02
|
||||||
|
resource ADC_CURR 1 C03
|
||||||
|
resource FLASH_CS 1 B03
|
||||||
|
resource OSD_CS 1 B12
|
||||||
|
resource GYRO_EXTI 1 C04
|
||||||
|
resource GYRO_CS 1 A04
|
||||||
|
resource USB_DETECT 1 C05
|
||||||
|
|
||||||
|
# timer
|
||||||
|
timer C09 1
|
||||||
|
timer A03 0
|
||||||
|
timer B00 1
|
||||||
|
timer B01 0
|
||||||
|
timer A02 0
|
||||||
|
timer A00 1
|
||||||
|
timer B09 1
|
||||||
|
|
||||||
|
# dma
|
||||||
|
dma ADC 1 1
|
||||||
|
# ADC 1: DMA2 Stream 4 Channel 0
|
||||||
|
dma pin C09 0
|
||||||
|
# pin C09: DMA2 Stream 7 Channel 7
|
||||||
|
dma pin A03 1
|
||||||
|
# pin A03: DMA1 Stream 6 Channel 3
|
||||||
|
dma pin B00 0
|
||||||
|
# pin B00: DMA1 Stream 7 Channel 5
|
||||||
|
dma pin B01 0
|
||||||
|
# pin B01: DMA2 Stream 6 Channel 0
|
||||||
|
dma pin A02 0
|
||||||
|
# pin A02: DMA1 Stream 1 Channel 3
|
||||||
|
dma pin A00 0
|
||||||
|
# pin A00: DMA1 Stream 2 Channel 6
|
||||||
|
|
||||||
|
# feature
|
||||||
|
feature -RX_PARALLEL_PWM
|
||||||
|
feature RX_SERIAL
|
||||||
|
feature OSD
|
||||||
|
|
||||||
|
# serial
|
||||||
|
serial 2 8192 115200 57600 0 115200
|
||||||
|
|
||||||
|
# master
|
||||||
|
set mag_hardware = NONE
|
||||||
|
set baro_hardware = NONE
|
||||||
|
set rssi_src_frame_errors = ON
|
||||||
|
set serialrx_provider = SBUS
|
||||||
|
set blackbox_device = SPIFLASH
|
||||||
|
set dshot_idle_value = 300
|
||||||
|
set motor_pwm_protocol = DSHOT600
|
||||||
|
set current_meter = ADC
|
||||||
|
set battery_meter = ADC
|
||||||
|
set beeper_inversion = ON
|
||||||
|
set beeper_od = OFF
|
||||||
|
set pid_process_denom = 1
|
||||||
|
set system_hse_mhz = 8
|
||||||
|
set max7456_spi_bus = 2
|
||||||
|
set dashboard_i2c_bus = 1
|
||||||
|
set flash_spi_bus = 3
|
||||||
|
set gyro_1_bustype = SPI
|
||||||
|
set gyro_1_spibus = 1
|
||||||
|
set gyro_1_sensor_align = CW180
|
||||||
|
set gyro_2_spibus = 1
|
|
@ -112,7 +112,6 @@ set beeper_frequency = 0
|
||||||
set sdcard_detect_inverted = ON
|
set sdcard_detect_inverted = ON
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 4
|
set sdcard_spi_bus = 4
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_clock = DEFAULT
|
set max7456_clock = DEFAULT
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set max7456_preinit_opu = OFF
|
set max7456_preinit_opu = OFF
|
||||||
|
|
|
@ -92,7 +92,6 @@ set battery_meter = ADC
|
||||||
set ibata_scale = 450
|
set ibata_scale = 450
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set flash_spi_bus = 3
|
set flash_spi_bus = 3
|
||||||
|
|
|
@ -91,7 +91,6 @@ set beeper_od = OFF
|
||||||
set sdcard_detect_inverted = ON
|
set sdcard_detect_inverted = ON
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 1
|
set sdcard_spi_bus = 1
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
|
|
|
@ -85,7 +85,6 @@ set current_meter = ADC
|
||||||
set battery_meter = ADC
|
set battery_meter = ADC
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set flash_spi_bus = 1
|
set flash_spi_bus = 1
|
||||||
|
|
|
@ -1,4 +1,4 @@
|
||||||
# Betaflight / STM32F7X2 (S7X2) 4.0.0 Mar 15 2019 / 08:10:21 (d50e721) MSP API: 1.41
|
# Betaflight / STM32F7X2 (S7X2) 4.1.0 May 12 2019 / 23:09:44 (a8e9dd94e) MSP API: 1.42
|
||||||
|
|
||||||
board_name MATEKF722
|
board_name MATEKF722
|
||||||
manufacturer_id MTKS
|
manufacturer_id MTKS
|
||||||
|
@ -96,6 +96,7 @@ set mag_bustype = I2C
|
||||||
set mag_i2c_device = 1
|
set mag_i2c_device = 1
|
||||||
set baro_bustype = I2C
|
set baro_bustype = I2C
|
||||||
set baro_i2c_device = 1
|
set baro_i2c_device = 1
|
||||||
|
set blackbox_device = SDCARD
|
||||||
set dshot_burst = ON
|
set dshot_burst = ON
|
||||||
set current_meter = ADC
|
set current_meter = ADC
|
||||||
set battery_meter = ADC
|
set battery_meter = ADC
|
||||||
|
@ -104,10 +105,9 @@ set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 3
|
set sdcard_spi_bus = 3
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
set gyro_1_spibus = 1
|
set gyro_1_spibus = 1
|
||||||
set gyro_1_sensor_align = CW180
|
set gyro_1_sensor_align = CW180
|
||||||
set gyro_2_spibus = 1
|
set gyro_2_spibus = 1
|
||||||
|
|
|
@ -113,7 +113,6 @@ set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 3
|
set sdcard_spi_bus = 3
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set flash_spi_bus = 3
|
set flash_spi_bus = 3
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
|
|
|
@ -7,9 +7,6 @@ manufacturer_id BKMN
|
||||||
|
|
||||||
defaults nosave
|
defaults nosave
|
||||||
|
|
||||||
# External crystal frequency
|
|
||||||
set system_hse_mhz = 8
|
|
||||||
|
|
||||||
# Basic I/O
|
# Basic I/O
|
||||||
resource LED 1 B06
|
resource LED 1 B06
|
||||||
resource LED 2 B05
|
resource LED 2 B05
|
||||||
|
|
|
@ -37,6 +37,7 @@ resource ADC_CURR 1 C01
|
||||||
resource FLASH_CS 1 A02
|
resource FLASH_CS 1 A02
|
||||||
resource OSD_CS 1 C15
|
resource OSD_CS 1 C15
|
||||||
resource GYRO_CS 1 D02
|
resource GYRO_CS 1 D02
|
||||||
|
resource GYRO_CS 2 C04
|
||||||
|
|
||||||
# timer
|
# timer
|
||||||
timer A15 0
|
timer A15 0
|
||||||
|
@ -81,10 +82,10 @@ set ibata_scale = 179
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set pid_process_denom = 1
|
set pid_process_denom = 1
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set flash_spi_bus = 1
|
set flash_spi_bus = 1
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
set gyro_1_spibus = 3
|
set gyro_1_spibus = 3
|
||||||
set gyro_1_sensor_align = CW0
|
set gyro_1_sensor_align = CW0
|
||||||
set gyro_2_spibus = 3
|
set gyro_2_spibus = 1
|
||||||
|
set gyro_2_sensor_align = CW0
|
||||||
|
|
|
@ -81,7 +81,6 @@ set ibata_scale = 179
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set pid_process_denom = 1
|
set pid_process_denom = 1
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set flash_spi_bus = 1
|
set flash_spi_bus = 1
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
|
|
|
@ -100,7 +100,6 @@ set beeper_od = OFF
|
||||||
set sdcard_detect_inverted = ON
|
set sdcard_detect_inverted = ON
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 4
|
set sdcard_spi_bus = 4
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 2
|
set dashboard_i2c_bus = 2
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
|
|
|
@ -84,7 +84,6 @@ set current_meter = ADC
|
||||||
set battery_meter = ADC
|
set battery_meter = ADC
|
||||||
set beeper_inversion = ON
|
set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set flash_spi_bus = 3
|
set flash_spi_bus = 3
|
||||||
|
|
|
@ -120,7 +120,6 @@ set beeper_inversion = ON
|
||||||
set beeper_od = OFF
|
set beeper_od = OFF
|
||||||
set sdcard_mode = SPI
|
set sdcard_mode = SPI
|
||||||
set sdcard_spi_bus = 3
|
set sdcard_spi_bus = 3
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set gyro_1_bustype = SPI
|
set gyro_1_bustype = SPI
|
||||||
|
|
|
@ -93,7 +93,6 @@ set blackbox_device = NONE
|
||||||
set dshot_burst = ON
|
set dshot_burst = ON
|
||||||
set current_meter = ADC
|
set current_meter = ADC
|
||||||
set battery_meter = ADC
|
set battery_meter = ADC
|
||||||
set system_hse_mhz = 8
|
|
||||||
set max7456_spi_bus = 2
|
set max7456_spi_bus = 2
|
||||||
set dashboard_i2c_bus = 1
|
set dashboard_i2c_bus = 1
|
||||||
set gyro_1_spibus = 1
|
set gyro_1_spibus = 1
|
||||||
|
|
116
unified_targets/configs/VGOODRCF4.config
Normal file
116
unified_targets/configs/VGOODRCF4.config
Normal file
|
@ -0,0 +1,116 @@
|
||||||
|
# Betaflight / VGOODRCF4 (VGF4) 4.1.0 Apr 30 2019 / 09:30:28 () MSP API: 1.42
|
||||||
|
|
||||||
|
board_name VGOODRCF4
|
||||||
|
manufacturer_id VGRC
|
||||||
|
|
||||||
|
# resources
|
||||||
|
resource BEEPER 1 C13
|
||||||
|
resource MOTOR 1 A09
|
||||||
|
resource MOTOR 2 A10
|
||||||
|
resource MOTOR 3 B00
|
||||||
|
resource MOTOR 4 B01
|
||||||
|
resource MOTOR 5 C08
|
||||||
|
resource MOTOR 6 C09
|
||||||
|
resource PPM 1 C07
|
||||||
|
resource LED_STRIP 1 A08
|
||||||
|
resource SERIAL_TX 1 B06
|
||||||
|
resource SERIAL_TX 2 A02
|
||||||
|
resource SERIAL_TX 3 C10
|
||||||
|
resource SERIAL_TX 4 A00
|
||||||
|
resource SERIAL_TX 5 C12
|
||||||
|
resource SERIAL_TX 6 C06
|
||||||
|
resource SERIAL_TX 11 B02
|
||||||
|
resource SERIAL_RX 1 B07
|
||||||
|
resource SERIAL_RX 2 A03
|
||||||
|
resource SERIAL_RX 3 C11
|
||||||
|
resource SERIAL_RX 4 A01
|
||||||
|
resource SERIAL_RX 5 D02
|
||||||
|
resource SERIAL_RX 6 C07
|
||||||
|
resource SERIAL_RX 11 C05
|
||||||
|
resource I2C_SCL 1 B08
|
||||||
|
resource I2C_SCL 2 B10
|
||||||
|
resource I2C_SDA 1 B09
|
||||||
|
resource I2C_SDA 2 B11
|
||||||
|
resource LED 1 C14
|
||||||
|
resource LED 2 C15
|
||||||
|
resource SPI_SCK 1 A05
|
||||||
|
resource SPI_SCK 2 B13
|
||||||
|
resource SPI_SCK 3 B03
|
||||||
|
resource SPI_MISO 1 A06
|
||||||
|
resource SPI_MISO 2 B14
|
||||||
|
resource SPI_MISO 3 B04
|
||||||
|
resource SPI_MOSI 1 A07
|
||||||
|
resource SPI_MOSI 2 B15
|
||||||
|
resource SPI_MOSI 3 B05
|
||||||
|
resource CAMERA_CONTROL 1 C09
|
||||||
|
resource ADC_BATT 1 C01
|
||||||
|
resource ADC_RSSI 1 C02
|
||||||
|
resource ADC_CURR 1 C00
|
||||||
|
resource PINIO 1 A13
|
||||||
|
resource PINIO 2 A14
|
||||||
|
resource FLASH_CS 1 B12
|
||||||
|
resource OSD_CS 1 A04
|
||||||
|
resource GYRO_EXTI 1 C03
|
||||||
|
resource GYRO_CS 1 A15
|
||||||
|
resource USB_DETECT 1 C04
|
||||||
|
|
||||||
|
# timer
|
||||||
|
timer C07 1
|
||||||
|
timer A09 0
|
||||||
|
timer B00 1
|
||||||
|
timer B01 1
|
||||||
|
timer C08 1
|
||||||
|
timer C09 1
|
||||||
|
timer A08 0
|
||||||
|
|
||||||
|
# dma
|
||||||
|
dma ADC 2 1
|
||||||
|
# ADC 2: DMA2 Stream 3 Channel 1
|
||||||
|
dma pin C07 0
|
||||||
|
# pin C07: DMA2 Stream 2 Channel 0
|
||||||
|
dma pin A09 0
|
||||||
|
# pin A09: DMA2 Stream 6 Channel 0
|
||||||
|
dma pin B00 0
|
||||||
|
# pin B00: DMA1 Stream 7 Channel 5
|
||||||
|
dma pin B01 0
|
||||||
|
# pin B01: DMA1 Stream 2 Channel 5
|
||||||
|
dma pin C08 0
|
||||||
|
# pin C08: DMA2 Stream 2 Channel 0
|
||||||
|
dma pin C09 0
|
||||||
|
# pin C09: DMA2 Stream 7 Channel 7
|
||||||
|
dma pin A08 1
|
||||||
|
# pin A08: DMA2 Stream 1 Channel 6
|
||||||
|
|
||||||
|
# master
|
||||||
|
set gyro_to_use = FIRST
|
||||||
|
set align_mag = DEFAULT
|
||||||
|
set mag_bustype = I2C
|
||||||
|
set mag_i2c_device = 1
|
||||||
|
set mag_i2c_address = 0
|
||||||
|
set mag_spi_device = 0
|
||||||
|
set baro_bustype = I2C
|
||||||
|
set baro_spi_device = 0
|
||||||
|
set baro_i2c_device = 2
|
||||||
|
set baro_i2c_address = 0
|
||||||
|
set adc_device = 2
|
||||||
|
set blackbox_device = SPIFLASH
|
||||||
|
set dshot_burst = OFF
|
||||||
|
set current_meter = ADC
|
||||||
|
set battery_meter = ADC
|
||||||
|
set ibata_scale = 179
|
||||||
|
set beeper_inversion = ON
|
||||||
|
set beeper_od = OFF
|
||||||
|
set beeper_frequency = 0
|
||||||
|
set system_hse_mhz = 8
|
||||||
|
set max7456_clock = DEFAULT
|
||||||
|
set max7456_spi_bus = 1
|
||||||
|
set max7456_preinit_opu = OFF
|
||||||
|
set led_inversion = 0
|
||||||
|
set dashboard_i2c_bus = 0
|
||||||
|
set dashboard_i2c_addr = 60
|
||||||
|
set usb_msc_pin_pullup = ON
|
||||||
|
set flash_spi_bus = 2
|
||||||
|
set gyro_1_bustype = SPI
|
||||||
|
set gyro_1_spibus = 3
|
||||||
|
set gyro_1_sensor_align = CW180
|
||||||
|
set mco2_on_pc9 = OFF
|
Loading…
Add table
Add a link
Reference in a new issue