diff --git a/Makefile b/Makefile index dfb9bcf8d0..c6d2c6463d 100644 --- a/Makefile +++ b/Makefile @@ -15,7 +15,7 @@ # Things that the user might override on the commandline # -# The target to build, see BASE_TARGETS/EXE_TARGETS below +# The target or config to build TARGET ?= CONFIG ?= @@ -58,7 +58,7 @@ FORKNAME = betaflight # Working directories # ROOT_DIR is the full path to the directory containing this Makefile -ROOT_DIR := $(dir $(abspath $(lastword $(MAKEFILE_LIST)))) +ROOT_DIR := $(realpath $(dir $(abspath $(lastword $(MAKEFILE_LIST))))) # ROOT is the relative path to the directory containing this Makefile ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) @@ -98,13 +98,6 @@ include $(MAKE_SCRIPT_DIR)/checks.mk PLATFORMS := $(sort $(notdir $(patsubst /%,%, $(wildcard $(PLATFORM_DIR)/*)))) BASE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/target.mk))))) -# list of targets that are executed on host - using exe as goal recipe -EXE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/.exe))))) -# list of targets using uf2 as goal recipe -UF2_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/.uf2))))) -# list of targets using hex as goal recipe (default) -HEX_TARGETS := $(filter-out $(EXE_TARGETS) $(UF2_TARGETS),$(BASE_TARGETS)) - # configure some directories that are relative to wherever ROOT_DIR is located TOOLS_DIR ?= $(ROOT)/tools DL_DIR := $(ROOT)/downloads @@ -134,7 +127,7 @@ FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) -# import config handling +# import config handling (must occur after the hydration of hex, exe and uf2 targets) include $(MAKE_SCRIPT_DIR)/config.mk # default xtal value @@ -150,7 +143,8 @@ TARGET_PLATFORM_DIR := $(PLATFORM_DIR)/$(TARGET_PLATFORM) LINKER_DIR := $(TARGET_PLATFORM_DIR)/link ifneq ($(TARGET),) -include $(TARGET_PLATFORM_DIR)/target/$(TARGET)/target.mk +TARGET_DIR = $(TARGET_PLATFORM_DIR)/target/$(TARGET) +include $(TARGET_DIR)/target.mk endif REVISION := norevision @@ -229,22 +223,17 @@ ifneq ($(HSE_VALUE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) endif -TARGET_DIR = $(TARGET_PLATFORM_DIR)/target/$(TARGET) endif # TARGET specified +ifeq ($(or $(CONFIG),$(TARGET)),) +.DEFAULT_GOAL := all +else +.DEFAULT_GOAL := fwo +endif + # openocd specific includes include $(MAKE_SCRIPT_DIR)/openocd.mk -ifeq ($(CONFIG)$(TARGET),) -.DEFAULT_GOAL := all -else ifneq ($(filter $(TARGET),$(EXE_TARGETS)),) -.DEFAULT_GOAL := exe -else ifneq ($(filter $(TARGET),$(UF2_TARGETS)),) -.DEFAULT_GOAL := uf2 -else -.DEFAULT_GOAL := hex -endif - INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(ROOT)/lib/main/MAVLink @@ -370,6 +359,12 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ $(addprefix -isystem,$(SYS_INCLUDE_DIRS)) \ -I/usr/include -I/usr/include/linux +ifneq ($(filter fwo hex uf2 bin elf zip, $(MAKECMDGOALS)),) + ifeq ($(TARGET),) + $(error "You must specify a target to build.") + endif +endif + TARGET_NAME := $(TARGET) ifneq ($(CONFIG),) @@ -414,6 +409,7 @@ CLEAN_ARTIFACTS += $(TARGET_HEX_REV) $(TARGET_HEX) CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) CLEAN_ARTIFACTS += $(TARGET_LST) CLEAN_ARTIFACTS += $(TARGET_DFU) +CLEAN_ARTIFACTS += $(TARGET_UF2) # Make sure build date and revision is updated on every incremental build $(TARGET_OBJ_DIR)/build/version.o : $(SRC) @@ -433,10 +429,6 @@ $(TARGET_HEX): $(TARGET_ELF) @echo "Creating HEX $(TARGET_HEX)" "$(STDOUT)" $(V1) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ -$(TARGET_UF2): $(TARGET_ELF) - @echo "Creating UF2 $(TARGET_UF2)" "$(STDOUT)" - $(V1) $(PICOTOOL) uf2 convert $< $@ || { echo "Failed to convert ELF to UF2 format"; exit 1; } - $(TARGET_DFU): $(TARGET_HEX) @echo "Creating DFU $(TARGET_DFU)" "$(STDOUT)" $(V1) $(PYTHON) $(DFUSE-PACK) -i $< $@ @@ -493,8 +485,12 @@ $(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT) $(LD_SCRIPTS) $(V1) $(CROSS_CC) -o $@ $(filter-out %.ld,$^) $(LD_FLAGS) $(V1) $(SIZE) $(TARGET_ELF) +$(TARGET_UF2): $(TARGET_ELF) + @echo "Creating UF2 $(TARGET_UF2)" "$(STDOUT)" + $(V1) $(PICOTOOL) uf2 convert $< $@ || { echo "Failed to convert ELF to UF2 format"; exit 1; } + $(TARGET_EXE): $(TARGET_ELF) - @echo Copy $< to $@ "$(STDOUT)" + @echo "Creating exe - copying $< to $@" "$(STDOUT)" $(V1) cp $< $@ # Compile @@ -550,22 +546,11 @@ $(TARGET_OBJ_DIR)/%.o: %.S ## all : Build all currently built targets all: $(CI_TARGETS) -$(HEX_TARGETS): - $(V0) @echo "Building hex target $@" && \ - $(MAKE) hex TARGET=$@ && \ - echo "Building $@ succeeded." +.PHONY: $(BASE_TARGETS) +$(BASE_TARGETS): + $(MAKE) fwo TARGET=$@ -$(UF2_TARGETS): - $(V0) @echo "Building uf2 target $@" && \ - $(MAKE) uf2 TARGET=$@ && \ - echo "Building $@ succeeded." - -$(EXE_TARGETS): - $(V0) @echo "Building executable target $@" && \ - $(MAKE) exe TARGET=$@ && \ - echo "Building $@ succeeded." - -TARGETS_CLEAN = $(addsuffix _clean,$(HEX_TARGETS) $(UF2_TARGETS) $(EXE_TARGETS)) +TARGETS_CLEAN = $(addsuffix _clean,$(BASE_TARGETS)) CONFIGS_CLEAN = $(addsuffix _clean,$(BASE_CONFIGS)) @@ -600,7 +585,7 @@ preview: $(PREVIEW_TARGETS) test ## all_configs : Build all configs all_configs: $(BASE_CONFIGS) -TARGETS_FLASH = $(addsuffix _flash,$(HEX_TARGETS)) +TARGETS_FLASH = $(addsuffix _flash,$(BASE_TARGETS)) ## _flash : build and flash a target $(TARGETS_FLASH): @@ -638,49 +623,59 @@ openocd-gdb: $(TARGET_ELF) $(V0) $(OPENOCD_COMMAND) & $(CROSS_GDB) $(TARGET_ELF) -ex "target remote localhost:3333" -ex "load" endif -TARGETS_ZIP = $(addsuffix _zip,$(HEX_TARGETS)) +TARGETS_ZIP = $(addsuffix _zip,$(BASE_TARGETS)) ## _zip : build target and zip it (useful for posting to GitHub) +.PHONY: $(TARGETS_ZIP) $(TARGETS_ZIP): - $(V0) $(MAKE) hex TARGET=$(subst _zip,,$@) - $(V0) $(MAKE) zip TARGET=$(subst _zip,,$@) + $(V1) $(MAKE) $(MAKE_PARALLEL) zip TARGET=$(subst _zip,,$@) .PHONY: zip -zip: - $(V0) zip $(TARGET_ZIP) $(TARGET_HEX) +zip: $(TARGET_HEX) + $(V1) zip $(TARGET_ZIP) $(TARGET_HEX) .PHONY: binary binary: - $(V0) $(MAKE) $(MAKE_PARALLEL) $(TARGET_BIN) + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_BIN) .PHONY: hex hex: - $(V0) $(MAKE) $(MAKE_PARALLEL) $(TARGET_HEX) + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_HEX) .PHONY: uf2 uf2: - $(V0) $(MAKE) $(MAKE_PARALLEL) $(TARGET_UF2) + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_UF2) .PHONY: exe exe: $(TARGET_EXE) -TARGETS_REVISION = $(addsuffix _rev,$(HEX_TARGETS)) +# FWO (Firmware Output) is the default output for building the firmware +.PHONY: fwo +fwo: +ifeq ($(DEFAULT_OUTPUT),exe) + $(V1) $(MAKE) exe +else ifeq ($(DEFAULT_OUTPUT),uf2) + $(V1) $(MAKE) uf2 +else + $(V1) $(MAKE) hex +endif + +TARGETS_REVISION = $(addsuffix _rev, $(BASE_TARGETS)) ## _rev : build target and add revision to filename +.PHONY: $(TARGETS_REVISION) $(TARGETS_REVISION): - $(V0) $(MAKE) hex REV=yes TARGET=$(subst _rev,,$@) + $(V1) $(MAKE) fwo REV=yes TARGET=$(subst _rev,,$@) -EXE_TARGETS_REVISION = $(addsuffix _rev,$(EXE_TARGETS)) -## _rev : build executable target and add revision to filename -$(EXE_TARGETS_REVISION): - $(V0) $(MAKE) exe REV=yes TARGET=$(subst _rev,,$@) - -all_rev: $(addsuffix _rev,$(CI_TARGETS)) +.PHONY: all_rev +all_rev: $(addsuffix _rev, $(CI_TARGETS)) +.PHONY: unbrick_$(TARGET) unbrick_$(TARGET): $(TARGET_HEX) $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) ## unbrick : unbrick flight controller +.PHONY: unbrick unbrick: unbrick_$(TARGET) ## cppcheck : run static analysis on C source code @@ -698,12 +693,6 @@ $(DIRECTORIES): version: @echo $(FC_VER) -.PHONY: submodules -submodules: - @echo "Updating submodules" - $(V1) git submodule update --init --recursive || { echo "Failed to update submodules"; exit 1; } - @echo "Submodules updated" - ## help : print this help message and exit help: Makefile mk/tools.mk @echo "" @@ -727,8 +716,6 @@ help: Makefile mk/tools.mk targets: @echo "Platforms: $(PLATFORMS)" @echo "Valid targets: $(BASE_TARGETS)" - @echo "Executable targets: $(EXE_TARGETS)" - @echo "UF2 targets: $(UF2_TARGETS)" @echo "Built targets: $(CI_TARGETS)" @echo "Default target: $(TARGET)" @echo "CI common targets: $(CI_COMMON_TARGETS)" diff --git a/mk/build_verbosity.mk b/mk/build_verbosity.mk index 9d2f5dc3f3..c1c6206b43 100644 --- a/mk/build_verbosity.mk +++ b/mk/build_verbosity.mk @@ -9,6 +9,7 @@ ifndef V export V0 := export V1 := $(AT) export STDOUT := +export MAKE := $(MAKE) --no-print-directory else ifeq ($(V), 0) export V0 := $(AT) export V1 := $(AT) diff --git a/mk/config.mk b/mk/config.mk index 5f85d4987d..d1c9e54c65 100644 --- a/mk/config.mk +++ b/mk/config.mk @@ -57,21 +57,23 @@ endif #config .PHONY: configs configs: ifeq ($(shell realpath $(CONFIG_DIR)),$(shell realpath $(CONFIGS_SUBMODULE_DIR))) - git submodule update --init --remote -- $(CONFIGS_SUBMODULE_DIR) + @echo "Updating config submodule: $(CONFIGS_SUBMODULE_DIR)" + $(V1) git submodule update --init -- $(CONFIGS_SUBMODULE_DIR) || { echo "Config submodule update failed. Please check your git configuration."; exit 1; } + @echo "Submodule update succeeded." else ifeq ($(wildcard $(CONFIG_DIR)),) @echo "Hydrating clone for configs: $(CONFIG_DIR)" - $(V0) git clone $(CONFIGS_REPO_URL) $(CONFIG_DIR) + $(V1) git clone $(CONFIGS_REPO_URL) $(CONFIG_DIR) else - $(V0) git -C $(CONFIG_DIR) pull origin + $(V1) git -C $(CONFIG_DIR) pull origin endif endif $(BASE_CONFIGS): @echo "Building target config $@" - $(V0) $(MAKE) $(MAKE_PARALLEL) hex CONFIG=$@ + $(V0) $(MAKE) fwo CONFIG=$@ @echo "Building target config $@ succeeded." ## _rev : build configured target and add revision to filename $(addsuffix _rev,$(BASE_CONFIGS)): - $(V0) $(MAKE) $(MAKE_PARALLEL) hex CONFIG=$(subst _rev,,$@) REV=yes + $(V0) $(MAKE) fwo CONFIG=$(subst _rev,,$@) REV=yes diff --git a/mk/tools.mk b/mk/tools.mk index 5ecf7c79ab..0b53aedecb 100644 --- a/mk/tools.mk +++ b/mk/tools.mk @@ -340,22 +340,28 @@ PICOTOOL_DIR := $(TOOLS_DIR)/picotool PICO_SDK_PATH ?= $(ROOT_DIR)/lib/main/pico-sdk PICOTOOL ?= $(PICOTOOL_DIR)/picotool -ifeq ($(filter picotool_install,$(MAKECMDGOALS)), picotool_install) - ifneq ($(wildcard $(PICO_SDK_PATH)/CMakeLists.txt),$(PICO_SDK_PATH)/CMakeLists.txt) - $(error "PICO_SDK_PATH ($(PICO_SDK_PATH)) does not point to a valid Pico SDK. Please 'make submodules' to hydrate the Pico SDK.") +ifneq ($(filter picotool_install uf2,$(MAKECMDGOALS)),) + ifeq ($(wildcard $(PICO_SDK_PATH)/CMakeLists.txt),) + $(error "PICO_SDK_PATH ($(PICO_SDK_PATH)) does not point to a valid Pico SDK. Please 'make pico_sdk' to hydrate the Pico SDK.") endif endif -ifeq ($(filter uf2,$(MAKECMDGOALS)), uf2) +ifneq ($(filter uf2,$(MAKECMDGOALS)),) ifeq (,$(wildcard $(PICOTOOL))) ifeq (,$(shell which picotool 2>/dev/null)) - $(error "picotool not in the PATH or setup in tools. Run 'make picotool_install' to install in the tools folder.") + $(error "picotool not in the PATH or configured. Run 'make picotool_install' to install in the tools folder.") else PICOTOOL := picotool endif endif endif +.PHONY: pico_sdk +pico_sdk: + @echo "Updating pico-sdk" + $(V1) git submodule update --init --recursive -- lib/main/pico-sdk || { echo "Failed to update pico-sdk"; exit 1; } + @echo "pico-sdk updated" + .PHONY: picotool_install picotool_install: | $(DL_DIR) $(TOOLS_DIR) picotool_install: picotool_clean diff --git a/src/config b/src/config index 4136fa21f2..eda6b30999 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit 4136fa21f2902321caad438b73505caf0c64dda3 +Subproject commit eda6b309994923772eeab82fce3d6d8c3c0812a2 diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 8fd7d3aee2..e12cae2ae6 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -224,7 +224,8 @@ static const char * const mixerNames[] = { "FLYING_WING", "Y4", "HEX6X", "OCTOX8", "OCTOFLATP", "OCTOFLATX", "AIRPLANE", "HELI_120_CCPM", "HELI_90_DEG", "VTAIL4", "HEX6H", "PPM_TO_SERVO", "DUALCOPTER", "SINGLECOPTER", - "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", NULL + "ATAIL4", "CUSTOM", "CUSTOMAIRPLANE", "CUSTOMTRI", "QUADX1234", + "OCTOX8P", NULL }; #endif @@ -5000,9 +5001,9 @@ static void cliRcSmoothing(const char *cmdName, char *cmdline) if (rcSmoothingAutoCalculate()) { cliPrint("# Detected Rx frequency: "); if (getRxRateValid()) { - cliPrintLinef("%dHz", lrintf(rcSmoothingData->smoothedRxRateHz)); + cliPrintLinef("%dHz", lrintf(rcSmoothingData->smoothedRxRateHz)); } else { - cliPrintLine("NO SIGNAL"); + cliPrintLine("NO SIGNAL"); } } cliPrintf("# Active setpoint cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency); diff --git a/src/main/drivers/accgyro/accgyro_spi_icm40609.c b/src/main/drivers/accgyro/accgyro_spi_icm40609.c index 5ed6c8eb73..ed45cdb668 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm40609.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm40609.c @@ -243,7 +243,7 @@ #define ICM40609_ACCEL_DATA_X1_UI 0x1F #define ICM40609_GYRO_DATA_X1_UI 0x25 -#define ICM40609_RESET_REG 0x4C +#define ICM40609_RESET_REG 0x11 #define ICM40609_SOFT_RESET_VAL 0x01 #ifndef ICM40609_LOCK diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 2a3a327e4d..b323d2211d 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -60,6 +60,10 @@ #define ICM426XX_CLKIN_FREQ 32000 +// Soft Reset +#define ICM426XX_RA_DEVICE_CONFIG 0x17 +#define DEVICE_CONFIG_SOFT_RESET_BIT (1 << 0) // Soft reset bit + #define ICM426XX_RA_REG_BANK_SEL 0x76 #define ICM426XX_BANK_SELECT0 0x00 #define ICM426XX_BANK_SELECT1 0x01 @@ -249,8 +253,19 @@ static void icm426xxEnableExternalClock(const extDevice_t *dev) } #endif +static void icm426xxSoftReset(const extDevice_t *dev) +{ + setUserBank(dev, ICM426XX_BANK_SELECT0); + + spiWriteReg(dev, ICM426XX_RA_DEVICE_CONFIG, DEVICE_CONFIG_SOFT_RESET_BIT); + + delay(1); +} + uint8_t icm426xxSpiDetect(const extDevice_t *dev) { + delay(1); // power-on time + icm426xxSoftReset(dev); spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, 0x00); #if defined(USE_GYRO_CLKIN) @@ -260,7 +275,7 @@ uint8_t icm426xxSpiDetect(const extDevice_t *dev) uint8_t icmDetected = MPU_NONE; uint8_t attemptsRemaining = 20; do { - delay(150); + delay(1); const uint8_t whoAmI = spiReadRegMsk(dev, MPU_RA_WHO_AM_I); switch (whoAmI) { case ICM42605_WHO_AM_I_CONST: diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.c b/src/main/drivers/rangefinder/rangefinder_lidartf.c index 643b66694a..51e4043fa4 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.c +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.c @@ -34,16 +34,24 @@ #include "drivers/rangefinder/rangefinder.h" #include "drivers/rangefinder/rangefinder_lidartf.h" -#define TF_DEVTYPE_NONE 0 -#define TF_DEVTYPE_MINI 1 -#define TF_DEVTYPE_02 2 -#define TF_DEVTYPE_NOVA 3 +typedef struct { + rangefinderType_e rfType; + uint16_t rangeMin; + uint16_t rangeMax; +} lidarTFInfo_t; -static uint8_t tfDevtype = TF_DEVTYPE_NONE; + +static const lidarTFInfo_t *devInfo = NULL; +static const lidarTFInfo_t devInfos[] = { + { .rfType = RANGEFINDER_TFMINI, .rangeMin = 40, .rangeMax = 1200}, + { .rfType = RANGEFINDER_TF02, .rangeMin = 40, .rangeMax = 2200}, + { .rfType = RANGEFINDER_TFNOVA, .rangeMin = 10, .rangeMax = 1400}, +}; #define TF_FRAME_LENGTH 6 // Excluding sync bytes (0x59) x 2 and checksum #define TF_FRAME_SYNC_BYTE 0x59 #define TF_TIMEOUT_MS (100 * 2) +#define TF_TASK_PERIOD_MS 10 // // Benewake TFmini frame format @@ -98,21 +106,10 @@ static uint8_t tfDevtype = TF_DEVTYPE_NONE; // Credibility // 1. If Confidence level < 90, unreliable // 2. If distance is 14m (1400cm), then OoR. -// + #define TF_NOVA_FRAME_CONFIDENCE 5 -// Maximum ratings - -#define TF_MINI_RANGE_MIN 40 -#define TF_MINI_RANGE_MAX 1200 - -#define TF_02_RANGE_MIN 40 -#define TF_02_RANGE_MAX 2200 - -#define TF_NOVA_RANGE_MIN 10 -#define TF_NOVA_RANGE_MAX 1400 - -#define TF_DETECTION_CONE_DECIDEGREES 900 +#define TF_DETECTION_CONE_DECIDEGREES 900 // TODO static serialPort_t *tfSerialPort = NULL; @@ -130,21 +127,35 @@ static uint8_t tfReceivePosition; // TFmini and TF02 // Command for 100Hz sampling (10msec interval) // At 100Hz scheduling, skew will cause 10msec delay at the most. -static const uint8_t tfCmd[] = { 0x42, 0x57, 0x02, 0x00, 0x00, 0x00, 0x01, 0x06 }; +// This command format does not match latest Benewake documentation +static const uint8_t tfConfigCmd[] = { 0x42, 0x57, 0x02, 0x00, 0x00, 0x00, 0x01, 0x06 }; -static int32_t lidarTFValue; -static uint16_t lidarTFerrors = 0; +static int lidarTFValue; +static unsigned lidarTFerrors = 0; -static void lidarTFSendCommand(void) + +static const lidarTFInfo_t* findInfo(rangefinderType_e rfType) { - switch (tfDevtype) { - case TF_DEVTYPE_MINI: - case TF_DEVTYPE_02: - serialWriteBuf(tfSerialPort, tfCmd, sizeof(tfCmd)); + for (const lidarTFInfo_t* p = devInfos; p < ARRAYEND(devInfos); p++) { + if (p->rfType == rfType) { + return p; + } + } + return NULL; +} + +// configure/reconfigure device +// may be called multiple times (when frames are missing) +static void lidarTFConfig(rangefinderDev_t *dev, const lidarTFInfo_t* inf) +{ + UNUSED(dev); + switch (inf->rfType) { + case RANGEFINDER_TFMINI: + case RANGEFINDER_TF02: + serialWriteBuf(tfSerialPort, tfConfigCmd, sizeof(tfConfigCmd)); break; default: break; - } } @@ -156,13 +167,54 @@ static void lidarTFInit(rangefinderDev_t *dev) tfReceivePosition = 0; } +static int tfProcessFrame(const uint8_t* frame, int len) +{ + UNUSED(len); + uint16_t distance = frame[0] | (frame[1] << 8); + uint16_t strength = frame[2] | (frame[3] << 8); + + DEBUG_SET(DEBUG_LIDAR_TF, 0, distance); // 0,1 + DEBUG_SET(DEBUG_LIDAR_TF, 1, strength); // 2,3 + DEBUG_SET(DEBUG_LIDAR_TF, 2, frame[4]); + DEBUG_SET(DEBUG_LIDAR_TF, 3, frame[5]); + + // common distance check + if (distance < devInfo->rangeMin || distance > devInfo->rangeMax) { + return RANGEFINDER_OUT_OF_RANGE; + } + + switch (devInfo->rfType) { + case RANGEFINDER_TFMINI: + if (frame[TF_MINI_FRAME_INTEGRAL_TIME] == 7) { + // When integral time is long (7), measured distance tends to be longer by 12~13. + distance -= 13; + } + break; + case RANGEFINDER_TF02: + if (frame[TF_02_FRAME_SIG] < 7) { + return RANGEFINDER_OUT_OF_RANGE; + + } + break; + case RANGEFINDER_TFNOVA: + if (frame[TF_NOVA_FRAME_CONFIDENCE] < 90) { + return RANGEFINDER_OUT_OF_RANGE; + } + break; + default: + return RANGEFINDER_HARDWARE_FAILURE; // internal error + } + // distance is valid + return distance; +} + static void lidarTFUpdate(rangefinderDev_t *dev) { - UNUSED(dev); static timeMs_t lastFrameReceivedMs = 0; + static timeMs_t lastReconfMs = 0; const timeMs_t timeNowMs = millis(); - if (tfSerialPort == NULL) { + if (tfSerialPort == NULL || devInfo == NULL) { return; } @@ -190,76 +242,37 @@ static void lidarTFUpdate(rangefinderDev_t *dev) } break; - case TF_FRAME_STATE_WAIT_CKSUM: - { - uint8_t cksum = TF_FRAME_SYNC_BYTE + TF_FRAME_SYNC_BYTE; - for (int i = 0; i < TF_FRAME_LENGTH; i++) { - cksum += tfFrame[i]; - } - - if (c == cksum) { - - uint16_t distance = tfFrame[0] | (tfFrame[1] << 8); - uint16_t strength = tfFrame[2] | (tfFrame[3] << 8); - - DEBUG_SET(DEBUG_LIDAR_TF, 0, distance); - DEBUG_SET(DEBUG_LIDAR_TF, 1, strength); - DEBUG_SET(DEBUG_LIDAR_TF, 2, tfFrame[4]); - DEBUG_SET(DEBUG_LIDAR_TF, 3, tfFrame[5]); - - switch (tfDevtype) { - case TF_DEVTYPE_MINI: - if (distance >= TF_MINI_RANGE_MIN && distance < TF_MINI_RANGE_MAX) { - lidarTFValue = distance; - if (tfFrame[TF_MINI_FRAME_INTEGRAL_TIME] == 7) { - // When integral time is long (7), measured distance tends to be longer by 12~13. - lidarTFValue -= 13; - } - } else { - lidarTFValue = -1; - } - break; - - case TF_DEVTYPE_02: - if (distance >= TF_02_RANGE_MIN && distance < TF_02_RANGE_MAX && tfFrame[TF_02_FRAME_SIG] >= 7) { - lidarTFValue = distance; - } else { - lidarTFValue = -1; - } - break; - - case TF_DEVTYPE_NOVA: - if (distance >= TF_NOVA_RANGE_MIN && distance <= TF_NOVA_RANGE_MAX && tfFrame[TF_NOVA_FRAME_CONFIDENCE] >= 90) { - lidarTFValue = distance; - } else { - lidarTFValue = -1; - } - break; - } - lastFrameReceivedMs = timeNowMs; - } else { - // Checksum error. Simply discard the current frame. - ++lidarTFerrors; - //DEBUG_SET(DEBUG_LIDAR_TF, 3, lidarTFerrors); - } + case TF_FRAME_STATE_WAIT_CKSUM: { + uint8_t cksum = TF_FRAME_SYNC_BYTE + TF_FRAME_SYNC_BYTE; // SYNC bytes are checksummed too, but not stored + for (int i = 0; i < TF_FRAME_LENGTH; i++) { + cksum += tfFrame[i]; } + if (c == cksum) { + lidarTFValue = tfProcessFrame(tfFrame, TF_FRAME_LENGTH); + lastFrameReceivedMs = timeNowMs; + } else { + // Checksum error. Simply ignore the current frame. + ++lidarTFerrors; + DEBUG_SET(DEBUG_LIDAR_TF, 4, lidarTFerrors); + } tfFrameState = TF_FRAME_STATE_WAIT_START1; tfReceivePosition = 0; - break; } + } } - // If valid frame hasn't been received for more than a timeout, resend command. - - if (timeNowMs - lastFrameReceivedMs > TF_TIMEOUT_MS) { - lidarTFSendCommand(); + // If valid frame hasn't been received for more than a timeout, try reinit. + if (cmp32(timeNowMs, lastFrameReceivedMs) > TF_TIMEOUT_MS + && cmp32(timeNowMs, lastReconfMs) > 500) { + lidarTFConfig(dev, devInfo); + lastReconfMs = timeNowMs; // delay sensor reconf } } // Return most recent device output in cm - +// TODO - handle timeout; return value only once (see lidarMT) static int32_t lidarTFGetDistance(rangefinderDev_t *dev) { UNUSED(dev); @@ -267,37 +280,25 @@ static int32_t lidarTFGetDistance(rangefinderDev_t *dev) return lidarTFValue; } -static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) +bool lidarTFDetect(rangefinderDev_t *dev, rangefinderType_e rfType) { - const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); + const lidarTFInfo_t* inf = findInfo(rfType); + if (!inf) { + return false; // supplied rfType is not TF + } + const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_LIDAR_TF); if (!portConfig) { return false; } tfSerialPort = openSerialPort(portConfig->identifier, FUNCTION_LIDAR_TF, NULL, NULL, 115200, MODE_RXTX, 0); - if (tfSerialPort == NULL) { return false; } - tfDevtype = devtype; - - dev->delayMs = 10; - switch (devtype) { - case TF_DEVTYPE_MINI: - dev->maxRangeCm = TF_MINI_RANGE_MAX; - break; - case TF_DEVTYPE_02: - dev->maxRangeCm = TF_02_RANGE_MAX; - break; - case TF_DEVTYPE_NOVA: - dev->maxRangeCm = TF_NOVA_RANGE_MAX; - break; - default: - dev->maxRangeCm = 0; - break; - } + dev->delayMs = TF_TASK_PERIOD_MS; + dev->maxRangeCm = inf->rangeMax; dev->detectionConeDeciDegrees = TF_DETECTION_CONE_DECIDEGREES; dev->detectionConeExtendedDeciDegrees = TF_DETECTION_CONE_DECIDEGREES; @@ -306,22 +307,12 @@ static bool lidarTFDetect(rangefinderDev_t *dev, uint8_t devtype) dev->update = &lidarTFUpdate; dev->read = &lidarTFGetDistance; + devInfo = inf; + + // configure device + lidarTFConfig(dev, devInfo); + return true; } -bool lidarTFminiDetect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_MINI); -} - -bool lidarTF02Detect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_02); -} - -bool lidarTFNovaDetect(rangefinderDev_t *dev) -{ - return lidarTFDetect(dev, TF_DEVTYPE_NOVA); -} - #endif diff --git a/src/main/drivers/rangefinder/rangefinder_lidartf.h b/src/main/drivers/rangefinder/rangefinder_lidartf.h index cd786a79bc..c84370dd4c 100644 --- a/src/main/drivers/rangefinder/rangefinder_lidartf.h +++ b/src/main/drivers/rangefinder/rangefinder_lidartf.h @@ -20,10 +20,7 @@ #pragma once -#include "common/time.h" +#include "drivers/rangefinder/rangefinder.h" +#include "sensors/rangefinder.h" -#define RANGEFINDER_TF_TASK_PERIOD_MS 10 - -bool lidarTFminiDetect(rangefinderDev_t *dev); -bool lidarTF02Detect(rangefinderDev_t *dev); -bool lidarTFNovaDetect(rangefinderDev_t *dev); +bool lidarTFDetect(rangefinderDev_t *dev, rangefinderType_e rfType); diff --git a/src/main/sensors/rangefinder.c b/src/main/sensors/rangefinder.c index e243b5027f..4c1ac78d69 100644 --- a/src/main/sensors/rangefinder.c +++ b/src/main/sensors/rangefinder.c @@ -109,29 +109,13 @@ static bool rangefinderDetect(rangefinderDev_t * dev, uint8_t rangefinderHardwar #endif break; +#if defined(USE_RANGEFINDER_TF) case RANGEFINDER_TFMINI: -#if defined(USE_RANGEFINDER_TF) - if (lidarTFminiDetect(dev)) { - rangefinderHardware = RANGEFINDER_TFMINI; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); - } -#endif - break; - case RANGEFINDER_TF02: -#if defined(USE_RANGEFINDER_TF) - if (lidarTF02Detect(dev)) { - rangefinderHardware = RANGEFINDER_TF02; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); - } -#endif - break; - case RANGEFINDER_TFNOVA: -#if defined(USE_RANGEFINDER_TF) - if (lidarTFNovaDetect(dev)) { - rangefinderHardware = RANGEFINDER_TFNOVA; - rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(RANGEFINDER_TF_TASK_PERIOD_MS)); + if (lidarTFDetect(dev, rangefinderHardwareToUse)) { + rangefinderHardware = rangefinderHardwareToUse; + rescheduleTask(TASK_RANGEFINDER, TASK_PERIOD_MS(dev->delayMs)); } #endif break; diff --git a/src/platform/PICO/startup/bs2_default_padded_checksummed.S b/src/platform/PICO/startup/bs2_default_padded_checksummed.S deleted file mode 100644 index 124bd8d265..0000000000 --- a/src/platform/PICO/startup/bs2_default_padded_checksummed.S +++ /dev/null @@ -1,25 +0,0 @@ -// Padded and checksummed version of: /home/black/src/pico/hello/build/pico-sdk/src/rp2350/boot_stage2/bs2_default.bin - -.cpu cortex-m0plus -.thumb - -.section .boot2, "ax" - -.global __boot2_entry_point -__boot2_entry_point: -.byte 0x00, 0xb5, 0x24, 0x4b, 0x21, 0x20, 0x58, 0x60, 0x13, 0xf5, 0x40, 0x53, 0x02, 0x20, 0x98, 0x60 -.byte 0xd8, 0x60, 0x18, 0x61, 0x58, 0x61, 0x13, 0xf5, 0x0d, 0x23, 0x1f, 0x49, 0x19, 0x60, 0x18, 0x68 -.byte 0x10, 0xf0, 0x02, 0x0f, 0xfb, 0xd1, 0x35, 0x20, 0x00, 0xf0, 0x2c, 0xf8, 0x02, 0x28, 0x14, 0xd0 -.byte 0x06, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x22, 0xf8, 0x98, 0x68, 0x01, 0x20, 0x58, 0x60, 0x00, 0x20 -.byte 0x58, 0x60, 0x02, 0x20, 0x58, 0x60, 0x00, 0xf0, 0x19, 0xf8, 0x98, 0x68, 0x98, 0x68, 0x98, 0x68 -.byte 0x05, 0x20, 0x00, 0xf0, 0x17, 0xf8, 0x40, 0x08, 0xfa, 0xd2, 0x31, 0xf0, 0x01, 0x01, 0x19, 0x60 -.byte 0x0e, 0x48, 0xd8, 0x60, 0x4a, 0xf2, 0xeb, 0x00, 0x58, 0x61, 0x0d, 0x48, 0x18, 0x61, 0x4f, 0xf0 -.byte 0xa0, 0x51, 0x09, 0x78, 0x20, 0xf4, 0x80, 0x50, 0x18, 0x61, 0x00, 0xbd, 0x18, 0x68, 0x80, 0x08 -.byte 0xfc, 0xd2, 0x70, 0x47, 0x00, 0xb5, 0x58, 0x60, 0x58, 0x60, 0xff, 0xf7, 0xf7, 0xff, 0x98, 0x68 -.byte 0x98, 0x68, 0x00, 0xbd, 0x00, 0x00, 0x04, 0x40, 0x41, 0x00, 0x80, 0x07, 0x02, 0x02, 0x00, 0x40 -.byte 0xa8, 0x92, 0x04, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 -.byte 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00 diff --git a/src/platform/SIMULATOR/mk/SITL.mk b/src/platform/SIMULATOR/mk/SITL.mk index 989306556f..757b0e4da8 100644 --- a/src/platform/SIMULATOR/mk/SITL.mk +++ b/src/platform/SIMULATOR/mk/SITL.mk @@ -1,3 +1,7 @@ +# SITL Makefile for the simulator platform + +# Default output is an exe file +DEFAULT_OUTPUT := exe INCLUDE_DIRS := \ $(INCLUDE_DIRS) \