diff --git a/Makefile b/Makefile index 7be4e6a6d2..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 ?= @@ -57,7 +57,11 @@ CFLAGS_DISABLED := FORKNAME = betaflight # Working directories +# ROOT_DIR is the full path to the directory containing this Makefile +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)))) + PLATFORM_DIR := $(ROOT)/src/platform SRC_DIR := $(ROOT)/src/main LIB_MAIN_DIR := $(ROOT)/lib/main @@ -90,12 +94,9 @@ MAKE_PARALLEL = $(if $(filter -j%, $(MAKEFLAGS)),$(EMPTY),-j$(DEFAULT_PAR # pre-build sanity checks include $(MAKE_SCRIPT_DIR)/checks.mk -# list of targets that are executed on host (using exe as goal) -EXE_TARGETS := SITL - # basic target list PLATFORMS := $(sort $(notdir $(patsubst /%,%, $(wildcard $(PLATFORM_DIR)/*)))) -BASE_TARGETS := $(filter-out $(EXE_TARGETS),$(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/target.mk)))))) +BASE_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/target.mk))))) # configure some directories that are relative to wherever ROOT_DIR is located TOOLS_DIR ?= $(ROOT)/tools @@ -126,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 @@ -134,7 +135,7 @@ HSE_VALUE ?= 8000000 CI_EXCLUDED_TARGETS := $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(PLATFORM_DIR)/*/target/*/.exclude))))) CI_COMMON_TARGETS := STM32F4DISCOVERY CRAZYBEEF4SX1280 CRAZYBEEF4FR MATEKF405TE AIRBOTG4AIO TBS_LUCID_FC IFLIGHT_BLITZ_F722 NUCLEOF446 SPRACINGH7EXTREME SPRACINGH7RF -CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS) $(EXE_TARGETS)) $(filter $(CI_COMMON_TARGETS), $(BASE_CONFIGS)) +CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS) $(filter $(CI_COMMON_TARGETS), $(BASE_CONFIGS))) PREVIEW_TARGETS := MATEKF411 AIKONF4V2 AIRBOTG4AIO ZEEZF7V3 FOXEERF745V4_AIO KAKUTEH7 TBS_LUCID_FC SITL SPRACINGH7EXTREME SPRACINGH7RF TARGET_PLATFORM := $(notdir $(patsubst %/,%,$(subst target/$(TARGET)/,, $(dir $(wildcard $(PLATFORM_DIR)/*/target/$(TARGET)/target.mk))))) @@ -142,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 @@ -221,24 +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),) -ifeq ($(TARGET),) -.DEFAULT_GOAL := all -else ifneq ($(filter $(TARGET),$(EXE_TARGETS)),) -.DEFAULT_GOAL := exe -else -.DEFAULT_GOAL := hex -endif -else # ifeq ($(CONFIG),) -.DEFAULT_GOAL := hex -endif - INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(ROOT)/lib/main/MAVLink @@ -364,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),) @@ -378,21 +379,22 @@ TARGET_FULLNAME = $(FORKNAME)_$(FC_VER)_$(TARGET_NAME) # # Things we will build # -TARGET_BIN = $(BIN_DIR)/$(TARGET_FULLNAME).bin -TARGET_HEX = $(BIN_DIR)/$(TARGET_FULLNAME).hex -TARGET_EXE = $(BIN_DIR)/$(TARGET_FULLNAME) -TARGET_DFU = $(BIN_DIR)/$(TARGET_FULLNAME).dfu -TARGET_ZIP = $(BIN_DIR)/$(TARGET_FULLNAME).zip -TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET_NAME) -TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).elf -TARGET_EXST_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_EXST.elf -TARGET_UNPATCHED_BIN = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_UNPATCHED.bin -TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).lst -TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) -TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) -TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).map +TARGET_BIN := $(BIN_DIR)/$(TARGET_FULLNAME).bin +TARGET_HEX := $(BIN_DIR)/$(TARGET_FULLNAME).hex +TARGET_UF2 := $(BIN_DIR)/$(TARGET_FULLNAME).uf2 +TARGET_EXE := $(BIN_DIR)/$(TARGET_FULLNAME) +TARGET_DFU := $(BIN_DIR)/$(TARGET_FULLNAME).dfu +TARGET_ZIP := $(BIN_DIR)/$(TARGET_FULLNAME).zip +TARGET_OBJ_DIR := $(OBJECT_DIR)/$(TARGET_NAME) +TARGET_ELF := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).elf +TARGET_EXST_ELF := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_EXST.elf +TARGET_UNPATCHED_BIN := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_UNPATCHED.bin +TARGET_LST := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).lst +TARGET_OBJS := $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_DEPS := $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_MAP := $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).map -TARGET_EXST_HASH_SECTION_FILE = $(TARGET_OBJ_DIR)/exst_hash_section.bin +TARGET_EXST_HASH_SECTION_FILE := $(TARGET_OBJ_DIR)/exst_hash_section.bin ifeq ($(DEBUG_MIXED),yes) TARGET_EF_HASH := $(shell echo -n -- "$(EXTRA_FLAGS)" "$(OPTIONS)" "$(DEVICE_FLAGS)" "$(TARGET_FLAGS)" | openssl dgst -md5 -r | awk '{print $$1;}') @@ -407,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) @@ -482,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 @@ -539,17 +546,11 @@ $(TARGET_OBJ_DIR)/%.o: %.S ## all : Build all currently built targets all: $(CI_TARGETS) +.PHONY: $(BASE_TARGETS) $(BASE_TARGETS): - $(V0) @echo "Building target $@" && \ - $(MAKE) hex TARGET=$@ && \ - echo "Building $@ succeeded." + $(MAKE) fwo TARGET=$@ -$(EXE_TARGETS): - $(V0) @echo "Building executable target $@" && \ - $(MAKE) exe TARGET=$@ && \ - echo "Building $@ succeeded." - -TARGETS_CLEAN = $(addsuffix _clean,$(BASE_TARGETS) $(EXE_TARGETS)) +TARGETS_CLEAN = $(addsuffix _clean,$(BASE_TARGETS)) CONFIGS_CLEAN = $(addsuffix _clean,$(BASE_CONFIGS)) @@ -625,39 +626,56 @@ endif 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,,$@) -zip: - $(V0) zip $(TARGET_ZIP) $(TARGET_HEX) +.PHONY: zip +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: exe +.PHONY: uf2 +uf2: + $(V1) $(MAKE) $(MAKE_PARALLEL) $(TARGET_UF2) + +.PHONY: exe exe: $(TARGET_EXE) -TARGETS_REVISION = $(addsuffix _rev,$(BASE_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 @@ -690,7 +708,7 @@ help: Makefile mk/tools.mk @echo "To populate configuration targets:" @echo " make configs" @echo "" - @echo "Valid TARGET values are: $(EXE_TARGETS) $(BASE_TARGETS)" + @echo "Valid TARGET values are: $(BASE_TARGETS)" @echo "" @sed -n 's/^## //p' $? @@ -698,7 +716,6 @@ help: Makefile mk/tools.mk targets: @echo "Platforms: $(PLATFORMS)" @echo "Valid targets: $(BASE_TARGETS)" - @echo "Executable targets: $(EXE_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/source.mk b/mk/source.mk index 13e55fb4d6..ad3f7e4fc4 100644 --- a/mk/source.mk +++ b/mk/source.mk @@ -299,6 +299,7 @@ COMMON_SRC += \ drivers/accgyro/accgyro_spi_icm20689.c \ drivers/accgyro/accgyro_spi_icm426xx.c \ drivers/accgyro/accgyro_spi_icm456xx.c \ + drivers/accgyro/accgyro_spi_icm40609.c \ drivers/accgyro/accgyro_spi_l3gd20.c \ drivers/accgyro/accgyro_spi_lsm6dso.c \ drivers/accgyro/accgyro_spi_lsm6dso_init.c \ diff --git a/mk/tools.mk b/mk/tools.mk index 3dc42ab47a..0b53aedecb 100644 --- a/mk/tools.mk +++ b/mk/tools.mk @@ -331,3 +331,54 @@ breakpad_clean: $(V1) [ ! -d "$(BREAKPAD_DIR)" ] || $(RM) -rf $(BREAKPAD_DIR) @echo " CLEAN $(BREAKPAD_DL_FILE)" $(V1) $(RM) -f $(BREAKPAD_DL_FILE) + +# Raspberry Pi Pico tools +PICOTOOL_REPO := https://github.com/raspberrypi/picotool.git +PICOTOOL_DL_DIR := $(DL_DIR)/picotool +PICOTOOL_BUILD_DIR := $(PICOTOOL_DL_DIR)/build +PICOTOOL_DIR := $(TOOLS_DIR)/picotool +PICO_SDK_PATH ?= $(ROOT_DIR)/lib/main/pico-sdk +PICOTOOL ?= $(PICOTOOL_DIR)/picotool + +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 + +ifneq ($(filter uf2,$(MAKECMDGOALS)),) + ifeq (,$(wildcard $(PICOTOOL))) + ifeq (,$(shell which picotool 2>/dev/null)) + $(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 + @echo "\n CLONE $(PICOTOOL_REPO)" + $(V1) git clone --depth 1 $(PICOTOOL_REPO) "$(PICOTOOL_DL_DIR)" || { echo "Failed to clone picotool repository"; exit 1; } + @echo "\n BUILD $(PICOTOOL_BUILD_DIR)" + $(V1) [ -d "$(PICOTOOL_DIR)" ] || mkdir -p $(PICOTOOL_DIR) + $(V1) [ -d "$(PICOTOOL_BUILD_DIR)" ] || mkdir -p $(PICOTOOL_BUILD_DIR) + $(V1) cmake -S $(PICOTOOL_DL_DIR) -B $(PICOTOOL_BUILD_DIR) -D PICO_SDK_PATH=$(PICO_SDK_PATH) || { echo "CMake configuration failed"; exit 1; } + $(V1) $(MAKE) -C $(PICOTOOL_BUILD_DIR) || { echo "picotool build failed"; exit 1; } + $(V1) cp $(PICOTOOL_BUILD_DIR)/picotool $(PICOTOOL_DIR)/picotool || { echo "Failed to install picotool binary"; exit 1; } + @echo "\n VERSION:" + $(V1) $(PICOTOOL_DIR)/picotool version + +.PHONY: picotool_clean +picotool_clean: + @echo " CLEAN $(PICOTOOL_DIR)" + $(V1) [ ! -d "$(PICOTOOL_DIR)" ] || $(RM) -rf $(PICOTOOL_DIR) + @echo " CLEAN $(PICOTOOL_DL_DIR)" + $(V1) [ ! -d "$(PICOTOOL_DL_DIR)" ] || $(RM) -rf $(PICOTOOL_DL_DIR) diff --git a/src/config b/src/config index 22dc66d412..ec429513a6 160000 --- a/src/config +++ b/src/config @@ -1 +1 @@ -Subproject commit 22dc66d412b21f9cbf78fe481b7a3c158c46ca68 +Subproject commit ec429513a68b3362647ead039719f12f156edcf4 diff --git a/src/main/build/build_config.h b/src/main/build/build_config.h index 4665627e47..22a59c65f3 100644 --- a/src/main/build/build_config.h +++ b/src/main/build/build_config.h @@ -63,6 +63,7 @@ typedef enum { MCU_TYPE_APM32F405, MCU_TYPE_APM32F407, MCU_TYPE_AT32F435M, + MCU_TYPE_RP2350A, MCU_TYPE_RP2350B, MCU_TYPE_COUNT, MCU_TYPE_UNKNOWN = 255, diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 6f9ca1cec5..2ef7b5f1f7 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 and FF cutoff: %dhz ", rcSmoothingData->setpointCutoffFrequency); diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index f6171946c9..e2ccc28f85 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -163,6 +163,8 @@ const char * const lookupTableAccHardware[] = { "IIM42653", "ICM45605", "ICM45686", + "ICM40609D", + "IIM42652", "VIRTUAL" }; @@ -189,6 +191,8 @@ const char * const lookupTableGyroHardware[] = { "IIM42653", "ICM45605", "ICM45686", + "ICM40609D", + "IIM42652", "VIRTUAL" }; @@ -1844,21 +1848,25 @@ const clivalue_t valueTable[] = { { "gyro_2_align_yaw", VAR_INT16 | HARDWARE_VALUE, .config.minmax = { -3600, 3600 }, PG_GYRO_DEVICE_CONFIG, PG_ARRAY_ELEMENT_OFFSET(gyroDeviceConfig_t, 1, customAlignment.yaw) }, #endif #ifdef I2C_FULL_RECONFIGURABILITY +#ifdef USE_I2C_DEVICE_0 + { "i2c0_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_0, pullUp) }, + { "i2c0_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_0, clockSpeed) }, +#endif #ifdef USE_I2C_DEVICE_1 - { "i2c1_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, pullUp) }, - { "i2c1_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 0, clockSpeed) }, + { "i2c1_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_1, pullUp) }, + { "i2c1_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_1, clockSpeed) }, #endif #ifdef USE_I2C_DEVICE_2 - { "i2c2_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 1, pullUp) }, - { "i2c2_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 1, clockSpeed) }, + { "i2c2_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_2, pullUp) }, + { "i2c2_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_2, clockSpeed) }, #endif #ifdef USE_I2C_DEVICE_3 - { "i2c3_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 2, pullUp) }, - { "i2c3_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 2, clockSpeed) }, + { "i2c3_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_3, pullUp) }, + { "i2c3_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_3, clockSpeed) }, #endif #ifdef USE_I2C_DEVICE_4 - { "i2c4_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 3, pullUp) }, - { "i2c4_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, 3, clockSpeed) }, + { "i2c4_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_4, pullUp) }, + { "i2c4_clockspeed_khz", VAR_UINT16 | HARDWARE_VALUE, .config.minmax = { I2C_CLOCKSPEED_MIN_KHZ, I2C_CLOCKSPEED_MAX_KHZ }, PG_I2C_CONFIG, PG_ARRAY_ELEMENT_OFFSET(i2cConfig_t, I2CDEV_4, clockSpeed) }, #endif #endif #ifdef USE_MCO diff --git a/src/main/common/strtol.c b/src/main/common/strtol.c index f94f3fc38d..0739cec593 100644 --- a/src/main/common/strtol.c +++ b/src/main/common/strtol.c @@ -30,6 +30,7 @@ #define _STRTO_ENDPTR 1 +#if PLATFORM_NO_LIBC static unsigned long _strto_l(const char * str, char ** endptr, int base, int sflag) { unsigned long number, cutoff; @@ -127,6 +128,7 @@ unsigned long strtoul(const char * str, char ** endptr, int base) { return _strto_l(str, endptr, base, 0); } +#endif int atoi(const char *str) { diff --git a/src/main/common/time.h b/src/main/common/time.h index 33121739ab..9bf3b9c190 100644 --- a/src/main/common/time.h +++ b/src/main/common/time.h @@ -46,6 +46,7 @@ typedef uint32_t timeUs_t; #define SECONDS_PER_MINUTE 60.0f static inline timeDelta_t cmpTimeUs(timeUs_t a, timeUs_t b) { return (timeDelta_t)(a - b); } +static inline timeDelta_t cmpTimeMs(timeMs_t a, timeMs_t b) { return (timeDelta_t)(a - b); } static inline int32_t cmpTimeCycles(uint32_t a, uint32_t b) { return (int32_t)(a - b); } #define FORMATTED_DATE_TIME_BUFSIZE 30 diff --git a/src/main/drivers/accgyro/accgyro.h b/src/main/drivers/accgyro/accgyro.h index d8be175115..9a50c6b69b 100644 --- a/src/main/drivers/accgyro/accgyro.h +++ b/src/main/drivers/accgyro/accgyro.h @@ -64,6 +64,8 @@ typedef enum { GYRO_IIM42653, GYRO_ICM45605, GYRO_ICM45686, + GYRO_ICM40609D, + GYRO_IIM42652, GYRO_VIRTUAL } gyroHardware_e; diff --git a/src/main/drivers/accgyro/accgyro_mpu.c b/src/main/drivers/accgyro/accgyro_mpu.c index 930028f0a3..f2a43ca6b6 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.c +++ b/src/main/drivers/accgyro/accgyro_mpu.c @@ -58,6 +58,7 @@ #include "drivers/accgyro/accgyro_spi_l3gd20.h" #include "drivers/accgyro/accgyro_spi_lsm6dsv16x.h" #include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_spi_icm40609.h" #include "pg/pg.h" #include "pg/gyrodev.h" @@ -377,6 +378,9 @@ static gyroSpiDetectFn_t gyroSpiDetectFnTable[] = { #endif #ifdef USE_GYRO_L3GD20 l3gd20Detect, +#endif +#ifdef USE_ACCGYRO_ICM40609D + icm40609SpiDetect, #endif NULL // Avoid an empty array }; diff --git a/src/main/drivers/accgyro/accgyro_mpu.h b/src/main/drivers/accgyro/accgyro_mpu.h index b72356ddef..b3e4fe7ef2 100644 --- a/src/main/drivers/accgyro/accgyro_mpu.h +++ b/src/main/drivers/accgyro/accgyro_mpu.h @@ -47,8 +47,10 @@ #define ICM42688P_WHO_AM_I_CONST (0x47) #define ICM45686_WHO_AM_I_CONST (0xE9) #define ICM45605_WHO_AM_I_CONST (0xE5) +#define IIM42652_WHO_AM_I_CONST (0x6F) #define IIM42653_WHO_AM_I_CONST (0x56) #define LSM6DSV16X_WHO_AM_I_CONST (0x70) +#define ICM40609_WHO_AM_I_CONST (0x3B) // RA = Register Address @@ -206,6 +208,7 @@ typedef enum { ICM_20689_SPI, ICM_42605_SPI, ICM_42688P_SPI, + IIM_42652_SPI, IIM_42653_SPI, BMI_160_SPI, BMI_270_SPI, @@ -214,6 +217,7 @@ typedef enum { LSM6DSV16X_SPI, ICM_45605_SPI, ICM_45686_SPI, + ICM_40609_SPI } mpuSensor_e; typedef enum { diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi160.c b/src/main/drivers/accgyro/accgyro_spi_bmi160.c index 31260a0f96..fbf4aacb81 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi160.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi160.c @@ -267,6 +267,7 @@ extiCallbackRec_t bmi160IntCallbackRec; // Called in ISR context // Gyro read has just completed +#ifdef USE_DMA static busStatus_e bmi160Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; @@ -280,6 +281,7 @@ static busStatus_e bmi160Intcallback(uint32_t arg) return BUS_READY; } +#endif static void bmi160ExtiHandler(extiCallbackRec_t *cb) { diff --git a/src/main/drivers/accgyro/accgyro_spi_bmi270.c b/src/main/drivers/accgyro/accgyro_spi_bmi270.c index f13f39c75f..a64cfa64b4 100644 --- a/src/main/drivers/accgyro/accgyro_spi_bmi270.c +++ b/src/main/drivers/accgyro/accgyro_spi_bmi270.c @@ -278,6 +278,7 @@ extiCallbackRec_t bmi270IntCallbackRec; */ // Called in ISR context // Gyro read has just completed +#ifdef USE_DMA static busStatus_e bmi270Intcallback(uint32_t arg) { gyroDev_t *gyro = (gyroDev_t *)arg; @@ -291,6 +292,7 @@ static busStatus_e bmi270Intcallback(uint32_t arg) return BUS_READY; } +#endif static void bmi270ExtiHandler(extiCallbackRec_t *cb) { diff --git a/src/main/drivers/accgyro/accgyro_spi_icm40609.c b/src/main/drivers/accgyro/accgyro_spi_icm40609.c new file mode 100644 index 0000000000..ed45cdb668 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_icm40609.c @@ -0,0 +1,764 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +#include +#include +#include +#include + +#include "platform.h" + +#if defined(USE_ACCGYRO_ICM40609D) + +#include "common/axis.h" +#include "common/maths.h" + +#include "drivers/accgyro/accgyro.h" +#include "drivers/accgyro/accgyro_mpu.h" +#include "drivers/accgyro/accgyro_spi_icm40609.h" +#include "drivers/bus_spi.h" +#include "drivers/exti.h" +#include "drivers/io.h" +#include "drivers/pwm_output.h" +#include "drivers/sensor.h" +#include "drivers/time.h" + +#include "fc/runtime_config.h" + +#include "sensors/gyro.h" +#include "pg/gyrodev.h" + +// Datasheet: https://invensense.tdk.com/wp-content/uploads/2022/07/DS-000330-ICM-40609-D-v1.2.pdf + +#define ICM40609_WHO_AM_I_REG 0x75 + +#define ICM40609_REG_BANK_SEL 0x76 + +#define ICM40609_USER_BANK_0 0x00 +#define ICM40609_USER_BANK_1 0x01 +#define ICM40609_USER_BANK_2 0x02 +#define ICM40609_USER_BANK_3 0x03 +#define ICM40609_USER_BANK_4 0x04 + +// Registers in BANK 0 +#define ICM40609_REG_INT_CONFIG 0x14 +#define ICM40609_REG_INTF_CONFIG0 0x4C +#define ICM40609_REG_PWR_MGMT0 0x4E +#define ICM40609_REG_GYRO_CONFIG0 0x4F +#define ICM40609_REG_ACCEL_CONFIG0 0x50 +#define ICM40609_REG_GYRO_CONFIG1 0x51 // Bandwidth of the temperature signal DLPF +#define ICM40609_REG_GYRO_ACCEL_CONFIG0 0x52 // Bandwidth for Gyro & Accel LPF +#define ICM40609_REG_GYRO_ACCEL_CONFIG1 0x53 // Bandwidth for Gyro & Accel LPF +#define ICM40609_REG_INT_CONFIG0 0x63 +#define ICM40609_REG_INT_CONFIG1 0x64 +#define ICM40609_REG_INT_SOURCE0 0x65 + +// Registers in BANK 1 +#define ICM40609_REG_GYRO_CONFIG_STATIC2 0x0B +#define ICM40609_REG_GYRO_CONFIG_STATIC3 0x0C +#define ICM40609_REG_GYRO_CONFIG_STATIC4 0x0D +#define ICM40609_REG_GYRO_CONFIG_STATIC5 0x0E +#define ICM40609_REG_GYRO_CONFIG_STATIC6 0x0F +#define ICM40609_REG_GYRO_CONFIG_STATIC7 0x10 +#define ICM40609_REG_GYRO_CONFIG_STATIC8 0x11 +#define ICM40609_REG_GYRO_CONFIG_STATIC9 0x12 +#define ICM40609_REG_GYRO_CONFIG_STATIC10 0x13 // gyro notch filter + +// Registers in BANK 2 +#define ICM40609_REG_ACCEL_CONFIG_STATIC2 0x03 +#define ICM40609_REG_ACCEL_CONFIG_STATIC3 0x04 +#define ICM40609_REG_ACCEL_CONFIG_STATIC4 0x05 + +// PWR_MGMT0_REG - 0x4E +#define ICM40609_TEMP_SENSOR_ENABLED (0 << 5) +#define ICM40609_TEMP_SENSOR_DISABLED (1 << 5) +#define ICM40609_IDLE (0 << 4) +#define ICM40609_RC_ON (1 << 4) + +// // PWR_MGMT0_REG - 0x4E bits [3:2] +#define ICM40609_GYRO_MODE_OFF (0 << 2) +#define ICM40609_GYRO_MODE_STANDBY (1 << 2) +#define ICM40609_GYRO_MODE_LN (3 << 2) + +// // PWR_MGMT0_REG - 0x4E bits [1:0] +#define ICM40609_ACCEL_MODE_OFF (0 << 0) // Of course, this is joke, but it's so easy to check bits orders in datasheet +#define ICM40609_ACCEL_MODE_PWR_OFF (1 << 0) +#define ICM40609_ACCEL_MODE_LP (2 << 0) +#define ICM40609_ACCEL_MODE_LN (3 << 0) + +// GYRO_CONFIG0_REG - 0x4F bits [7:5] +#define ICM40609_GYRO_FS_SEL_2000DPS (0 << 5) // default) +#define ICM40609_GYRO_FS_SEL_1000DPS (1 << 5) +#define ICM40609_GYRO_FS_SEL_500DPS (2 << 5) +#define ICM40609_GYRO_FS_SEL_250DPS (3 << 5) +#define ICM40609_GYRO_FS_SEL_125DPS (4 << 5) +#define ICM40609_GYRO_FS_SEL_62_5DPS (5 << 5) +#define ICM40609_GYRO_FS_SEL_31_25DPS (6 << 5) +#define ICM40609_GYRO_FS_SEL_15_625DPS (7 << 5) + +// GYRO_CONFIG0_REG - 0x4F bits [3:0] +#define ICM40609_GYRO_ODR_32KHZ 0x01 +#define ICM40609_GYRO_ODR_16KHZ 0x02 +#define ICM40609_GYRO_ODR_8KHZ 0x03 +#define ICM40609_GYRO_ODR_4KHZ 0x04 +#define ICM40609_GYRO_ODR_2KHZ 0x05 +#define ICM40609_GYRO_ODR_1KHZ 0x06 // default +#define ICM40609_GYRO_ODR_200HZ 0x07 +#define ICM40609_GYRO_ODR_100HZ 0x08 +#define ICM40609_GYRO_ODR_50HZ 0x09 +#define ICM40609_GYRO_ODR_25HZ 0x0A +#define ICM40609_GYRO_ODR_12_5HZ 0x0B +#define ICM40609_GYRO_ODR_RESERVED_C 0x0C +#define ICM40609_GYRO_ODR_RESERVED_D 0x0D +#define ICM40609_GYRO_ODR_RESERVED_E 0x0E +#define ICM40609_GYRO_ODR_500HZ 0x0F + +// ACCEL_CONFIG0_REG - 0x50 bits [7:5] +#define ICM40609_ACCEL_FS_SEL_16G (0 << 5) +#define ICM40609_ACCEL_FS_SEL_8G (1 << 5) +#define ICM40609_ACCEL_FS_SEL_4G (2 << 5) +#define ICM40609_ACCEL_FS_SEL_2G (3 << 5) +#define ICM40609_ACCEL_FS_SEL_1G (4 << 5) +#define ICM40609_ACCEL_FS_SEL_0_5G (5 << 5) +#define ICM40609_ACCEL_FS_SEL_0_25G (6 << 5) +#define ICM40609_ACCEL_FS_SEL_0_125G (7 << 5) + +// ACCEL_CONFIG0_REG - 0x50 bits [3:0] +#define ICM40609_ACCEL_ODR_32KHZ 0x01 +#define ICM40609_ACCEL_ODR_16KHZ 0x02 +#define ICM40609_ACCEL_ODR_8KHZ 0x03 +#define ICM40609_ACCEL_ODR_4KHZ 0x04 +#define ICM40609_ACCEL_ODR_2KHZ 0x05 +#define ICM40609_ACCEL_ODR_1KHZ 0x06 // 1kHz (LN mode) (default) +#define ICM40609_ACCEL_ODR_200HZ 0x07 +#define ICM40609_ACCEL_ODR_100HZ 0x08 +#define ICM40609_ACCEL_ODR_50HZ 0x09 +#define ICM40609_ACCEL_ODR_25HZ 0x0A +#define ICM40609_ACCEL_ODR_12_5HZ 0x0B +#define ICM40609_ACCEL_ODR_500HZ 0x0F + +// INT_CONFIG_REG - 0x14 +#define ICM40609_INT1_MODE_PULSED (0 << 2) +#define ICM40609_INT1_MODE_LATCHED (1 << 2) + +#define ICM40609_INT1_DRIVE_OPEN_DRAIN (0 << 1) +#define ICM40609_INT1_DRIVE_PUSH_PULL (1 << 1) + +#define ICM40609_INT1_POLARITY_ACTIVE_LOW (0 << 0) +#define ICM40609_INT1_POLARITY_ACTIVE_HIGH (1 << 0) + +// NT_SOURCE0_REG - 0x65 +#define ICM40609_UI_FSYNC_INT1_EN (1 << 6) +#define ICM40609_PLL_RDY_INT1_EN (1 << 5) +#define ICM40609_RESET_DONE_INT1_EN (1 << 4) +#define ICM40609_UI_DRDY_INT1_EN (1 << 3) +#define ICM40609_FIFO_THS_INT1_EN (1 << 2) +#define ICM40609_FIFO_FULL_INT1_EN (1 << 1) +#define ICM40609_UI_AGC_RDY_INT1_EN (1 << 0) + +// INT_CONFIG0 - 0x63 +#define ICM40609_UI_DRDY_INT_CLEAR_STATUS (0 << 4) + +// INT_CONFIG1 - 0x64 +#define ICM40609_INT_TPULSE_100US (0 << 6) // ODR < 4kHz, optional +#define ICM40609_INT_TPULSE_8US (1 << 6) // ODR ≥ 4kHz +#define ICM40609_INT_TDEASSERT_ENABLED (0 << 5) +#define ICM40609_INT_TDEASSERT_DISABLED (1 << 5) +#define ICM40609_INT_ASYNC_RESET_ENABLED (1 << 4) +#define ICM40609_INT_ASYNC_RESET_DISABLED (0 << 4) + +// REG_GYRO_CONFIG1 - 0x51 bits [3:2] +#define ICM40609_GYRO_UI_FILT_ORDER_1ST (0 << 2) +#define ICM40609_GYRO_UI_FILT_ORDER_2ND (1 << 2) +#define ICM40609_GYRO_UI_FILT_ORDER_3RD (2 << 2) + +// REG_GYRO_CONFIG1 - 0x51 bits [1:0] +#define ICM40609_GYRO_DEC2_M2_ORDER_3RD (2 << 0) + +// REG_GYRO_ACCEL_CONFIG0 - 0x52 bits [7:4] +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV2 (0 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV4 (1 << 4) // default +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV5 (2 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV8 (3 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV10 (4 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV16 (5 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV20 (6 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_ODR_DIV40 (7 << 4) +#define ICM40609_ACCEL_UI_FILT_BW_LP_TRIVIAL_400HZ_ODR (14 << 4) // Bit[7:4] - Low Latency +#define ICM40609_ACCEL_UI_FILT_BW_LP_TRIVIAL_200HZ_8XODR (15 << 4) // Bit[7:4] - Low Latency + +// REG_GYRO_ACCEL_CONFIG0 - 0x52 bits [3:0] +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV2 (0 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV4 (1 << 0) // default +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV5 (2 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV8 (3 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV10 (4 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV16 (5 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV20 (6 << 0) +#define ICM40609_GYRO_UI_FILT_BW_ODR_DIV40 (7 << 0) +#define ICM40609_GYRO_UI_FILT_BW_LP_TRIVIAL_400HZ_ODR (14 << 0) // Bit[3:0] - Low Latency +#define ICM40609_GYRO_UI_FILT_BW_LP_TRIVIAL_200HZ_8XODR (15 << 0) // Bit[3:0] - Low Latency + +// REG_ACCEL_CONFIG_STATIC2 - 0x03 bit [0] +#define ICM40609_ACCEL_AAF_DIS (1 << 0) + +// REG_GYRO_CONFIG_STATIC2 - 0x0B bit [1] +#define ICM40609_GYRO_AAF_DIS (1 << 1) + +//REG_GYRO_CONFIG_STATIC2 - 0x0B bit [0] +#define ICM40609_GYRO_NF_DIS_BIT (1 << 0) + +// GYRO_HPF_BW_IND - 0x13 bit [3:1] — High-pass filter 3dB cutoff frequency selection +#define ICM40609_GYRO_HPF_BW_IND_MASK (0x07 << 1) // bits [3:1] + +// GYRO_HPF_ORD_IND [0] — High-pass filter order (1st or 2nd) +#define ICM40609_GYRO_HPF_ORD_IND_MASK (1 << 0) + +// GYRO_CONFIG1 (0x51) +#define ICM40609_GYRO_UI_FILT_ORD_MASK (0x03 << 2) // bits [3:2] +#define ICM40609_GYRO_DEC2_M2_ORD_MASK (0x03 << 0) // bits [1:0] + +// ACCEL_CONFIG1 (0x53) +#define ICM40609_ACCEL_UI_FILT_ORD_MASK (0x03 << 3) // bits [4:3] +#define ICM40609_ACCEL_DEC2_M2_ORD_MASK (0x03 << 1) // bits [2:1] + +#define ICM40609_ACCEL_DATA_X1_UI 0x1F +#define ICM40609_GYRO_DATA_X1_UI 0x25 + +#define ICM40609_RESET_REG 0x11 +#define ICM40609_SOFT_RESET_VAL 0x01 + +#ifndef ICM40609_LOCK +// Default: 24 MHz max SPI frequency +#define ICM40609_MAX_SPI_CLK_HZ 24000000 +#else +// Use the supplied value +#define ICM40609_MAX_SPI_CLK_HZ ICM40609_LOCK +#endif + +#define ICM40609_AAF_PROFILE_COUNT 63 + +// Table 5.2 Bandwidth (Hz) +typedef struct { + uint16_t hz; + uint8_t delt; + uint16_t deltsqr; + uint8_t bitshift; +} ICM40609_AafProfile; + + +static const ICM40609_AafProfile aafProfiles[ICM40609_AAF_PROFILE_COUNT] = { + { 42, 1, 1, 15 }, + { 84, 2, 4, 13 }, + { 126, 3, 9, 12 }, + { 170, 4, 16, 11 }, + { 213, 5, 25, 10 }, + { 258, 6, 36, 10 }, + { 303, 7, 49, 9 }, + { 348, 8, 64, 9 }, + { 394, 9, 81, 9 }, + { 441, 10, 100, 8 }, + { 488, 11, 122, 8 }, + { 536, 12, 144, 8 }, + { 585, 13, 170, 8 }, + { 634, 14, 196, 8 }, + { 684, 15, 224, 7 }, + { 734, 16, 256, 7 }, + { 785, 17, 288, 7 }, + { 837, 18, 324, 7 }, + { 890, 19, 360, 6 }, + { 943, 20, 400, 6 }, + { 997, 21, 440, 6 }, + { 1051, 22, 488, 6 }, + { 1107, 23, 528, 6 }, + { 1163, 24, 576, 6 }, + { 1220, 25, 624, 6 }, + { 1277, 26, 680, 6 }, + { 1336, 27, 736, 5 }, + { 1395, 28, 784, 5 }, + { 1454, 29, 848, 5 }, + { 1515, 30, 896, 5 }, + { 1577, 31, 960, 5 }, + { 1639, 32, 1024, 5 }, + { 1702, 33, 1088, 5 }, + { 1766, 34, 1152, 5 }, + { 1830, 35, 1232, 5 }, + { 1896, 36, 1296, 5 }, + { 1962, 37, 1376, 4 }, + { 2029, 38, 1440, 4 }, + { 2097, 39, 1536, 4 }, + { 2166, 40, 1600, 4 }, + { 2235, 41, 1696, 4 }, + { 2306, 42, 1760, 4 }, + { 2377, 43, 1856, 4 }, + { 2449, 44, 1952, 4 }, + { 2522, 45, 2016, 4 }, + { 2596, 46, 2112, 4 }, + { 2671, 47, 2208, 4 }, + { 2746, 48, 2304, 4 }, + { 2823, 49, 2400, 4 }, + { 2900, 50, 2496, 4 }, + { 2978, 51, 2592, 4 }, + { 3057, 52, 2720, 4 }, + { 3137, 53, 2816, 4 }, + { 3217, 54, 2944, 3 }, + { 3299, 55, 3008, 3 }, + { 3381, 56, 3136, 3 }, + { 3464, 57, 3264, 3 }, + { 3548, 58, 3392, 3 }, + { 3633, 59, 3456, 3 }, + { 3718, 60, 3584, 3 }, + { 3805, 61, 3712, 3 }, + { 3892, 62, 3840, 3 }, + { 3979, 63, 3968, 3 }, +}; + +/* + * ICM-40609D Group Delay @DC (ODR = 8000 Hz) + * + * +-------------------+--------------------+----------+ + * | Filter Order | Delay (UI_FILT_BW) | NBW (Hz) | + * +-------------------+--------------------+----------+ + * | 1st order filter | 0.2 ms | 2204.6 | + * | 2nd order filter | 0.2 ms | 2204.6 | + * | 3rd order filter | 0.2 ms | 2096.3 | + * +-------------------+--------------------+----------+ + * + * Note: + * Delay is independent of UI_FILT_BW when ODR = 8000Hz. + * 5.4 UI FILTER BLOCK TDK ICM-40609D Datasheet Rev 1.2 (2023) + * + * Filter order (standard DSP behavior): + * 1st order -6 dB/octave + * 2nd order -12 dB/octave + * 3rd order -18 dB/octave + * These roll-off rates are typical for LPF/HPF filters in digital signal processing (DSP). + */ +typedef enum { + ICM40609_UI_FILT_ORDER_1ST = 0, + ICM40609_UI_FILT_ORDER_2ND = 1, + ICM40609_UI_FILT_ORDER_3RD = 2 +} icm40609UiFiltOrder_e; + +typedef enum { + ICM40609_HPF_ORDER_1ST = 0, + ICM40609_HPF_ORDER_2ND = 1 +} icm40609HpfOrder_e; + +// Bandwidth selection for High-Pass Filter +// ICM40609_REG_GYRO_CONFIG_STATIC10 - 0x13 bits [3:1] +// NOTE: clarify with new datasheet, section 5.6 not found in V1.2 +typedef enum { + ICM40609_HPF_BW_0 = 0, + ICM40609_HPF_BW_1 = 1, + ICM40609_HPF_BW_2 = 2, + ICM40609_HPF_BW_3 = 3, + ICM40609_HPF_BW_4 = 4, + ICM40609_HPF_BW_5 = 5, + ICM40609_HPF_BW_6 = 6, + ICM40609_HPF_BW_7 = 7, +} icm40609HpfBw_e; + +// Bandwidth selection for Notch Filter GYRO_NF_BW_SEL +// ICM40609_REG_GYRO_CONFIG_STATIC10 - 0x13 bits [6:4] +typedef enum { + ICM40609_GYRO_NF_BW_1449HZ = 0, + ICM40609_GYRO_NF_BW_680HZ = 1, + ICM40609_GYRO_NF_BW_329HZ = 2, + ICM40609_GYRO_NF_BW_162HZ = 3, + ICM40609_GYRO_NF_BW_80HZ = 4, + ICM40609_GYRO_NF_BW_40HZ = 5, + ICM40609_GYRO_NF_BW_20HZ = 6, + ICM40609_GYRO_NF_BW_10HZ = 7, +} icm40609GyroNfBw_e; + +typedef enum { + ICM40609_TEMP_FILT_BW_4000HZ = 0, // 4000Hz, 0.125ms latency (default) + ICM40609_TEMP_FILT_BW_170HZ = 1, // 170Hz, 1ms latency + ICM40609_TEMP_FILT_BW_82HZ = 2, // 82Hz, 2ms latency + ICM40609_TEMP_FILT_BW_40HZ = 3, // 40Hz, 4ms latency + ICM40609_TEMP_FILT_BW_20HZ = 4, // 20Hz, 8ms latency + ICM40609_TEMP_FILT_BW_10HZ = 5, // 10Hz, 16ms latency + ICM40609_TEMP_FILT_BW_5HZ = 6, // 5Hz, 32ms latency +} icm40609TempFiltBw_e; + +static void icm40609SelectUserBank(const extDevice_t *dev, uint8_t bank) +{ + if (bank > 4) { + return; // out of range + } + spiWriteReg(dev, ICM40609_REG_BANK_SEL, bank & 0x07); // bit [2:0] +} + +static void setGyroAccPowerMode(const extDevice_t *dev, bool enable) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + spiWriteReg(dev, ICM40609_REG_PWR_MGMT0, + ICM40609_RC_ON | + ICM40609_TEMP_SENSOR_ENABLED | + (enable ? ICM40609_GYRO_MODE_LN | ICM40609_ACCEL_MODE_LN + : ICM40609_GYRO_MODE_OFF | ICM40609_ACCEL_MODE_OFF)); + + if (enable) { + delayMicroseconds(200); + } else { + delay(50); + } +} + +static void icm40609GetAafParams(uint16_t targetHz, ICM40609_AafProfile* res) +{ + uint16_t i = 0; + while (i < ICM40609_AAF_PROFILE_COUNT && targetHz > aafProfiles[i].hz) { + i++; + } + if (i < ICM40609_AAF_PROFILE_COUNT) { + *res = aafProfiles[i]; + } else { + // not found - Requested frequency is higher than max available + *res = aafProfiles[ICM40609_AAF_PROFILE_COUNT - 1]; + } +} + +static void icm40609SetAccelAafByHz(const extDevice_t *dev, bool aafEnable, uint16_t targetHz) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_2); + + if (aafEnable && targetHz > 0) { + ICM40609_AafProfile aafProfile; + + icm40609GetAafParams(targetHz, &aafProfile); + + uint8_t reg03 = spiReadRegMsk(dev, ICM40609_REG_ACCEL_CONFIG_STATIC2); + + reg03 &= ~ICM40609_ACCEL_AAF_DIS; // Clear ACCEL_AAF_DIS to enable AAF + reg03 = (reg03 & 0x81) | (aafProfile.delt << 1); // Keep reserved bit 7, set ACCEL_AAF_DELT + spiWriteReg(dev, ICM40609_REG_ACCEL_CONFIG_STATIC2, reg03); + + uint8_t reg04 = aafProfile.deltsqr & 0xFF; + uint8_t reg05 = ((aafProfile.bitshift & 0x0F) << 4) | ((aafProfile.deltsqr >> 8) & 0x0F); + + spiWriteReg(dev, ICM40609_REG_ACCEL_CONFIG_STATIC3, reg04); + spiWriteReg(dev, ICM40609_REG_ACCEL_CONFIG_STATIC4, reg05); + + } else { + uint8_t reg03 = spiReadRegMsk(dev, ICM40609_REG_ACCEL_CONFIG_STATIC2); + reg03 |= ICM40609_ACCEL_AAF_DIS; // Set ACCEL_AAF_DIS to disable AAF + spiWriteReg(dev, ICM40609_REG_ACCEL_CONFIG_STATIC2, reg03); + } + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); +} + +static void icm40609SetGyroAafByHz(const extDevice_t *dev, bool aafEnable, uint16_t targetHz) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_1); + + if (aafEnable && targetHz > 0) { + ICM40609_AafProfile aafProfile; + + icm40609GetAafParams(targetHz, &aafProfile); + + uint8_t reg0C = aafProfile.delt & 0x3F; + uint8_t reg0D = aafProfile.deltsqr & 0xFF; + uint8_t reg0E = ((aafProfile.bitshift & 0x0F) << 4) | ((aafProfile.deltsqr >> 8) & 0x0F); + + uint8_t reg0B = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG_STATIC2); + reg0B &= ~ICM40609_GYRO_AAF_DIS; // Clear AAF_DIS (bit1) to enable AAF + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC2, reg0B); + + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC3, reg0C); + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC4, reg0D); + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC5, reg0E); + + } else { + uint8_t reg0B = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG_STATIC2); + reg0B |= ICM40609_GYRO_AAF_DIS; // Set AAF_DIS (bit1) to disable AAF + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC2, reg0B); + } + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); +} + +static void icm40609SetGyroHPF(const extDevice_t *dev, bool hpfEnable, icm40609HpfBw_e hpfBwInd, icm40609HpfOrder_e hpfOrder) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_1); + + uint8_t reg13 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG_STATIC10); + + reg13 &= ~(ICM40609_GYRO_HPF_BW_IND_MASK | ICM40609_GYRO_HPF_ORD_IND_MASK); // clear HPF bits + + if (hpfEnable) { + reg13 |= (hpfBwInd << 1) | (hpfOrder << 0); + } + + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC10, reg13); + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); +} + +static void icm40609SetGyroNotch(const extDevice_t *dev, bool notchEnable, icm40609GyroNfBw_e bwSel, float fdesiredKhz) +{ + if (fdesiredKhz < 1.0f || fdesiredKhz > 3.0f) { + return; // (1kHz to 3kHz) Operating the notch filter outside this range is not supported. + } + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_1); + + // Enable/disable Notch filter + uint8_t reg2 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG_STATIC2); + if (notchEnable) { + reg2 &= ~ICM40609_GYRO_NF_DIS_BIT; + } else { + reg2 |= ICM40609_GYRO_NF_DIS_BIT; // Bypass + } + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC2, reg2); + + if (notchEnable) { + // Set Bandwidth in STATIC10 (0x13) + uint8_t reg13 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG_STATIC10); + reg13 &= ~(0x07 << 4); + reg13 |= (bwSel & 0x07) << 4; // GYRO_NF_BW_SEL [6:4] + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC10, reg13); + + // Section 5.1.1 (v1.2) Frequency of Notch Filter (each axis) + // Calculate COSWZ and SEL based on desired frequency + float coswz = cosf(2.0f * M_PIf * fdesiredKhz / 32.0f); + uint8_t nf_coswz_lsb = 0; + uint8_t nf_coswz_msb = 0; + uint8_t nf_coswz_sel = 0; + + if (fabsf(coswz) <= 0.875f) { + int16_t nf_coswz = (int16_t)roundf(coswz * 256.0f); + nf_coswz_lsb = nf_coswz & 0xFF; + nf_coswz_msb = (nf_coswz >> 8) & 0x01; + nf_coswz_sel = 0; + } else { + nf_coswz_sel = 1; + int16_t nf_coswz; + if (coswz > 0.875f) { + nf_coswz = (int16_t)roundf(8.0f * (1.0f - coswz) * 256.0f); + } else { + nf_coswz = (int16_t)roundf(8.0f * (1.0f + coswz) * 256.0f); + } + nf_coswz_lsb = nf_coswz & 0xFF; + nf_coswz_msb = (nf_coswz >> 8) & 0x01; + } + + // Write NF_COSWZ[7:0] for X, Y, Z + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC6, nf_coswz_lsb); // X + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC7, nf_coswz_lsb); // Y + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC8, nf_coswz_lsb); // Z + + // Write NF_COSWZ[8] and NF_COSWZ_SEL into STATIC9 (0x12) + uint8_t reg9 = 0; + reg9 |= (nf_coswz_msb << 0); // X NF_COSWZ[8] + reg9 |= (nf_coswz_msb << 1); // Y NF_COSWZ[8] + reg9 |= (nf_coswz_msb << 2); // Z NF_COSWZ[8] + reg9 |= (nf_coswz_sel << 3); // X COSWZ_SEL + reg9 |= (nf_coswz_sel << 4); // Y COSWZ_SEL + reg9 |= (nf_coswz_sel << 5); // Z COSWZ_SEL + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG_STATIC9, reg9); + } + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); +} + +static void icm40609SetTempFiltBw(const extDevice_t *dev, icm40609TempFiltBw_e bw) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + uint8_t reg51 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG1); + reg51 &= ~(0x07 << 5); + reg51 |= (bw << 5); + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG1, reg51); +} + +static void icm40609SetGyroUiFiltOrder(const extDevice_t *dev, icm40609UiFiltOrder_e order) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + uint8_t reg51 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG1); + reg51 &= ~ICM40609_GYRO_UI_FILT_ORD_MASK; + reg51 |= (order << 2); // Write GYRO_UI_FILT_ORD to bits [3:2] + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG1, reg51); +} + +static void icm40609SetAccelUiFiltOrder(const extDevice_t *dev, icm40609UiFiltOrder_e order) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + uint8_t reg53 = spiReadRegMsk(dev, ICM40609_REG_GYRO_ACCEL_CONFIG1); + reg53 &= ~ICM40609_ACCEL_UI_FILT_ORD_MASK; + reg53 |= (order << 3); // Write ACCEL_UI_FILT_ORD to bits [4:3] + spiWriteReg(dev, ICM40609_REG_GYRO_ACCEL_CONFIG1, reg53); +} + +static void icm40609SetGyroDec2M2(const extDevice_t *dev, bool enable) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + uint8_t reg51 = spiReadRegMsk(dev, ICM40609_REG_GYRO_CONFIG1); + reg51 &= ~ICM40609_GYRO_DEC2_M2_ORD_MASK; + + if (enable) { + reg51 |= (2 << 0); + } + + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG1, reg51); +} + +// Set endianness for sensor data (bit 4 of INTF_CONFIG0, reg 0x4C) +// true = Big Endian +// false = Little Endian +static void icm40609SetEndianess(const extDevice_t *dev, bool bigEndian) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + uint8_t reg4C = spiReadRegMsk(dev, ICM40609_REG_INTF_CONFIG0); + reg4C &= ~(1 << 4); + reg4C |= bigEndian << 4; + + spiWriteReg(dev, ICM40609_REG_INTF_CONFIG0, reg4C); +} + +void icm40609AccInit(accDev_t *acc) +{ + acc->acc_1G = 2048; // 16g scale + acc->gyro->accSampleRateHz = 1000; + +} + +void icm40609GyroInit(gyroDev_t *gyro) +{ + const extDevice_t *dev = &gyro->dev; + spiSetClkDivisor(dev, spiCalculateDivider(ICM40609_MAX_SPI_CLK_HZ)); + + mpuGyroInit(gyro); + gyro->accDataReg = ICM40609_ACCEL_DATA_X1_UI; + gyro->gyroDataReg = ICM40609_GYRO_DATA_X1_UI; + + setGyroAccPowerMode(dev, false); + + icm40609SetEndianess(dev, true); + + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + spiWriteReg(dev, ICM40609_REG_GYRO_CONFIG0, ICM40609_GYRO_FS_SEL_2000DPS | ICM40609_GYRO_ODR_8KHZ); + gyro->scale = GYRO_SCALE_2000DPS; + gyro->gyroRateKHz = GYRO_RATE_8_kHz; + gyro->gyroSampleRateHz = 8000; + + spiWriteReg(dev, ICM40609_REG_ACCEL_CONFIG0, ICM40609_ACCEL_FS_SEL_16G | ICM40609_ACCEL_ODR_1KHZ ); + + icm40609SetTempFiltBw(dev, ICM40609_TEMP_FILT_BW_4000HZ); // 4000Hz, 0.125ms latency (default) + icm40609SetGyroUiFiltOrder(dev, ICM40609_UI_FILT_ORDER_3RD); + icm40609SetAccelUiFiltOrder(dev, ICM40609_UI_FILT_ORDER_3RD); + icm40609SetGyroDec2M2(dev, true); + + // Set filter bandwidth: Low Latency + spiWriteReg(&gyro->dev, ICM40609_REG_GYRO_ACCEL_CONFIG0, + ICM40609_ACCEL_UI_FILT_BW_LP_TRIVIAL_200HZ_8XODR | + ICM40609_GYRO_UI_FILT_BW_LP_TRIVIAL_200HZ_8XODR); + + uint16_t gyroHWLpf; // Anti-Alias Filter (AAF) in Hz + switch (gyroConfig()->gyro_hardware_lpf) { + case GYRO_HARDWARE_LPF_NORMAL: + gyroHWLpf = 213; + break; + case GYRO_HARDWARE_LPF_OPTION_1: + gyroHWLpf = 488; + break; + case GYRO_HARDWARE_LPF_OPTION_2: + gyroHWLpf = 997; + break; +#ifdef USE_GYRO_DLPF_EXPERIMENTAL + case GYRO_HARDWARE_LPF_EXPERIMENTAL: + gyroHWLpf = 1962; + break; +#endif + default: + gyroHWLpf = 213; + } + + icm40609SetGyroAafByHz(dev, true, gyroHWLpf); + icm40609SetAccelAafByHz(dev, true, gyroHWLpf); + + icm40609SetGyroNotch(dev, true, ICM40609_GYRO_NF_BW_1449HZ, 1.5f); + + icm40609SetGyroHPF(dev, true, ICM40609_HPF_BW_1, ICM40609_HPF_ORDER_1ST); + + // Enable interrupt + spiWriteReg(dev, ICM40609_REG_INT_SOURCE0, ICM40609_UI_DRDY_INT1_EN); + + // Set INT1 to pulse mode, push-pull, active high + spiWriteReg(dev, ICM40609_REG_INT_CONFIG, + ICM40609_INT1_MODE_PULSED | + ICM40609_INT1_DRIVE_PUSH_PULL | + ICM40609_INT1_POLARITY_ACTIVE_HIGH); + + spiWriteReg(dev, ICM40609_REG_INT_CONFIG0, ICM40609_UI_DRDY_INT_CLEAR_STATUS); // auto clear after read + + // Set INT1 pulse width to 8us, deassertion enabled, async reset disabled + spiWriteReg(dev, ICM40609_REG_INT_CONFIG1, + ICM40609_INT_TPULSE_8US | + ICM40609_INT_TDEASSERT_DISABLED | + ICM40609_INT_ASYNC_RESET_DISABLED); + + setGyroAccPowerMode(dev, true); + +} + +uint8_t icm40609SpiDetect(const extDevice_t *dev) +{ + icm40609SelectUserBank(dev, ICM40609_USER_BANK_0); + + spiWriteReg(dev, ICM40609_RESET_REG, ICM40609_SOFT_RESET_VAL); + delay(1); + + uint8_t whoAmI = spiReadRegMsk(dev, ICM40609_WHO_AM_I_REG); + if (whoAmI == ICM40609_WHO_AM_I_CONST) { + return ICM_40609_SPI; + } + return MPU_NONE; +} + +bool icm40609SpiAccDetect(accDev_t *acc) +{ + if (acc->mpuDetectionResult.sensor == ICM_40609_SPI) { + acc->initFn = icm40609AccInit; + acc->readFn = mpuAccReadSPI; + return true; + } + return false; +} + +bool icm40609SpiGyroDetect(gyroDev_t *gyro) +{ + if (gyro->mpuDetectionResult.sensor == ICM_40609_SPI) { + gyro->initFn = icm40609GyroInit; + gyro->readFn = mpuGyroReadSPI; + return true; + } + return false; +} + +#endif // USE_ACCGYRO_ICM40609D diff --git a/src/main/drivers/accgyro/accgyro_spi_icm40609.h b/src/main/drivers/accgyro/accgyro_spi_icm40609.h new file mode 100644 index 0000000000..0211311079 --- /dev/null +++ b/src/main/drivers/accgyro/accgyro_spi_icm40609.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +#pragma once + +#include "drivers/bus.h" + +void icm40609AccInit(accDev_t *acc); +void icm40609GyroInit(gyroDev_t *gyro); + +uint8_t icm40609SpiDetect(const extDevice_t *dev); + +bool icm40609SpiAccDetect(accDev_t *acc); +bool icm40609SpiGyroDetect(gyroDev_t *gyro); diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 2a3a327e4d..afdc21e2fa 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -28,7 +28,7 @@ #include "platform.h" -#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42653) +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42652) || defined(USE_ACCGYRO_IIM42653) #include "common/axis.h" #include "common/utils.h" @@ -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: @@ -269,6 +284,9 @@ uint8_t icm426xxSpiDetect(const extDevice_t *dev) case ICM42688P_WHO_AM_I_CONST: icmDetected = ICM_42688P_SPI; break; + case IIM42652_WHO_AM_I_CONST: + icmDetected = IIM_42652_SPI; + break; case IIM42653_WHO_AM_I_CONST: icmDetected = IIM_42653_SPI; break; @@ -291,6 +309,7 @@ void icm426xxAccInit(accDev_t *acc) { switch (acc->mpuDetectionResult.sensor) { case IIM_42653_SPI: + case IIM_42652_SPI: acc->acc_1G = 512 * 2; // Accel scale 32g (1024 LSB/g) break; default: @@ -304,6 +323,7 @@ bool icm426xxSpiAccDetect(accDev_t *acc) switch (acc->mpuDetectionResult.sensor) { case ICM_42605_SPI: case ICM_42688P_SPI: + case IIM_42652_SPI: case IIM_42653_SPI: break; default: @@ -412,6 +432,7 @@ bool icm426xxSpiGyroDetect(gyroDev_t *gyro) case ICM_42688P_SPI: gyro->scale = GYRO_SCALE_2000DPS; break; + case IIM_42652_SPI: case IIM_42653_SPI: gyro->scale = GYRO_SCALE_4000DPS; break; @@ -429,6 +450,8 @@ static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig { switch (gyroModel){ case ICM_42605_SPI: + case IIM_42652_SPI: + case IIM_42653_SPI: switch (config) { case GYRO_HARDWARE_LPF_NORMAL: return aafLUT42605[AAF_CONFIG_258HZ]; @@ -441,7 +464,6 @@ static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig } case ICM_42688P_SPI: - case IIM_42653_SPI: default: switch (config) { case GYRO_HARDWARE_LPF_NORMAL: @@ -460,4 +482,4 @@ static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig } } -#endif // USE_GYRO_SPI_ICM42605 || USE_GYRO_SPI_ICM42688P || USE_ACCGYRO_IIM42653 +#endif // USE_GYRO_SPI_ICM42605 || USE_GYRO_SPI_ICM42688P || USE_ACCGYRO_IIM42652 || USE_ACCGYRO_IIM42653 diff --git a/src/main/drivers/adc_impl.h b/src/main/drivers/adc_impl.h index 66baa5da9c..add1083bf2 100644 --- a/src/main/drivers/adc_impl.h +++ b/src/main/drivers/adc_impl.h @@ -20,10 +20,14 @@ #pragma once +#include "platform.h" #include "drivers/adc.h" #include "drivers/dma.h" #include "drivers/io_types.h" -#include "drivers/rcc_types.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif #if defined(STM32F4) || defined(STM32F7) #define ADC_TAG_MAP_COUNT 16 @@ -73,8 +77,8 @@ typedef struct adcTagMap_s { #define ADC_DEVICES_345 ((1 << ADCDEV_3)|(1 << ADCDEV_4)|(1 << ADCDEV_5)) typedef struct adcDevice_s { -#if !defined(SIMULATOR_BUILD) ADC_TypeDef* ADCx; +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rccADC; #endif #if !defined(USE_DMA_SPEC) diff --git a/src/main/drivers/bus_i2c.h b/src/main/drivers/bus_i2c.h index 74dcfadb3d..29176a9a7c 100644 --- a/src/main/drivers/bus_i2c.h +++ b/src/main/drivers/bus_i2c.h @@ -23,7 +23,6 @@ #include "platform.h" #include "drivers/io_types.h" -#include "drivers/rcc_types.h" #ifndef I2C_DEVICE #define I2C_DEVICE I2CINVALID @@ -31,20 +30,18 @@ typedef enum I2CDevice { I2CINVALID = -1, - I2CDEV_1 = 0, + I2CDEV_FIRST = 0, +#if defined(USE_I2C_DEVICE_0) + I2CDEV_0 = I2CDEV_FIRST, + I2CDEV_1, +#else + I2CDEV_1 = I2CDEV_FIRST, +#endif I2CDEV_2, I2CDEV_3, I2CDEV_4, } I2CDevice; -#if defined(STM32F4) || defined(APM32F4) -#define I2CDEV_COUNT 3 -#elif defined(STM32F7) -#define I2CDEV_COUNT 4 -#else -#define I2CDEV_COUNT 4 -#endif - // Macros to convert between CLI bus number and I2CDevice. #define I2C_CFG_TO_DEV(x) ((x) - 1) #define I2C_DEV_TO_CFG(x) ((x) + 1) @@ -54,7 +51,7 @@ typedef enum I2CDevice { #define I2C_ADDR7_MAX 119 struct i2cConfig_s; -void i2cHardwareConfigure(const struct i2cConfig_s *i2cConfig); +void i2cPinConfigure(const struct i2cConfig_s *i2cConfig); void i2cInit(I2CDevice device); bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *data); bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg, uint8_t data); diff --git a/src/main/drivers/bus_i2c_impl.h b/src/main/drivers/bus_i2c_impl.h index 0dd1fb2c99..2ce413685b 100644 --- a/src/main/drivers/bus_i2c_impl.h +++ b/src/main/drivers/bus_i2c_impl.h @@ -23,7 +23,10 @@ #include "platform.h" #include "drivers/io_types.h" -#include "drivers/rcc_types.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif #define I2C_TIMEOUT_US 10000 #define I2C_TIMEOUT_SYS_TICKS (I2C_TIMEOUT_US / 1000) @@ -32,12 +35,12 @@ typedef struct i2cPinDef_s { ioTag_t ioTag; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN uint8_t af; #endif } i2cPinDef_t; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN #define I2CPINDEF(pin, af) { DEFIO_TAG_E(pin), af } #else #define I2CPINDEF(pin) { DEFIO_TAG_E(pin) } @@ -48,14 +51,16 @@ typedef struct i2cHardware_s { I2C_TypeDef *reg; i2cPinDef_t sclPins[I2C_PIN_SEL_MAX]; i2cPinDef_t sdaPins[I2C_PIN_SEL_MAX]; +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif uint8_t ev_irq; uint8_t er_irq; } i2cHardware_t; extern const i2cHardware_t i2cHardware[]; -#if defined(STM32F4) +#if I2C_TRAIT_STATE typedef struct i2cState_s { volatile bool error; volatile bool busy; @@ -74,7 +79,7 @@ typedef struct i2cDevice_s { I2C_TypeDef *reg; IO_t scl; IO_t sda; -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN uint8_t sclAF; uint8_t sdaAF; #endif @@ -82,10 +87,10 @@ typedef struct i2cDevice_s { uint16_t clockSpeed; // MCU/Driver dependent member follows -#if defined(STM32F4) +#if I2C_TRAIT_STATE i2cState_t state; #endif -#if defined(USE_HAL_DRIVER) || defined(AT32F4) +#if I2C_TRAIT_HANDLE I2C_HandleTypeDef handle; #endif } i2cDevice_t; diff --git a/src/main/drivers/bus_quadspi.c b/src/main/drivers/bus_quadspi.c index 4944e12d0d..7ce4069cd4 100644 --- a/src/main/drivers/bus_quadspi.c +++ b/src/main/drivers/bus_quadspi.c @@ -32,7 +32,10 @@ #include "drivers/bus_quadspi_impl.h" #include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/rcc.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc.h" +#endif #include "pg/bus_quadspi.h" @@ -264,7 +267,9 @@ void quadSpiPinConfigure(const quadSpiConfig_t *pConfig) if (haveResources) { pDev->dev = hw->reg; +#if PLATFORM_TRAIT_RCC pDev->rcc = hw->rcc; +#endif } } } diff --git a/src/main/drivers/bus_quadspi.h b/src/main/drivers/bus_quadspi.h index 6defb3514f..7fdb75cceb 100644 --- a/src/main/drivers/bus_quadspi.h +++ b/src/main/drivers/bus_quadspi.h @@ -23,7 +23,6 @@ #pragma once #include "drivers/io_types.h" -#include "drivers/rcc_types.h" #include "pg/pg.h" #include "pg/pg_ids.h" diff --git a/src/main/drivers/bus_quadspi_impl.h b/src/main/drivers/bus_quadspi_impl.h index eda709b918..b226f2723a 100644 --- a/src/main/drivers/bus_quadspi_impl.h +++ b/src/main/drivers/bus_quadspi_impl.h @@ -22,17 +22,19 @@ #pragma once +#include "platform.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif + typedef struct quadSpiPinDef_s { ioTag_t pin; -#if defined(STM32H7) +#if QUADSPI_TRAIT_AF_PIN uint8_t af; #endif } quadSpiPinDef_t; -#if defined(STM32H7) -#define MAX_QUADSPI_PIN_SEL 3 -#endif - typedef struct quadSpiHardware_s { QUADSPIDevice device; QUADSPI_TypeDef *reg; @@ -48,7 +50,9 @@ typedef struct quadSpiHardware_s { quadSpiPinDef_t bk2IO3Pins[MAX_QUADSPI_PIN_SEL]; quadSpiPinDef_t bk2CSPins[MAX_QUADSPI_PIN_SEL]; +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif } quadSpiHardware_t; extern const quadSpiHardware_t quadSpiHardware[]; @@ -78,9 +82,12 @@ typedef struct QUADSPIDevice_s { uint8_t bk2IO3AF; uint8_t bk2CSAF; #endif + +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif volatile uint16_t errorCount; -#if defined(USE_HAL_DRIVER) +#if QUADSPI_TRAIT_HANDLE QSPI_HandleTypeDef hquadSpi; #endif } quadSpiDevice_t; diff --git a/src/main/drivers/bus_spi_impl.h b/src/main/drivers/bus_spi_impl.h index cccca9a73d..4b5106c8c4 100644 --- a/src/main/drivers/bus_spi_impl.h +++ b/src/main/drivers/bus_spi_impl.h @@ -20,13 +20,19 @@ #pragma once +#include "platform.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif + #define SPI_TIMEOUT_US 10000 #define BUS_SPI_FREE 0x0 typedef struct spiPinDef_s { ioTag_t pin; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if SPI_TRAIT_AF_PIN //TODO: move to GPIO uint8_t af; #endif } spiPinDef_t; @@ -37,33 +43,40 @@ typedef struct spiHardware_s { spiPinDef_t sckPins[MAX_SPI_PIN_SEL]; spiPinDef_t misoPins[MAX_SPI_PIN_SEL]; spiPinDef_t mosiPins[MAX_SPI_PIN_SEL]; -#ifndef STM32F7 +#if SPI_TRAIT_AF_PORT uint8_t af; #endif + +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif + #ifdef USE_DMA uint8_t dmaIrqHandler; #endif } spiHardware_t; -extern const spiHardware_t spiHardware[]; +extern const spiHardware_t spiHardware[SPIDEV_COUNT]; typedef struct SPIDevice_s { SPI_TypeDef *dev; ioTag_t sck; ioTag_t miso; ioTag_t mosi; -#if defined(STM32F7) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if SPI_TRAIT_AF_PIN uint8_t sckAF; uint8_t misoAF; uint8_t mosiAF; -#else +#endif +#if SPI_TRAIT_AF_PORT uint8_t af; #endif -#if defined(HAL_SPI_MODULE_ENABLED) +#if SPI_TRAIT_HANDLE SPI_HandleTypeDef hspi; #endif +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif volatile uint16_t errorCount; bool leadingEdge; #ifdef USE_DMA diff --git a/src/main/drivers/dshot.h b/src/main/drivers/dshot.h index 19105b0659..609fc22892 100644 --- a/src/main/drivers/dshot.h +++ b/src/main/drivers/dshot.h @@ -95,6 +95,8 @@ uint16_t prepareDshotPacket(dshotProtocolControl_t *pcb); extern bool useDshotTelemetry; extern uint8_t dshotMotorCount; +bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig); + #ifdef USE_DSHOT_TELEMETRY typedef struct dshotTelemetryMotorState_s { @@ -113,7 +115,6 @@ typedef struct dshotTelemetryState_s { dshotRawValueState_t rawValueState; } dshotTelemetryState_t; -#ifdef USE_DSHOT_TELEMETRY extern uint32_t readDoneCount; FAST_DATA_ZERO_INIT extern uint32_t inputStampUs; @@ -125,10 +126,6 @@ typedef struct dshotTelemetryCycleCounters_s { FAST_DATA_ZERO_INIT extern dshotTelemetryCycleCounters_t dshotDMAHandlerCycleCounters; -#endif - -bool dshotPwmDevInit(motorDevice_t *device, const motorDevConfig_t *motorConfig); - extern dshotTelemetryState_t dshotTelemetryState; #ifdef USE_DSHOT_TELEMETRY_STATS diff --git a/src/main/drivers/dshot_command.c b/src/main/drivers/dshot_command.c index 90f80185d8..fc95dbc3aa 100644 --- a/src/main/drivers/dshot_command.c +++ b/src/main/drivers/dshot_command.c @@ -149,7 +149,20 @@ static bool allMotorsAreIdle(void) bool dshotStreamingCommandsAreEnabled(void) { - return motorIsEnabled() && motorGetMotorEnableTimeMs() && millis() > motorGetMotorEnableTimeMs() + DSHOT_PROTOCOL_DETECTION_DELAY_MS; + static bool firstCommand = true; + bool goodMotorDetectDelay; + + if (firstCommand) { + goodMotorDetectDelay = motorGetMotorEnableTimeMs() && (cmpTimeMs(millis(), motorGetMotorEnableTimeMs()) > DSHOT_PROTOCOL_DETECTION_DELAY_MS); + + if (goodMotorDetectDelay) { + firstCommand = false; + } + } else { + goodMotorDetectDelay = true; + } + + return motorIsEnabled() && goodMotorDetectDelay; } static bool dshotCommandsAreEnabled(dshotCommandType_e commandType) @@ -203,9 +216,11 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot } if (commandType == DSHOT_CMD_TYPE_BLOCKING) { +#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY) bool isBitbangActive = false; #ifdef USE_DSHOT_BITBANG isBitbangActive = isDshotBitbangActive(&motorConfig()->dev); +#endif #endif // Fake command in queue. Blocking commands are launched from cli, and no inline commands are running for (uint8_t i = 0; i < motorDeviceCount(); i++) { diff --git a/src/main/drivers/io.c b/src/main/drivers/io.c index 7c8dc12203..25f905143a 100644 --- a/src/main/drivers/io.c +++ b/src/main/drivers/io.c @@ -22,14 +22,10 @@ #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" #include "common/utils.h" -// io ports defs are stored in array by index now -struct ioPortDef_s { - rccPeriphTag_t rcc; -}; +// io ports defs are stored by index in array ioRecs of ioRec_t ioRec_t* IO_Rec(IO_t io) { @@ -48,39 +44,6 @@ uint16_t IO_Pin(IO_t io) return ioRec->pin; } -#if defined(STM32F4) || defined(APM32F4) -int IO_EXTI_PortSourceGPIO(IO_t io) -{ - return IO_GPIOPortIdx(io); -} -#endif - -int IO_GPIO_PortSource(IO_t io) -{ - return IO_GPIOPortIdx(io); -} - -// zero based pin index -int IO_GPIOPinIdx(IO_t io) -{ - if (!io) { - return -1; - } - return 31 - __builtin_clz(IO_Pin(io)); -} - -#if defined(STM32F4) || defined(APM32F4) -int IO_EXTI_PinSource(IO_t io) -{ - return IO_GPIOPinIdx(io); -} -#endif - -int IO_GPIO_PinSource(IO_t io) -{ - return IO_GPIOPinIdx(io); -} - // claim IO pin, set owner and resources void IOInit(IO_t io, resourceOwner_e owner, uint8_t index) { diff --git a/src/main/drivers/io_def.h b/src/main/drivers/io_def.h index 6566bd34fb..2204005221 100644 --- a/src/main/drivers/io_def.h +++ b/src/main/drivers/io_def.h @@ -41,11 +41,24 @@ // get ioRec by index #define DEFIO_REC_INDEXED(idx) (ioRecs + (idx)) +// split ioTag bits between pin and port +// port is encoded as +1 to avoid collision with 0x0 (false as bool) +#ifndef DEFIO_PORT_PINS +// pins per port +#define DEFIO_PORT_PINS 16 +#endif + +STATIC_ASSERT((DEFIO_PORT_PINS & (DEFIO_PORT_PINS - 1)) == 0, "DEFIO_PORT_PINS must be power of 2"); + +#define DEFIO_PORT_BITSHIFT LOG2(DEFIO_PORT_PINS) +#define DEFIO_PIN_BITMASK ((1 << DEFIO_PORT_BITSHIFT ) - 1) + // ioTag_t accessor macros -#define DEFIO_TAG_MAKE(gpioid, pin) ((ioTag_t)((((gpioid) + 1) << 4) | (pin))) +#define DEFIO_TAG_MAKE(gpioid, pin) ((ioTag_t)((((gpioid) + 1) << DEFIO_PORT_BITSHIFT) | (pin))) #define DEFIO_TAG_ISEMPTY(tag) (!(tag)) -#define DEFIO_TAG_GPIOID(tag) (((tag) >> 4) - 1) -#define DEFIO_TAG_PIN(tag) ((tag) & 0x0f) +#define DEFIO_TAG_GPIOID(tag) (((tag) >> DEFIO_PORT_BITSHIFT) - 1) +#define DEFIO_TAG_PIN(tag) ((tag) & DEFIO_PIN_BITMASK) + // TARGET must define used pins #include "target.h" diff --git a/src/main/drivers/rangefinder/rangefinder_hcsr04.c b/src/main/drivers/rangefinder/rangefinder_hcsr04.c index 72d3e201b8..dc01608565 100644 --- a/src/main/drivers/rangefinder/rangefinder_hcsr04.c +++ b/src/main/drivers/rangefinder/rangefinder_hcsr04.c @@ -30,7 +30,6 @@ #include "drivers/exti.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" #include "drivers/time.h" #include "drivers/rangefinder/rangefinder.h" 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/drivers/rx/rx_spi.c b/src/main/drivers/rx/rx_spi.c index 05c6e803ea..19e7d69a1e 100644 --- a/src/main/drivers/rx/rx_spi.c +++ b/src/main/drivers/rx/rx_spi.c @@ -35,7 +35,6 @@ #include "drivers/io.h" #include "drivers/io_impl.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" #include "drivers/system.h" #include "drivers/time.h" diff --git a/src/main/drivers/serial_uart.c b/src/main/drivers/serial_uart.c index fb5c5291e3..172719885e 100644 --- a/src/main/drivers/serial_uart.c +++ b/src/main/drivers/serial_uart.c @@ -42,7 +42,6 @@ #include "drivers/dma.h" #include "drivers/dma_reqmap.h" -#include "drivers/rcc.h" #include "drivers/serial.h" #include "drivers/serial_impl.h" #include "drivers/serial_uart.h" diff --git a/src/main/drivers/serial_uart_impl.h b/src/main/drivers/serial_uart_impl.h index 9a6304129c..988a2858b2 100644 --- a/src/main/drivers/serial_uart_impl.h +++ b/src/main/drivers/serial_uart_impl.h @@ -33,6 +33,10 @@ #include "platform.h" +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif + #ifndef UART_RX_BUFFER_SIZE #define UART_RX_BUFFER_SIZE 256 #endif diff --git a/src/main/drivers/serial_uart_pinconfig.c b/src/main/drivers/serial_uart_pinconfig.c index 8d9b348354..896f0dce95 100644 --- a/src/main/drivers/serial_uart_pinconfig.c +++ b/src/main/drivers/serial_uart_pinconfig.c @@ -36,7 +36,6 @@ #include "build/build_config.h" -#include "drivers/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" #include "drivers/serial_uart_impl.h" diff --git a/src/main/drivers/timer.h b/src/main/drivers/timer.h index 40bae0689c..13bfec69c5 100644 --- a/src/main/drivers/timer.h +++ b/src/main/drivers/timer.h @@ -25,7 +25,11 @@ #include "drivers/dma.h" #include "drivers/io_types.h" -#include "drivers/rcc_types.h" + +#if PLATFORM_TRAIT_RCC +#include "platform/rcc_types.h" +#endif + #include "drivers/resource.h" #ifdef USE_TIMER @@ -69,7 +73,9 @@ typedef struct timerOvrHandlerRec_s { typedef struct timerDef_s { TIM_TypeDef *TIMx; +#if PLATFORM_TRAIT_RCC rccPeriphTag_t rcc; +#endif uint8_t inputIrq; } timerDef_t; @@ -180,7 +186,9 @@ uint32_t timerClock(const TIM_TypeDef *tim); void configTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); // TODO - just for migration void timerReconfigureTimeBase(TIM_TypeDef *tim, uint16_t period, uint32_t hz); +#if PLATFORM_TRAIT_RCC rccPeriphTag_t timerRCC(const TIM_TypeDef *tim); +#endif uint8_t timerInputIrq(const TIM_TypeDef *tim); #if defined(USE_TIMER_MGMT) diff --git a/src/main/fc/core.c b/src/main/fc/core.c index cab68d4d30..4cdcc4ba77 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -558,18 +558,8 @@ void tryArm(void) } #endif // choose crashflip outcome on arming - // disarm can arise in processRx() if the crashflip switch is reversed while in crashflip mode - // if we were unsuccessful, or cannot determin success, arming will be blocked and we can't get here - // hence we only get here with crashFlipModeActive if the switch was reversed and result successful - if (crashFlipModeActive) { - // flip was successful, continue into normal flight without need to disarm/rearm - // note: preceding disarm will have set motors to normal rotation direction - crashFlipModeActive = false; - } else { - // when arming and not in crashflip mode, block entry to crashflip if delayed by the dshot beeper, - // otherwise consider only the switch position - crashFlipModeActive = (tryingToArm == ARMING_DELAYED_CRASHFLIP) ? false : IS_RC_MODE_ACTIVE(BOXCRASHFLIP); - } + // consider only the switch position + crashFlipModeActive = IS_RC_MODE_ACTIVE(BOXCRASHFLIP); setMotorSpinDirection(crashFlipModeActive ? DSHOT_CMD_SPIN_DIRECTION_REVERSED : DSHOT_CMD_SPIN_DIRECTION_NORMAL); } diff --git a/src/main/fc/init.c b/src/main/fc/init.c index d48b5d6128..c156a4d0a6 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -624,11 +624,14 @@ void init(void) #endif #ifdef USE_I2C - i2cHardwareConfigure(i2cConfig(0)); + i2cPinConfigure(i2cConfig(0)); // Note: Unlike UARTs which are configured when client is present, // I2C buses are initialized unconditionally if they are configured. +#ifdef USE_I2C_DEVICE_0 + i2cInit(I2CDEV_0); +#endif #ifdef USE_I2C_DEVICE_1 i2cInit(I2CDEV_1); #endif diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index cf261669b6..91a5cb0fba 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -255,6 +255,7 @@ static void mspEscPassthroughFn(serialPort_t *serialPort) } #endif +#ifdef USE_SERIAL_PASSTHROUGH static serialPort_t *mspFindPassthroughSerialPort(void) { serialPortUsage_t *portUsage = NULL; @@ -284,9 +285,13 @@ static void mspSerialPassthroughFn(serialPort_t *serialPort) serialPassthrough(passthroughPort, serialPort, NULL, NULL); } } +#endif static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) { +#ifndef USE_SERIAL_PASSTHROUGH + UNUSED(mspPostProcessFn); +#endif const unsigned int dataSize = sbufBytesRemaining(src); if (dataSize == 0) { // Legacy format @@ -297,6 +302,7 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF } switch (mspPassthroughMode) { +#ifdef USE_SERIAL_PASSTHROUGH case MSP_PASSTHROUGH_SERIAL_ID: case MSP_PASSTHROUGH_SERIAL_FUNCTION_ID: if (mspFindPassthroughSerialPort()) { @@ -308,6 +314,7 @@ static void mspFcSetPassthroughCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessF sbufWriteU8(dst, 0); } break; +#endif #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE case MSP_PASSTHROUGH_ESC_4WAY: // get channel number diff --git a/src/main/pg/bus_i2c.c b/src/main/pg/bus_i2c.c index 20ce63365d..3b83ac0a1a 100644 --- a/src/main/pg/bus_i2c.c +++ b/src/main/pg/bus_i2c.c @@ -41,6 +41,12 @@ PG_REGISTER_ARRAY_WITH_RESET_FN(i2cConfig_t, I2CDEV_COUNT, i2cConfig, PG_I2C_CONFIG, 1); +#ifndef I2C0_SCL_PIN +#define I2C0_SCL_PIN NONE +#endif +#ifndef I2C0_SDA_PIN +#define I2C0_SDA_PIN NONE +#endif #ifndef I2C1_SCL_PIN #define I2C1_SCL_PIN NONE #endif @@ -74,6 +80,9 @@ typedef struct i2cDefaultConfig_s { } i2cDefaultConfig_t; static const i2cDefaultConfig_t i2cDefaultConfig[] = { +#ifdef USE_I2C_DEVICE_0 + { I2CDEV_0, IO_TAG(I2C0_SCL_PIN), IO_TAG(I2C0_SDA_PIN), I2C0_PULLUP, I2C0_CLOCKSPEED }, +#endif #ifdef USE_I2C_DEVICE_1 { I2CDEV_1, IO_TAG(I2C1_SCL_PIN), IO_TAG(I2C1_SDA_PIN), I2C1_PULLUP, I2C1_CLOCKSPEED }, #endif diff --git a/src/main/pg/bus_i2c.h b/src/main/pg/bus_i2c.h index f460c48aa8..a8827f760f 100644 --- a/src/main/pg/bus_i2c.h +++ b/src/main/pg/bus_i2c.h @@ -22,7 +22,6 @@ #include "drivers/bus_i2c.h" #include "drivers/io_types.h" -#include "drivers/rcc_types.h" #include "pg/pg.h" diff --git a/src/main/platform.h b/src/main/platform.h index 4f0a0f9ed1..e7c3583fdc 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -33,7 +33,7 @@ #include "target/common_pre.h" // MCU specific platform from platform/X -#include "platform_mcu.h" +#include "platform/platform.h" #include "target.h" #include "target/common_post.h" diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index 2c4706b9ed..9464544642 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -53,6 +53,8 @@ typedef enum { ACC_IIM42653, ACC_ICM45605, ACC_ICM45686, + ACC_ICM40609D, + ACC_IIM42652, ACC_VIRTUAL } accelerationSensor_e; diff --git a/src/main/sensors/acceleration_init.c b/src/main/sensors/acceleration_init.c index 0d59e46858..46a9943379 100644 --- a/src/main/sensors/acceleration_init.c +++ b/src/main/sensors/acceleration_init.c @@ -48,6 +48,7 @@ #include "drivers/accgyro/accgyro_spi_icm20689.h" #include "drivers/accgyro/accgyro_spi_icm426xx.h" #include "drivers/accgyro/accgyro_spi_icm456xx.h" +#include "drivers/accgyro/accgyro_spi_icm40609.h" #include "drivers/accgyro/accgyro_spi_lsm6dso.h" #include "drivers/accgyro/accgyro_spi_lsm6dsv16x.h" @@ -217,9 +218,10 @@ retry: FALLTHROUGH; #endif -#if defined(USE_ACC_SPI_ICM42605) || defined(USE_ACC_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42653) +#if defined(USE_ACC_SPI_ICM42605) || defined(USE_ACC_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42652) || defined(USE_ACCGYRO_IIM42653) case ACC_ICM42605: case ACC_ICM42688P: + case ACC_IIM42652: case ACC_IIM42653: if (icm426xxSpiAccDetect(dev)) { switch (dev->mpuDetectionResult.sensor) { @@ -229,6 +231,9 @@ retry: case ICM_42688P_SPI: accHardware = ACC_ICM42688P; break; + case IIM_42652_SPI: + accHardware = ACC_IIM42652; + break; case IIM_42653_SPI: accHardware = ACC_IIM42653; break; @@ -297,6 +302,15 @@ retry: FALLTHROUGH; #endif +#ifdef USE_ACCGYRO_ICM40609D + case ACC_ICM40609D: + if (icm40609SpiAccDetect(dev)) { + accHardware = ACC_ICM40609D; + break; + } + FALLTHROUGH; +#endif + #ifdef USE_VIRTUAL_ACC case ACC_VIRTUAL: if (virtualAccDetect(dev)) { diff --git a/src/main/sensors/gyro_init.c b/src/main/sensors/gyro_init.c index 568386e560..7a2de5f353 100644 --- a/src/main/sensors/gyro_init.c +++ b/src/main/sensors/gyro_init.c @@ -48,6 +48,7 @@ #include "drivers/accgyro/accgyro_spi_icm20689.h" #include "drivers/accgyro/accgyro_spi_icm426xx.h" #include "drivers/accgyro/accgyro_spi_icm456xx.h" +#include "drivers/accgyro/accgyro_spi_icm40609.h" #include "drivers/accgyro/accgyro_spi_l3gd20.h" #include "drivers/accgyro/accgyro_spi_lsm6dso.h" @@ -317,6 +318,7 @@ void gyroInitSensor(gyroSensor_t *gyroSensor, const gyroDeviceConfig_t *config) case GYRO_LSM6DSO: case GYRO_LSM6DSV16X: case GYRO_ICM42688P: + case GYRO_IIM42652: case GYRO_IIM42653: case GYRO_ICM42605: case GYRO_ICM45686: @@ -433,9 +435,10 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev) FALLTHROUGH; #endif -#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42653) +#if defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_IIM42652) || defined(USE_ACCGYRO_IIM42653) case GYRO_ICM42605: case GYRO_ICM42688P: + case GYRO_IIM42652: case GYRO_IIM42653: if (icm426xxSpiGyroDetect(dev)) { switch (dev->mpuDetectionResult.sensor) { @@ -445,6 +448,9 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev) case ICM_42688P_SPI: gyroHardware = GYRO_ICM42688P; break; + case IIM_42652_SPI: + gyroHardware = GYRO_IIM42652; + break; case IIM_42653_SPI: gyroHardware = GYRO_IIM42653; break; @@ -514,6 +520,16 @@ STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev) FALLTHROUGH; #endif + +#ifdef USE_ACCGYRO_ICM40609D + case GYRO_ICM40609D: + if (icm40609SpiGyroDetect(dev)) { + gyroHardware = GYRO_ICM40609D; + break; + } + FALLTHROUGH; +#endif + #ifdef USE_VIRTUAL_GYRO case GYRO_VIRTUAL: if (virtualGyroDetect(dev)) { 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/main/target/common_defaults_post.h b/src/main/target/common_defaults_post.h index e8b06bdf41..af162d6b5e 100644 --- a/src/main/target/common_defaults_post.h +++ b/src/main/target/common_defaults_post.h @@ -24,6 +24,9 @@ #define DEBUG_MODE DEBUG_NONE #endif +#ifndef I2C0_CLOCKSPEED +#define I2C0_CLOCKSPEED 800 +#endif #ifndef I2C1_CLOCKSPEED #define I2C1_CLOCKSPEED 800 #endif @@ -40,11 +43,13 @@ // Default values for internal pullup #if defined(USE_I2C_PULLUP) +#define I2C0_PULLUP true #define I2C1_PULLUP true #define I2C2_PULLUP true #define I2C3_PULLUP true #define I2C4_PULLUP true #else +#define I2C0_PULLUP false #define I2C1_PULLUP false #define I2C2_PULLUP false #define I2C3_PULLUP false diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 6a732310cf..ad68eee069 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -39,6 +39,10 @@ */ +#ifndef PLATFORM_NO_LIBC +#define PLATFORM_NO_LIBC 1 +#endif + #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) #define DEFAULT_AUX_CHANNEL_COUNT MAX_AUX_CHANNEL_COUNT #else @@ -101,6 +105,7 @@ && !defined(USE_ACC_SPI_ICM20649) \ && !defined(USE_ACC_SPI_ICM20689) \ && !defined(USE_ACC_SPI_ICM42605) \ + && !defined(USE_ACCGYRO_ICM40609D) \ && !defined(USE_ACC_SPI_ICM42688P) \ && !defined(USE_ACCGYRO_ICM45686) \ && !defined(USE_ACCGYRO_ICM45605) \ @@ -109,8 +114,9 @@ && !defined(USE_ACC_SPI_MPU6000) \ && !defined(USE_ACC_SPI_MPU6500) \ && !defined(USE_ACC_SPI_MPU9250) \ - && !defined(USE_VIRTUAL_ACC) \ - && !defined(USE_ACCGYRO_IIM42653) + && !defined(USE_ACCGYRO_IIM42652) \ + && !defined(USE_ACCGYRO_IIM42653) \ + && !defined(USE_VIRTUAL_ACC) #error At least one USE_ACC device definition required #endif @@ -126,13 +132,15 @@ && !defined(USE_GYRO_SPI_ICM42688P) \ && !defined(USE_ACCGYRO_ICM45686) \ && !defined(USE_ACCGYRO_ICM45605) \ + && !defined(USE_ACCGYRO_ICM40609D) \ && !defined(USE_ACCGYRO_LSM6DSO) \ && !defined(USE_ACCGYRO_LSM6DSV16X) \ && !defined(USE_GYRO_SPI_MPU6000) \ && !defined(USE_GYRO_SPI_MPU6500) \ && !defined(USE_GYRO_SPI_MPU9250) \ - && !defined(USE_VIRTUAL_GYRO) \ - && !defined(USE_ACCGYRO_IIM42653) + && !defined(USE_ACCGYRO_IIM42652) \ + && !defined(USE_ACCGYRO_IIM42653) \ + && !defined(USE_VIRTUAL_GYRO) #error At least one USE_GYRO device definition required #endif @@ -470,11 +478,11 @@ #define USE_GYRO_SPI_MPU6500 #endif -// Generate USE_SPI_GYRO or USE_I2C_GYRO +// Generate USE_SPI_GYRO #if defined(USE_GYRO_SPI_ICM20689) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU9250) \ || defined(USE_GYRO_L3GD20) || defined(USE_GYRO_SPI_ICM42605) || defined(USE_GYRO_SPI_ICM42688P) || defined(USE_ACCGYRO_ICM45686) \ || defined(USE_ACCGYRO_ICM45605) || defined(USE_ACCGYRO_IIM42653) || defined(USE_ACCGYRO_BMI160) || defined(USE_ACCGYRO_BMI270) \ - || defined(USE_ACCGYRO_LSM6DSV16X) || defined(USE_ACCGYRO_LSM6DSO) + || defined(USE_ACCGYRO_LSM6DSV16X) || defined(USE_ACCGYRO_LSM6DSO) || defined(USE_ACCGYRO_ICM40609D) || defined(USE_ACCGYRO_IIM42652) #ifndef USE_SPI_GYRO #define USE_SPI_GYRO #endif @@ -596,7 +604,7 @@ #endif #endif // USE_OPTICALFLOW_MT -#if defined(USE_RANGEFINDER_HCSR04) || defined(USE_RANGEFINDER_SRF10) || defined(USE_RANGEFINDER_HCSR04_I2C) || defined(USE_RANGEFINDER_VL53L0X) || defined(USE_RANGEFINDER_UIB) || defined(USE_RANGEFINDER_TF) || defined(USE_RANGEFINDER_MT) +#if defined(USE_RANGEFINDER_HCSR04) || defined(USE_RANGEFINDER_TF) || defined(USE_RANGEFINDER_MT) #ifndef USE_RANGEFINDER #define USE_RANGEFINDER #endif diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index d43b30aaaf..ed96a9f48f 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -116,10 +116,12 @@ #define USE_GYRO_SPI_ICM42688P #define USE_ACCGYRO_ICM45686 #define USE_ACCGYRO_ICM45605 +#define USE_ACCGYRO_IIM42652 #define USE_ACCGYRO_IIM42653 #define USE_ACC_SPI_ICM42605 #define USE_ACC_SPI_ICM42688P #define USE_ACCGYRO_LSM6DSV16X +#define USE_ACCGYRO_ICM40609D #if TARGET_FLASH_SIZE > 512 #define USE_ACC_MPU6050 diff --git a/src/platform/APM32/adc_apm32f4xx.c b/src/platform/APM32/adc_apm32f4xx.c index 2b93c1eba6..38004b23be 100644 --- a/src/platform/APM32/adc_apm32f4xx.c +++ b/src/platform/APM32/adc_apm32f4xx.c @@ -32,7 +32,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/dma.h" #include "drivers/sensor.h" #include "drivers/adc.h" @@ -270,8 +270,7 @@ void adcInit(const adcConfig_t *config) adcInitDevice(&adcInternal, 2); DDL_ADC_Enable(adcInternal.ADCx); adcInitInternalInjected(&adcInternal); - } - else { + } else { // Initialize for injected conversion adcInitInternalInjected(&adc); } diff --git a/src/platform/APM32/apm32f4xx_ddl_ex.h b/src/platform/APM32/apm32f4xx_ddl_ex.h index 187448df8d..30d53da2ac 100644 --- a/src/platform/APM32/apm32f4xx_ddl_ex.h +++ b/src/platform/APM32/apm32f4xx_ddl_ex.h @@ -31,10 +31,12 @@ __STATIC_INLINE void DDL_EX_TMR_DisableIT(TMR_TypeDef *TMRx, uint32_t Sources) { CLEAR_BIT(TMRx->DIEN, Sources); } + __STATIC_INLINE void DDL_EX_TMR_EnableIT(TMR_TypeDef *TMRx, uint32_t Sources) { SET_BIT(TMRx->DIEN, Sources); } + __STATIC_INLINE uint32_t DDL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_Streamy) { STATIC_ASSERT(DMA1_Stream0_BASE - DMA1_BASE == sizeof(DMA_TypeDef), DMA_TypeDef_has_padding); @@ -45,11 +47,13 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_Stream_to_Stream(DMA_Stream_TypeDef *DMAx_St return (((uint32_t) DMAx_Streamy & 0XFF) - firstStreamOffset) / streamSize; } + __STATIC_INLINE DMA_TypeDef *DDL_EX_DMA_Stream_to_DMA(DMA_Stream_TypeDef *DMAx_Streamy) { // clear stream address return (DMA_TypeDef *) (((uint32_t) DMAx_Streamy) & ((uint32_t) ~0XFF)); } + __STATIC_INLINE uint32_t DDL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) { DMA_TypeDef *DMA = DDL_EX_DMA_Stream_to_DMA(DMAx_Streamy); @@ -57,6 +61,7 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_DeInit(DMA_Stream_TypeDef *DMAx_Streamy) return DDL_DMA_DeInit(DMA, Stream); } + __STATIC_INLINE uint32_t DDL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, DDL_DMA_InitTypeDef *DMA_InitStruct) { DMA_TypeDef *DMA = DDL_EX_DMA_Stream_to_DMA(DMAx_Streamy); @@ -64,6 +69,7 @@ __STATIC_INLINE uint32_t DDL_EX_DMA_Init(DMA_Stream_TypeDef *DMAx_Streamy, DDL_D return DDL_DMA_Init(DMA, Stream, DMA_InitStruct); } + __STATIC_INLINE void DDL_EX_DMA_SetDataLength(DMA_Stream_TypeDef* DMAx_Streamy, uint32_t NbData) { MODIFY_REG(DMAx_Streamy->NDATA, DMA_NDATAx, NbData); @@ -81,6 +87,7 @@ __STATIC_INLINE void DDL_EX_DMA_EnableResource(DMA_Stream_TypeDef *DMAx_Streamy) { SET_BIT(DMAx_Streamy->SCFG, DMA_SCFGx_EN); } + __STATIC_INLINE void DDL_EX_DMA_DisableResource(DMA_Stream_TypeDef *DMAx_Streamy) { CLEAR_BIT(DMAx_Streamy->SCFG, DMA_SCFGx_EN); @@ -94,4 +101,4 @@ __STATIC_INLINE void DDL_EX_DMA_EnableIT_TC(DMA_Stream_TypeDef *DMAx_Streamy) __STATIC_INLINE void DDL_EX_TMR_CC_EnableNChannel(TMR_TypeDef *TMRx, uint32_t Channel) { DDL_TMR_CC_EnableChannel(TMRx, 4 * Channel); -} \ No newline at end of file +} diff --git a/src/platform/APM32/bus_i2c_apm32.c b/src/platform/APM32/bus_i2c_apm32.c index 12eb1d803a..147e5e986a 100644 --- a/src/platform/APM32/bus_i2c_apm32.c +++ b/src/platform/APM32/bus_i2c_apm32.c @@ -31,7 +31,7 @@ #include "drivers/io_impl.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" @@ -76,7 +76,7 @@ static volatile uint16_t i2cErrorCount = 0; static bool i2cHandleHardwareFailure(I2CDevice device) { - (void)device; + UNUSED(device); i2cErrorCount++; // reinit peripheral + clock out garbage //i2cInit(device); @@ -103,13 +103,15 @@ bool i2cWrite(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t data) HAL_StatusTypeDef status; - if (reg_ == 0xFF) + if (reg_ == 0xFF) { status = DAL_I2C_Master_Transmit(pHandle ,addr_ << 1, &data, 1, I2C_TIMEOUT_SYS_TICKS); - else + } else { status = DAL_I2C_Mem_Write(pHandle ,addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT, &data, 1, I2C_TIMEOUT_SYS_TICKS); + } - if (status != DAL_OK) + if (status != DAL_OK) { return i2cHandleHardwareFailure(device); + } return true; } @@ -135,8 +137,7 @@ bool i2cWriteBuffer(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len_, return false; } - if (status != DAL_OK) - { + if (status != DAL_OK) { return i2cHandleHardwareFailure(device); } @@ -158,10 +159,11 @@ bool i2cRead(I2CDevice device, uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t DAL_StatusTypeDef status; - if (reg_ == 0xFF) + if (reg_ == 0xFF) { status = DAL_I2C_Master_Receive(pHandle ,addr_ << 1, buf, len, I2C_TIMEOUT_SYS_TICKS); - else + } else { status = DAL_I2C_Mem_Read(pHandle, addr_ << 1, reg_, I2C_MEMADD_SIZE_8BIT,buf, len, I2C_TIMEOUT_SYS_TICKS); + } if (status != DAL_OK) { return i2cHandleHardwareFailure(device); @@ -206,8 +208,7 @@ bool i2cBusy(I2CDevice device, bool *error) *error = pHandle->ErrorCode; } - if (pHandle->State == DAL_I2C_STATE_READY) - { + if (pHandle->State == DAL_I2C_STATE_READY) { if (__DAL_I2C_GET_FLAG(pHandle, I2C_FLAG_BUSY) == SET) { return true; @@ -218,5 +219,4 @@ bool i2cBusy(I2CDevice device, bool *error) return true; } - #endif diff --git a/src/platform/APM32/bus_i2c_apm32_init.c b/src/platform/APM32/bus_i2c_apm32_init.c index 12dd1227d8..45fe92bfaa 100644 --- a/src/platform/APM32/bus_i2c_apm32_init.c +++ b/src/platform/APM32/bus_i2c_apm32_init.c @@ -30,7 +30,7 @@ #include "drivers/io.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/APM32/bus_spi_apm32.c b/src/platform/APM32/bus_spi_apm32.c index 6b15adf29d..6c58c5e8da 100644 --- a/src/platform/APM32/bus_spi_apm32.c +++ b/src/platform/APM32/bus_spi_apm32.c @@ -35,7 +35,7 @@ #include "drivers/bus_spi_impl.h" #include "drivers/dma.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" // Use DMA if possible if this many bytes are to be transferred #define SPI_DMA_THRESHOLD 8 @@ -347,8 +347,7 @@ FAST_CODE void spiSequenceStart(const extDevice_t *dev) IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_LOW, spi->sckAF); DDL_SPI_SetClockPhase(instance, DDL_SPI_PHASE_1EDGE); DDL_SPI_SetClockPolarity(instance, DDL_SPI_POLARITY_LOW); - } - else { + } else { IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_SCK_CFG_HIGH, spi->sckAF); DDL_SPI_SetClockPhase(instance, DDL_SPI_PHASE_2EDGE); DDL_SPI_SetClockPolarity(instance, DDL_SPI_POLARITY_HIGH); diff --git a/src/platform/APM32/dma_apm32f4xx.c b/src/platform/APM32/dma_apm32f4xx.c index 3c571a75e5..403f592fa4 100644 --- a/src/platform/APM32/dma_apm32f4xx.c +++ b/src/platform/APM32/dma_apm32f4xx.c @@ -29,7 +29,7 @@ #include "drivers/nvic.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" /* diff --git a/src/platform/APM32/dshot_bitbang.c b/src/platform/APM32/dshot_bitbang.c index cf971adf97..caec5e0bec 100644 --- a/src/platform/APM32/dshot_bitbang.c +++ b/src/platform/APM32/dshot_bitbang.c @@ -450,14 +450,15 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorProtocolTypes_e pwmP bbGpioSetup(&bbMotors[motorIndex]); + do { #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_INVERTED); - } else -#endif - { - bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED); + break; } +#endif + bbOutputDataInit(bbPort->portOutputBuffer, (1 << pinIndex), DSHOT_BITBANG_NONINVERTED); + } while (false); bbSwitchToOutput(bbPort); @@ -577,14 +578,15 @@ static void bbWriteInt(uint8_t motorIndex, uint16_t value) bbPort_t *bbPort = bbmotor->bbPort; + do { #ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED); - } else + if (useDshotTelemetry) { + bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_INVERTED); + break; + } #endif - { bbOutputDataSet(bbPort->portOutputBuffer, bbmotor->pinIndex, packet, DSHOT_BITBANG_NONINVERTED); - } + } while (false); } static void bbWrite(uint8_t motorIndex, float value) @@ -614,11 +616,8 @@ static void bbUpdateComplete(void) bbPort->inputActive = false; bbSwitchToOutput(bbPort); } - } else -#endif - { - // Nothing to do } +#endif bbDMA_Cmd(bbPort, ENABLE); } diff --git a/src/platform/APM32/dshot_bitbang_ddl.c b/src/platform/APM32/dshot_bitbang_ddl.c index dc7301c491..6e2eeff13b 100644 --- a/src/platform/APM32/dshot_bitbang_ddl.c +++ b/src/platform/APM32/dshot_bitbang_ddl.c @@ -56,23 +56,12 @@ void bbGpioSetup(bbMotor_t *bbMotor) bbPort->gpioModeInput |= (DDL_GPIO_MODE_INPUT << (pinIndex * 2)); bbPort->gpioModeOutput |= (DDL_GPIO_MODE_OUTPUT << (pinIndex * 2)); + bool inverted = false; #ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - bbPort->gpioIdleBSRR |= (1 << pinIndex); // BS (lower half) - } else + inverted = true; #endif - { - bbPort->gpioIdleBSRR |= (1 << (pinIndex + 16)); // BR (higher half) - } - -#ifdef USE_DSHOT_TELEMETRY - if (useDshotTelemetry) { - IOWrite(bbMotor->io, 1); - } else -#endif - { - IOWrite(bbMotor->io, 0); - } + bbPort->gpioIdleBSRR |= (1 << pinIndex) + (inverted ? 0 : 16); // write BITSET or BITRESET half of BSRR + IOWrite(bbMotor->io, inverted); } void bbTimerChannelInit(bbPort_t *bbPort) diff --git a/src/platform/APM32/platform_mcu.h b/src/platform/APM32/include/platform/platform.h similarity index 98% rename from src/platform/APM32/platform_mcu.h rename to src/platform/APM32/include/platform/platform.h index 10299b6d5c..368440773c 100644 --- a/src/platform/APM32/platform_mcu.h +++ b/src/platform/APM32/include/platform/platform.h @@ -104,8 +104,6 @@ #define U_ID_1 (*(uint32_t*)0x1fff7a14) #define U_ID_2 (*(uint32_t*)0x1fff7a18) -#define USE_PIN_AF - #ifndef APM32F4 #define APM32F4 #endif @@ -193,6 +191,11 @@ #define PLATFORM_TRAIT_RCC 1 #define UART_TRAIT_AF_PORT 1 #define SERIAL_TRAIT_PIN_CONFIG 1 +#define I2C_TRAIT_AF_PIN 1 +#define I2CDEV_COUNT 3 +#define I2C_TRAIT_HANDLE 1 + +#define SPI_TRAIT_AF_PIN 1 #define UARTHARDWARE_MAX_PINS 4 diff --git a/src/platform/APM32/io_apm32.c b/src/platform/APM32/io_apm32.c index d744117646..482a6b8fd8 100644 --- a/src/platform/APM32/io_apm32.c +++ b/src/platform/APM32/io_apm32.c @@ -23,7 +23,7 @@ #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "common/utils.h" diff --git a/src/platform/APM32/light_ws2811strip_apm32.c b/src/platform/APM32/light_ws2811strip_apm32.c index 2ef5cbcb30..c2cafd8ba7 100644 --- a/src/platform/APM32/light_ws2811strip_apm32.c +++ b/src/platform/APM32/light_ws2811strip_apm32.c @@ -32,7 +32,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/system.h" #include "drivers/timer.h" diff --git a/src/platform/APM32/mk/APM32F4.mk b/src/platform/APM32/mk/APM32F4.mk index c0b9a27c91..8bdb4b6cf7 100644 --- a/src/platform/APM32/mk/APM32F4.mk +++ b/src/platform/APM32/mk/APM32F4.mk @@ -179,8 +179,8 @@ MCU_COMMON_SRC = \ APM32/dma_apm32f4xx.c \ APM32/serial_uart_apm32f4xx.c \ drivers/adc.c \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/bus_spi_hw.c \ common/stm32/bus_spi_pinconfig.c \ common/stm32/serial_uart_hw.c \ @@ -217,8 +217,8 @@ SPEED_OPTIMISED_SRC += \ SIZE_OPTIMISED_SRC += \ APM32/usb/vcp/serial_usb_vcp.c \ drivers/inverter.c \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ diff --git a/src/platform/APM32/pwm_output_dshot_apm32.c b/src/platform/APM32/pwm_output_dshot_apm32.c index 499897394f..57010f08e8 100644 --- a/src/platform/APM32/pwm_output_dshot_apm32.c +++ b/src/platform/APM32/pwm_output_dshot_apm32.c @@ -41,7 +41,7 @@ #include "drivers/motor.h" #include "drivers/pwm_output.h" #include "pwm_output_dshot_shared.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/time.h" #include "drivers/timer.h" #include "drivers/system.h" @@ -133,18 +133,19 @@ FAST_CODE void pwmCompleteDshotMotorUpdate(void) } for (int i = 0; i < dmaMotorTimerCount; i++) { + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - xDDL_EX_DMA_SetDataLength(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength); - xDDL_EX_DMA_EnableResource(dmaMotorTimers[i].dmaBurstRef); + if (useBurstDshot) { + xDDL_EX_DMA_SetDataLength(dmaMotorTimers[i].dmaBurstRef, dmaMotorTimers[i].dmaBurstLength); + xDDL_EX_DMA_EnableResource(dmaMotorTimers[i].dmaBurstRef); - /* configure the DMA Burst Mode */ - DDL_TMR_ConfigDMABurst(dmaMotorTimers[i].timer, DDL_TMR_DMABURST_BASEADDR_CC1, DDL_TMR_DMABURST_LENGTH_4TRANSFERS); - /* Enable the TIM DMA Request */ - DDL_TMR_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer); - } else + /* configure the DMA Burst Mode */ + DDL_TMR_ConfigDMABurst(dmaMotorTimers[i].timer, DDL_TMR_DMABURST_BASEADDR_CC1, DDL_TMR_DMABURST_LENGTH_4TRANSFERS); + /* Enable the TIM DMA Request */ + DDL_TMR_EnableDMAReq_UPDATE(dmaMotorTimers[i].timer); + break; + } #endif - { DDL_TMR_DisableARRPreload(dmaMotorTimers[i].timer); dmaMotorTimers[i].timer->AUTORLD = dmaMotorTimers[i].outputPeriod; @@ -153,7 +154,7 @@ FAST_CODE void pwmCompleteDshotMotorUpdate(void) /* Enable channel DMA requests */ DDL_EX_TMR_EnableIT(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources); dmaMotorTimers[i].timerDmaSources = 0; - } + } while (false); } } @@ -164,16 +165,17 @@ FAST_CODE static void motor_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor) #ifdef USE_DSHOT_TELEMETRY dshotDMAHandlerCycleCounters.irqAt = getCycleCounter(); #endif + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - xDDL_EX_DMA_DisableResource(motor->timerHardware->dmaTimUPRef); - DDL_TMR_DisableDMAReq_UPDATE(motor->timerHardware->tim); - } else + if (useBurstDshot) { + xDDL_EX_DMA_DisableResource(motor->timerHardware->dmaTimUPRef); + DDL_TMR_DisableDMAReq_UPDATE(motor->timerHardware->tim); + break; + } #endif - { xDDL_EX_DMA_DisableResource(motor->dmaRef); DDL_EX_TMR_DisableIT(motor->timerHardware->tim, motor->timerDmaSource); - } + } while (false); #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { @@ -228,21 +230,22 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m dmaIdentifier_e dmaIdentifier = dmaGetIdentifier(dmaRef); bool dmaIsConfigured = false; + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - const resourceOwner_t *owner = dmaGetOwner(dmaIdentifier); - if (owner->owner == OWNER_TIMUP && owner->resourceIndex == timerGetTIMNumber(timerHardware->tim)) { - dmaIsConfigured = true; - } else if (!dmaAllocate(dmaIdentifier, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim))) { - return false; + if (useBurstDshot) { + const resourceOwner_t *owner = dmaGetOwner(dmaIdentifier); + if (owner->owner == OWNER_TIMUP && owner->resourceIndex == timerGetTIMNumber(timerHardware->tim)) { + dmaIsConfigured = true; + } else if (!dmaAllocate(dmaIdentifier, OWNER_TIMUP, timerGetTIMNumber(timerHardware->tim))) { + return false; + } + break; } - } else #endif - { if (!dmaAllocate(dmaIdentifier, OWNER_MOTOR, RESOURCE_INDEX(reorderedMotorIndex))) { return false; } - } + } while (false); motorDmaOutput_t * const motor = &dmaMotors[motorIndex]; motor->dmaRef = dmaRef; @@ -312,18 +315,19 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m } motor->llChannel = channel; + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - motor->timer->dmaBurstRef = dmaRef; + if (useBurstDshot) { + motor->timer->dmaBurstRef = dmaRef; #ifdef USE_DSHOT_TELEMETRY - motor->dmaRef = dmaRef; + motor->dmaRef = dmaRef; #endif - } else + break; + } #endif - { motor->timerDmaSource = timerDmaSource(timerHardware->channel); motor->timer->timerDmaSources &= ~motor->timerDmaSource; - } + } while (false); if (!dmaIsConfigured) { xDDL_EX_DMA_DisableResource(dmaRef); @@ -333,24 +337,25 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m } DDL_DMA_StructInit(&DMAINIT); + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0]; + if (useBurstDshot) { + motor->timer->dmaBurstBuffer = &dshotBurstDmaBuffer[timerIndex][0]; - DMAINIT.Channel = dmaChannel; - DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer; - DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_FULL; - DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR; - } else + DMAINIT.Channel = dmaChannel; + DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->timer->dmaBurstBuffer; + DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_FULL; + DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)&timerHardware->tim->DMAR; + break; + } #endif - { motor->dmaBuffer = &dshotDmaBuffer[motorIndex][0]; DMAINIT.Channel = dmaChannel; DMAINIT.MemoryOrM2MDstAddress = (uint32_t)motor->dmaBuffer; DMAINIT.FIFOThreshold = DDL_DMA_FIFOTHRESHOLD_1_4; DMAINIT.PeriphOrM2MSrcAddress = (uint32_t)timerChCCR(timerHardware); - } + } while (false); DMAINIT.Direction = DDL_DMA_DIRECTION_MEMORY_TO_PERIPH; DMAINIT.FIFOMode = DDL_DMA_FIFOMODE_ENABLE; @@ -380,16 +385,17 @@ bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t m pwmDshotSetDirectionOutput(motor, &OCINIT, &DMAINIT); #endif + do { #ifdef USE_DSHOT_DMAR - if (useBurstDshot) { - if (!dmaIsConfigured) { - dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); + if (useBurstDshot) { + if (!dmaIsConfigured) { + dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); + } + break; } - } else #endif - { dmaSetHandler(dmaIdentifier, motor_DMA_IRQHandler, NVIC_PRIO_DSHOT_DMA, motor->index); - } + } while (false); DDL_TMR_OC_Init(timer, channel, &OCINIT); DDL_TMR_OC_EnablePreload(timer, channel); diff --git a/src/platform/APM32/rcm_apm32.c b/src/platform/APM32/rcm_apm32.c index 96ecd59ac5..160dbfd723 100644 --- a/src/platform/APM32/rcm_apm32.c +++ b/src/platform/APM32/rcm_apm32.c @@ -20,7 +20,7 @@ */ #include "platform.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) { diff --git a/src/platform/APM32/serial_uart_apm32.c b/src/platform/APM32/serial_uart_apm32.c index e676ca2f93..64ac4a3da3 100644 --- a/src/platform/APM32/serial_uart_apm32.c +++ b/src/platform/APM32/serial_uart_apm32.c @@ -39,7 +39,7 @@ #include "common/utils.h" #include "drivers/inverter.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" @@ -82,35 +82,37 @@ void uartReconfigure(uartPort_t *uartPort) // Receive DMA or IRQ if (uartPort->port.mode & MODE_RX) { + do { #ifdef USE_DMA - if (uartPort->rxDMAResource) { - uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource; - uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel; - uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; - uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; - uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE; - uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; - uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR; + if (uartPort->rxDMAResource) { + uartPort->rxDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->rxDMAResource; + uartPort->txDMAHandle.Init.Channel = uartPort->rxDMAChannel; + uartPort->rxDMAHandle.Init.Direction = DMA_PERIPH_TO_MEMORY; + uartPort->rxDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; + uartPort->rxDMAHandle.Init.MemInc = DMA_MINC_ENABLE; + uartPort->rxDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + uartPort->rxDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + uartPort->rxDMAHandle.Init.Mode = DMA_CIRCULAR; #if defined(APM32F4) - uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; - uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; - uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; + uartPort->rxDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + uartPort->rxDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; + uartPort->rxDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; + uartPort->rxDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; #endif - uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; + uartPort->rxDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->rxDMAHandle); - DAL_DMA_Init(&uartPort->rxDMAHandle); - /* Associate the initialized DMA handle to the UART handle */ - __DAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle); + DAL_DMA_DeInit(&uartPort->rxDMAHandle); + DAL_DMA_Init(&uartPort->rxDMAHandle); + /* Associate the initialized DMA handle to the UART handle */ + __DAL_LINKDMA(&uartPort->Handle, hdmarx, uartPort->rxDMAHandle); - DAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize); + DAL_UART_Receive_DMA(&uartPort->Handle, (uint8_t*)uartPort->port.rxBuffer, uartPort->port.rxBufferSize); - uartPort->rxDMAPos = __DAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle); - } else + uartPort->rxDMAPos = __DAL_DMA_GET_COUNTER(&uartPort->rxDMAHandle); + break; + } #endif - { + /* Enable the UART Parity Error Interrupt */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_PEIEN); @@ -122,44 +124,44 @@ void uartReconfigure(uartPort_t *uartPort) /* Enable Idle Line detection */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_IDLEIEN); - } + } while(false); } // Transmit DMA or IRQ if (uartPort->port.mode & MODE_TX) { + do { #ifdef USE_DMA - if (uartPort->txDMAResource) { - uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource; - uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel; - uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH; - uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; - uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE; - uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; - uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; - uartPort->txDMAHandle.Init.Mode = DMA_NORMAL; - uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; - uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; - uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; - uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; - uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; + if (uartPort->txDMAResource) { + uartPort->txDMAHandle.Instance = (DMA_ARCH_TYPE *)uartPort->txDMAResource; + uartPort->txDMAHandle.Init.Channel = uartPort->txDMAChannel; + uartPort->txDMAHandle.Init.Direction = DMA_MEMORY_TO_PERIPH; + uartPort->txDMAHandle.Init.PeriphInc = DMA_PINC_DISABLE; + uartPort->txDMAHandle.Init.MemInc = DMA_MINC_ENABLE; + uartPort->txDMAHandle.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE; + uartPort->txDMAHandle.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE; + uartPort->txDMAHandle.Init.Mode = DMA_NORMAL; + uartPort->txDMAHandle.Init.FIFOMode = DMA_FIFOMODE_DISABLE; + uartPort->txDMAHandle.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL; + uartPort->txDMAHandle.Init.PeriphBurst = DMA_PBURST_SINGLE; + uartPort->txDMAHandle.Init.MemBurst = DMA_MBURST_SINGLE; + uartPort->txDMAHandle.Init.Priority = DMA_PRIORITY_MEDIUM; - DAL_DMA_DeInit(&uartPort->txDMAHandle); - DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle); - if (status != DAL_OK) { - while (1); + DAL_DMA_DeInit(&uartPort->txDMAHandle); + DAL_StatusTypeDef status = DAL_DMA_Init(&uartPort->txDMAHandle); + if (status != DAL_OK) { + while (1); + } + /* Associate the initialized DMA handle to the UART handle */ + __DAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle); + + __DAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0); + break; } - /* Associate the initialized DMA handle to the UART handle */ - __DAL_LINKDMA(&uartPort->Handle, hdmatx, uartPort->txDMAHandle); - - __DAL_DMA_SET_COUNTER(&uartPort->txDMAHandle, 0); - } else #endif - { - /* Enable the UART Transmit Data Register Empty Interrupt */ SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXBEIEN); SET_BIT(uartPort->USARTx->CTRL1, USART_CTRL1_TXCIEN); - } + } while(false); } } diff --git a/src/platform/APM32/serial_uart_apm32f4xx.c b/src/platform/APM32/serial_uart_apm32f4xx.c index 2c5151b62f..2df52a9ffd 100644 --- a/src/platform/APM32/serial_uart_apm32f4xx.c +++ b/src/platform/APM32/serial_uart_apm32f4xx.c @@ -36,7 +36,7 @@ #include "drivers/io.h" #include "drivers/dma.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" @@ -269,10 +269,12 @@ void uartDmaIrqHandler(dmaChannelDescriptor_t* descriptor) } handleUsartTxDma(s); } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF)) { DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF); } + if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF)) { DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF); diff --git a/src/platform/APM32/system_apm32f4xx.c b/src/platform/APM32/system_apm32f4xx.c index 0bf5b42231..75945bd924 100644 --- a/src/platform/APM32/system_apm32f4xx.c +++ b/src/platform/APM32/system_apm32f4xx.c @@ -121,10 +121,11 @@ void enableGPIOPowerUsageAndNoiseReductions(void) bool isMPUSoftReset(void) { - if (cachedRccCsrValue & RCM_CSTS_SWRSTFLG) + if (cachedRccCsrValue & RCM_CSTS_SWRSTFLG) { return true; - else + } else { return false; + } } void systemInit(void) diff --git a/src/platform/APM32/timer_apm32.c b/src/platform/APM32/timer_apm32.c index 12ef8f197b..710ebc509a 100644 --- a/src/platform/APM32/timer_apm32.c +++ b/src/platform/APM32/timer_apm32.c @@ -37,7 +37,7 @@ #include "drivers/io.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/timer_impl.h" @@ -340,7 +340,9 @@ TMR_HandleTypeDef* timerFindTimerHandle(TMR_TypeDef *tim) void timerReconfigureTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } handle->Init.Period = (period - 1) & 0xffff; // AKA TIMx_ARR handle->Init.Prescaler = (timerClock(tim) / hz) - 1; @@ -351,7 +353,9 @@ void timerReconfigureTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) void configTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } if (handle->Instance == tim) { // already configured @@ -368,8 +372,7 @@ void configTimeBase(TMR_TypeDef *tim, uint16_t period, uint32_t hz) handle->Init.RepetitionCounter = 0x0000; DAL_TMR_Base_Init(handle); - if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9) - { + if (tim == TMR1 || tim == TMR2 || tim == TMR3 || tim == TMR4 || tim == TMR5 || tim == TMR8 || tim == TMR9) { TMR_ClockConfigTypeDef sClockSourceConfig; memset(&sClockSourceConfig, 0, sizeof(sClockSourceConfig)); sClockSourceConfig.ClockSource = TMR_CLOCKSOURCE_INTERNAL; @@ -402,7 +405,6 @@ void timerConfigure(const timerHardware_t *timerHardwarePtr, uint16_t period, ui timerNVICConfigure(irq); // HACK - enable second IRQ on timers that need it switch (irq) { - case TMR1_CC_IRQn: timerNVICConfigure(TMR1_UP_TMR10_IRQn); break; @@ -421,13 +423,16 @@ void timerChInit(const timerHardware_t *timHw, channelType_t type, int irqPriori return; } unsigned channel = timHw - TIMER_HARDWARE; - if (channel >= TIMER_CHANNEL_COUNT) + if (channel >= TIMER_CHANNEL_COUNT) { return; + } timerChannelInfo[channel].type = type; unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } + if (irqPriority < timerInfo[timer].priority) { // it would be better to set priority in the end, but current startup sequence is not ready configTimeBase(usedTimers[timer], 0, 1); @@ -476,10 +481,11 @@ static void timerChConfig_UpdateOverflow(timerConfig_t *cfg, const TMR_TypeDef * *chain = NULL; } // enable or disable IRQ - if (cfg->overflowCallbackActive) + if (cfg->overflowCallbackActive) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TMR_IT_UPDATE); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TMR_IT_UPDATE); + } } // config edge and overflow callback for channel. Try to avoid overflowCallback, it is a bit expensive @@ -490,14 +496,17 @@ void timerChConfigCallbacks(const timerHardware_t *timHw, timerCCHandlerRec_t *e return; } uint8_t channelIndex = lookupChannelIndex(timHw->channel); - if (edgeCallback == NULL) // disable irq before changing callback to NULL + if (edgeCallback == NULL) { // disable irq before changing callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } + // setup callback info timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallback; timerConfig[timerIndex].overflowCallback[channelIndex] = overflowCallback; // enable channel IRQ - if (edgeCallback) + if (edgeCallback) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } timerChConfig_UpdateOverflow(&timerConfig[timerIndex], timHw->tim); } @@ -525,10 +534,13 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_ uint16_t chHi = timHw->channel | TMR_CHANNEL_2; // upper channel uint8_t channelIndex = lookupChannelIndex(chLo); // get index of lower channel - if (edgeCallbackLo == NULL) // disable irq before changing setting callback to NULL + if (edgeCallbackLo == NULL) { // disable irq before changing setting callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); - if (edgeCallbackHi == NULL) // disable irq before changing setting callback to NULL + } + + if (edgeCallbackHi == NULL) { // disable irq before changing setting callback to NULL __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); + } // setup callback info timerConfig[timerIndex].edgeCallback[channelIndex] = edgeCallbackLo; @@ -541,6 +553,7 @@ void timerChConfigCallbacksDual(const timerHardware_t *timHw, timerCCHandlerRec_ __DAL_TMR_CLEAR_FLAG(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chLo)); } + if (edgeCallbackHi) { __DAL_TMR_CLEAR_FLAG(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(chHi)); @@ -561,10 +574,11 @@ void timerChITConfigDualLo(const timerHardware_t *timHw, FunctionalState newStat return; } - if (newState) + if (newState) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TMR_CHANNEL_2)); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel & ~TMR_CHANNEL_2)); + } } //// enable or disable IRQ @@ -580,10 +594,11 @@ void timerChITConfig(const timerHardware_t *timHw, FunctionalState newState) return; } - if (newState) + if (newState) { __DAL_TMR_ENABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); - else + } else { __DAL_TMR_DISABLE_IT(&timerHandle[timerIndex].Handle, TIM_IT_CCx(timHw->channel)); + } } // clear Compare/Capture flag for channel @@ -623,9 +638,11 @@ static unsigned getFilter(unsigned ticks) 16*5, 16*6, 16*8, 32*5, 32*6, 32*8 }; - for (unsigned i = 1; i < ARRAYLEN(ftab); i++) - if (ftab[i] > ticks) + for (unsigned i = 1; i < ARRAYLEN(ftab); i++) { + if (ftab[i] > ticks) { return i - 1; + } + } return 0x0f; } @@ -633,8 +650,9 @@ static unsigned getFilter(unsigned ticks) void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_IC_InitTypeDef TIM_ICInitStructure; @@ -650,8 +668,9 @@ void timerChConfigIC(const timerHardware_t *timHw, bool polarityRising, unsigned void timerChConfigICDual(const timerHardware_t *timHw, bool polarityRising, unsigned inputFilterTicks) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_IC_InitTypeDef TIM_ICInitStructure; bool directRising = (timHw->channel & TMR_CHANNEL_2) ? !polarityRising : polarityRising; @@ -695,8 +714,9 @@ volatile timCCR_t* timerChCCR(const timerHardware_t *timHw) void timerChConfigOC(const timerHardware_t* timHw, bool outEnable, bool stateHigh) { unsigned timer = lookupTimerIndex(timHw->tim); - if (timer >= USED_TIMER_COUNT) + if (timer >= USED_TIMER_COUNT) { return; + } TMR_OC_InitTypeDef TIM_OCInitStructure; @@ -1000,7 +1020,9 @@ void timerInit(void) void timerStart(TMR_TypeDef *tim) { TMR_HandleTypeDef* handle = timerFindTimerHandle(tim); - if (handle == NULL) return; + if (handle == NULL) { + return; + } __DAL_TMR_ENABLE(handle); } @@ -1135,13 +1157,16 @@ DAL_StatusTypeDef DMA_SetCurrDataCounter(TMR_HandleTypeDef *htim, uint32_t Chann { if ((htim->State == DAL_TMR_STATE_BUSY)) { return DAL_BUSY; - } else if ((htim->State == DAL_TMR_STATE_READY)) { - if (((uint32_t) pData == 0) && (Length > 0)) { - return DAL_ERROR; - } else { - htim->State = DAL_TMR_STATE_BUSY; + } else { + if ((htim->State == DAL_TMR_STATE_READY)) { + if (((uint32_t) pData == 0) && (Length > 0)) { + return DAL_ERROR; + } else { + htim->State = DAL_TMR_STATE_BUSY; + } } } + switch (Channel) { case TMR_CHANNEL_1: { /* Set the DMA Period elapsed callback */ diff --git a/src/platform/APM32/timer_apm32f4xx.c b/src/platform/APM32/timer_apm32f4xx.c index 708e6f3e29..e67e450306 100644 --- a/src/platform/APM32/timer_apm32f4xx.c +++ b/src/platform/APM32/timer_apm32f4xx.c @@ -30,7 +30,7 @@ #include "timer_def.h" #include "apm32f4xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/APM32/transponder_ir_io_apm32.c b/src/platform/APM32/transponder_ir_io_apm32.c index 799ccb8494..29a6786a80 100644 --- a/src/platform/APM32/transponder_ir_io_apm32.c +++ b/src/platform/APM32/transponder_ir_io_apm32.c @@ -31,7 +31,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/transponder_ir_arcitimer.h" #include "drivers/transponder_ir_erlt.h" @@ -165,6 +165,7 @@ void transponderIrHardwareInit(ioTag_t ioTag, transponder_t *transponder) /* Configuration Error */ return; } + if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) { if (DAL_TMREx_PWMN_Start(&TmrHandle, timerChannel) != DAL_OK) { /* Starting PWM generation Error */ diff --git a/src/platform/AT32/adc_at32f43x.c b/src/platform/AT32/adc_at32f43x.c index 31b6a45b55..13e13b3c5e 100644 --- a/src/platform/AT32/adc_at32f43x.c +++ b/src/platform/AT32/adc_at32f43x.c @@ -54,7 +54,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" #include "drivers/dma.h" diff --git a/src/platform/AT32/bus_i2c_atbsp.c b/src/platform/AT32/bus_i2c_atbsp.c index daa9f4bc9a..1ddef8d7a0 100644 --- a/src/platform/AT32/bus_i2c_atbsp.c +++ b/src/platform/AT32/bus_i2c_atbsp.c @@ -31,7 +31,7 @@ #include "drivers/io_impl.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/AT32/bus_i2c_atbsp_init.c b/src/platform/AT32/bus_i2c_atbsp_init.c index 0d3d4c2542..0e3c6aa740 100644 --- a/src/platform/AT32/bus_i2c_atbsp_init.c +++ b/src/platform/AT32/bus_i2c_atbsp_init.c @@ -30,7 +30,7 @@ #include "drivers/io.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/AT32/bus_spi_at32bsp.c b/src/platform/AT32/bus_spi_at32bsp.c index 4182e195f1..fed36d685e 100644 --- a/src/platform/AT32/bus_spi_at32bsp.c +++ b/src/platform/AT32/bus_spi_at32bsp.c @@ -35,7 +35,7 @@ #include "drivers/bus_spi_impl.h" #include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" // Use DMA if possible if this many bytes are to be transferred #define SPI_DMA_THRESHOLD 8 diff --git a/src/platform/AT32/camera_control_at32.c b/src/platform/AT32/camera_control_at32.c index 12a69d18ca..05f8ef7b98 100644 --- a/src/platform/AT32/camera_control_at32.c +++ b/src/platform/AT32/camera_control_at32.c @@ -28,7 +28,7 @@ #include "drivers/camera_control_impl.h" #include "drivers/nvic.h" #include "drivers/pwm_output.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #ifdef CAMERA_CONTROL_SOFTWARE_PWM_AVAILABLE #include "build/atomic.h" diff --git a/src/platform/AT32/dma_at32f43x.c b/src/platform/AT32/dma_at32f43x.c index e233713a42..94710fb68d 100644 --- a/src/platform/AT32/dma_at32f43x.c +++ b/src/platform/AT32/dma_at32f43x.c @@ -29,7 +29,7 @@ #include "drivers/nvic.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" /* diff --git a/src/platform/AT32/platform_mcu.h b/src/platform/AT32/include/platform/platform.h similarity index 95% rename from src/platform/AT32/platform_mcu.h rename to src/platform/AT32/include/platform/platform.h index 2c55895061..7e0a352450 100644 --- a/src/platform/AT32/platform_mcu.h +++ b/src/platform/AT32/include/platform/platform.h @@ -57,8 +57,6 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define U_ID_1 (*(uint32_t*)0x1ffff7ec) #define U_ID_2 (*(uint32_t*)0x1ffff7f0) -#define USE_PIN_AF - #ifndef AT32F4 #define AT32F4 #endif @@ -144,12 +142,15 @@ typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; #define UART_TX_BUFFER_ATTRIBUTE // NONE #define UART_RX_BUFFER_ATTRIBUTE // NONE -#define PLATFORM_TRAIT_RCC 1 -#define UART_TRAIT_AF_PIN 1 -#define UART_TRAIT_PINSWAP 1 +#define PLATFORM_TRAIT_RCC 1 +#define UART_TRAIT_AF_PIN 1 +#define UART_TRAIT_PINSWAP 1 #define SERIAL_TRAIT_PIN_CONFIG 1 - -#define UARTHARDWARE_MAX_PINS 5 +#define I2C_TRAIT_AF_PIN 1 +#define I2CDEV_COUNT 4 +#define I2C_TRAIT_HANDLE 1 +#define SPI_TRAIT_AF_PIN 1 +#define UARTHARDWARE_MAX_PINS 5 #define UART_REG_RXD(base) ((base)->dt) #define UART_REG_TXD(base) ((base)->dt) diff --git a/src/platform/AT32/io_at32.c b/src/platform/AT32/io_at32.c index 5905f4055f..b5759f99f7 100644 --- a/src/platform/AT32/io_at32.c +++ b/src/platform/AT32/io_at32.c @@ -23,7 +23,7 @@ #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "common/utils.h" diff --git a/src/platform/AT32/light_ws2811strip_at32f43x.c b/src/platform/AT32/light_ws2811strip_at32f43x.c index 1827556d30..e4afd9f202 100644 --- a/src/platform/AT32/light_ws2811strip_at32f43x.c +++ b/src/platform/AT32/light_ws2811strip_at32f43x.c @@ -35,7 +35,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/light_ws2811strip.h" diff --git a/src/platform/AT32/mk/AT32F4.mk b/src/platform/AT32/mk/AT32F4.mk index ec377078aa..f78c4671c9 100644 --- a/src/platform/AT32/mk/AT32F4.mk +++ b/src/platform/AT32/mk/AT32F4.mk @@ -121,8 +121,8 @@ MCU_COMMON_SRC = \ drivers/bus_i2c_timing.c \ drivers/usb_msc_common.c \ drivers/adc.c \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/bus_spi_pinconfig.c \ common/stm32/bus_spi_hw.c \ common/stm32/serial_uart_hw.c \ @@ -144,8 +144,8 @@ SPEED_OPTIMISED_SRC += \ SIZE_OPTIMISED_SRC += \ drivers/bus_i2c_timing.c \ drivers/inverter.c \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ diff --git a/src/platform/AT32/pwm_output_dshot.c b/src/platform/AT32/pwm_output_dshot.c index 2d4722da04..eff7db614e 100644 --- a/src/platform/AT32/pwm_output_dshot.c +++ b/src/platform/AT32/pwm_output_dshot.c @@ -33,7 +33,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/time.h" #include "drivers/timer.h" #include "drivers/system.h" diff --git a/src/platform/AT32/rcc_at32.c b/src/platform/AT32/rcc_at32.c index d3b2d1a4f1..87f8030d4d 100644 --- a/src/platform/AT32/rcc_at32.c +++ b/src/platform/AT32/rcc_at32.c @@ -23,7 +23,7 @@ */ #include "platform.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) { diff --git a/src/platform/AT32/serial_uart_at32bsp.c b/src/platform/AT32/serial_uart_at32bsp.c index 0875364108..1752de4f71 100644 --- a/src/platform/AT32/serial_uart_at32bsp.c +++ b/src/platform/AT32/serial_uart_at32bsp.c @@ -41,7 +41,7 @@ #include "common/utils.h" #include "drivers/inverter.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/dma.h" diff --git a/src/platform/AT32/serial_uart_at32f43x.c b/src/platform/AT32/serial_uart_at32f43x.c index 61733f5266..13f85194fd 100644 --- a/src/platform/AT32/serial_uart_at32f43x.c +++ b/src/platform/AT32/serial_uart_at32f43x.c @@ -31,7 +31,7 @@ #include "drivers/dma.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/AT32/timer_at32bsp.c b/src/platform/AT32/timer_at32bsp.c index 6336ad1a2a..a6da1cb51c 100644 --- a/src/platform/AT32/timer_at32bsp.c +++ b/src/platform/AT32/timer_at32bsp.c @@ -35,7 +35,7 @@ #include "drivers/nvic.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/system.h" #include "drivers/timer.h" #include "drivers/timer_impl.h" diff --git a/src/platform/AT32/timer_at32f43x.c b/src/platform/AT32/timer_at32f43x.c index 13c4b99b87..e2e8ecc8d4 100644 --- a/src/platform/AT32/timer_at32f43x.c +++ b/src/platform/AT32/timer_at32f43x.c @@ -28,7 +28,7 @@ #include "timer_def.h" #include "drivers/dma.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/PICO/link/pico_rp2350.ld b/src/platform/PICO/link/pico_rp2350.ld deleted file mode 100644 index c8f3dd7c79..0000000000 --- a/src/platform/PICO/link/pico_rp2350.ld +++ /dev/null @@ -1,302 +0,0 @@ -/* Based on GCC ARM embedded samples. - Defines the following symbols for use by code: - __exidx_start - __exidx_end - __etext - __data_start__ - __preinit_array_start - __preinit_array_end - __init_array_start - __init_array_end - __fini_array_start - __fini_array_end - __data_end__ - __bss_start__ - __bss_end__ - __end__ - end - __HeapLimit - __StackLimit - __StackTop - __stack (== StackTop) -*/ - -MEMORY -{ - FLASH(rx) : ORIGIN = 0x10000000, LENGTH = 4m - RAM(rwx) : ORIGIN = 0x20000000, LENGTH = 512k - SCRATCH_X(rwx) : ORIGIN = 0x20080000, LENGTH = 4k - SCRATCH_Y(rwx) : ORIGIN = 0x20081000, LENGTH = 4k -} - -ENTRY(_entry_point) - -SECTIONS -{ - .flash_begin : { - __flash_binary_start = .; - } > FLASH - - /* The bootrom will enter the image at the point indicated in your - IMAGE_DEF, which is usually the reset handler of your vector table. - - The debugger will use the ELF entry point, which is the _entry_point - symbol, and in our case is *different from the bootrom's entry point.* - This is used to go back through the bootrom on debugger launches only, - to perform the same initial flash setup that would be performed on a - cold boot. - */ - - .text : { - __logical_binary_start = .; - KEEP (*(.vectors)) - KEEP (*(.binary_info_header)) - __binary_info_header_end = .; - KEEP (*(.embedded_block)) - __embedded_block_end = .; - KEEP (*(.reset)) - /* TODO revisit this now memset/memcpy/float in ROM */ - /* bit of a hack right now to exclude all floating point and time critical (e.g. memset, memcpy) code from - * FLASH ... we will include any thing excluded here in .data below by default */ - *(.init) - *libgcc.a:cmse_nonsecure_call.o - *(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .text*) - *(.fini) - /* Pull all c'tors into .text */ - *crtbegin.o(.ctors) - *crtbegin?.o(.ctors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .ctors) - *(SORT(.ctors.*)) - *(.ctors) - /* Followed by destructors */ - *crtbegin.o(.dtors) - *crtbegin?.o(.dtors) - *(EXCLUDE_FILE(*crtend?.o *crtend.o) .dtors) - *(SORT(.dtors.*)) - *(.dtors) - - . = ALIGN(4); - /* preinit data */ - PROVIDE_HIDDEN (__preinit_array_start = .); - KEEP(*(SORT(.preinit_array.*))) - KEEP(*(.preinit_array)) - PROVIDE_HIDDEN (__preinit_array_end = .); - - . = ALIGN(4); - /* init data */ - PROVIDE_HIDDEN (__init_array_start = .); - KEEP(*(SORT(.init_array.*))) - KEEP(*(.init_array)) - PROVIDE_HIDDEN (__init_array_end = .); - - . = ALIGN(4); - /* finit data */ - PROVIDE_HIDDEN (__fini_array_start = .); - *(SORT(.fini_array.*)) - *(.fini_array) - PROVIDE_HIDDEN (__fini_array_end = .); - - *(.eh_frame*) - . = ALIGN(4); - } > FLASH - - /* Note the boot2 section is optional, and should be discarded if there is - no reference to it *inside* the binary, as it is not called by the - bootrom. (The bootrom performs a simple best-effort XIP setup and - leaves it to the binary to do anything more sophisticated.) However - there is still a size limit of 256 bytes, to ensure the boot2 can be - stored in boot RAM. - - Really this is a "XIP setup function" -- the name boot2 is historic and - refers to its dual-purpose on RP2040, where it also handled vectoring - from the bootrom into the user image. - */ - - .boot2 : { - __boot2_start__ = .; - *(.boot2) - __boot2_end__ = .; - } > FLASH - - ASSERT(__boot2_end__ - __boot2_start__ <= 256, - "ERROR: Pico second stage bootloader must be no more than 256 bytes in size") - - .rodata : { - *(EXCLUDE_FILE(*libgcc.a: *libc.a:*lib_a-mem*.o *libm.a:) .rodata*) - *(.srodata*) - . = ALIGN(4); - *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.flashdata*))) - . = ALIGN(4); - } > FLASH - - .ARM.extab : - { - *(.ARM.extab* .gnu.linkonce.armextab.*) - } > FLASH - - __exidx_start = .; - .ARM.exidx : - { - *(.ARM.exidx* .gnu.linkonce.armexidx.*) - } > FLASH - __exidx_end = .; - - /* Machine inspectable binary information */ - . = ALIGN(4); - __binary_info_start = .; - .binary_info : - { - KEEP(*(.binary_info.keep.*)) - *(.binary_info.*) - } > FLASH - __binary_info_end = .; - . = ALIGN(4); - - .ram_vector_table (NOLOAD): { - *(.ram_vector_table) - } > RAM - - .uninitialized_data (NOLOAD): { - . = ALIGN(4); - *(.uninitialized_data*) - } > RAM - - .data : { - __data_start__ = .; - *(vtable) - - *(.time_critical*) - - /* remaining .text and .rodata; i.e. stuff we exclude above because we want it in RAM */ - *(.text*) - . = ALIGN(4); - *(.rodata*) - . = ALIGN(4); - - *(.data*) - *(.sdata*) - - . = ALIGN(4); - *(.after_data.*) - . = ALIGN(4); - /* preinit data */ - PROVIDE_HIDDEN (__mutex_array_start = .); - KEEP(*(SORT(.mutex_array.*))) - KEEP(*(.mutex_array)) - PROVIDE_HIDDEN (__mutex_array_end = .); - - *(.jcr) - . = ALIGN(4); - } > RAM AT> FLASH - - .tdata : { - . = ALIGN(4); - *(.tdata .tdata.* .gnu.linkonce.td.*) - /* All data end */ - __tdata_end = .; - } > RAM AT> FLASH - PROVIDE(__data_end__ = .); - - /* __etext is (for backwards compatibility) the name of the .data init source pointer (...) */ - __etext = LOADADDR(.data); - - .tbss (NOLOAD) : { - . = ALIGN(4); - __bss_start__ = .; - __tls_base = .; - *(.tbss .tbss.* .gnu.linkonce.tb.*) - *(.tcommon) - - __tls_end = .; - } > RAM - - .bss (NOLOAD) : { - . = ALIGN(4); - __tbss_end = .; - - *(SORT_BY_ALIGNMENT(SORT_BY_NAME(.bss*))) - *(COMMON) - PROVIDE(__global_pointer$ = . + 2K); - *(.sbss*) - . = ALIGN(4); - __bss_end__ = .; - } > RAM - - .heap (NOLOAD): - { - __end__ = .; - end = __end__; - KEEP(*(.heap*)) - } > RAM - /* historically on GCC sbrk was growing past __HeapLimit to __StackLimit, however - to be more compatible, we now set __HeapLimit explicitly to where the end of the heap is */ - __HeapLimit = ORIGIN(RAM) + LENGTH(RAM); - - /* Start and end symbols must be word-aligned */ - .scratch_x : { - __scratch_x_start__ = .; - *(.scratch_x.*) - . = ALIGN(4); - __scratch_x_end__ = .; - } > SCRATCH_X AT > FLASH - __scratch_x_source__ = LOADADDR(.scratch_x); - - .scratch_y : { - __scratch_y_start__ = .; - *(.scratch_y.*) - . = ALIGN(4); - __scratch_y_end__ = .; - } > SCRATCH_Y AT > FLASH - __scratch_y_source__ = LOADADDR(.scratch_y); - - /* .stack*_dummy section doesn't contains any symbols. It is only - * used for linker to calculate size of stack sections, and assign - * values to stack symbols later - * - * stack1 section may be empty/missing if platform_launch_core1 is not used */ - - /* by default we put core 0 stack at the end of scratch Y, so that if core 1 - * stack is not used then all of SCRATCH_X is free. - */ - .stack1_dummy (NOLOAD): - { - *(.stack1*) - } > SCRATCH_X - .stack_dummy (NOLOAD): - { - KEEP(*(.stack*)) - } > SCRATCH_Y - - .flash_end : { - KEEP(*(.embedded_end_block*)) - PROVIDE(__flash_binary_end = .); - } > FLASH =0xaa - - /* stack limit is poorly named, but historically is maximum heap ptr */ - __StackLimit = ORIGIN(RAM) + LENGTH(RAM); - __StackOneTop = ORIGIN(SCRATCH_X) + LENGTH(SCRATCH_X); - __StackTop = ORIGIN(SCRATCH_Y) + LENGTH(SCRATCH_Y); - __StackOneBottom = __StackOneTop - SIZEOF(.stack1_dummy); - __StackBottom = __StackTop - SIZEOF(.stack_dummy); - PROVIDE(__stack = __StackTop); - - /* picolibc and LLVM */ - PROVIDE (__heap_start = __end__); - PROVIDE (__heap_end = __HeapLimit); - PROVIDE( __tls_align = MAX(ALIGNOF(.tdata), ALIGNOF(.tbss)) ); - PROVIDE( __tls_size_align = (__tls_size + __tls_align - 1) & ~(__tls_align - 1)); - PROVIDE( __arm32_tls_tcb_offset = MAX(8, __tls_align) ); - - /* llvm-libc */ - PROVIDE (_end = __end__); - PROVIDE (__llvm_libc_heap_limit = __HeapLimit); - - /* Check if data + heap + stack exceeds RAM limit */ - ASSERT(__StackLimit >= __HeapLimit, "region RAM overflowed") - - ASSERT( __binary_info_header_end - __logical_binary_start <= 1024, "Binary info must be in first 1024 bytes of the binary") - ASSERT( __embedded_block_end - __logical_binary_start <= 4096, "Embedded block must be in first 4096 bytes of the binary") - - /* todo assert on extra code */ -} - diff --git a/src/platform/PICO/mk/PICO.mk b/src/platform/PICO/mk/PICO.mk deleted file mode 100644 index 699ee8f0fe..0000000000 --- a/src/platform/PICO/mk/PICO.mk +++ /dev/null @@ -1,158 +0,0 @@ -# -# Raspberry PICO Make file include -# - -ifeq ($(DEBUG_HARDFAULTS),PICO) -CFLAGS += -DDEBUG_HARDFAULTS -endif - -SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk - -#CMSIS -CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS - -#STDPERIPH -STDPERIPH_DIR = $(SDK_SIR) -STDPERIPH_SRC = \ - - -VPATH := $(VPATH):$(STDPERIPH_DIR) - -DEVICE_STDPERIPH_SRC := \ - $(STDPERIPH_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) \ - $(USBHID_SRC) \ - $(USBMSC_SRC) - -#CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(CMSIS_DIR)/Device/$(TARGET_MCU)/Include -CMSIS_SRC := - -#SRC -VPATH := $(VPATH):$(STDPERIPH_DIR) - -INCLUDE_DIRS := \ - $(INCLUDE_DIRS) \ - $(TARGET_PLATFORM_DIR) \ - $(TARGET_PLATFORM_DIR)/startup \ - $(SDK_DIR)/$(TARGET_MCU)/pico_platform/include \ - $(SDK_DIR)/$(TARGET_MCU)/hardware_regs/include \ - $(SDK_DIR)/$(TARGET_MCU)/hardware_structs/include \ - $(SDK_DIR)/common/pico_bit_ops_headers/include \ - $(SDK_DIR)/common/pico_base_headers/include \ - $(SDK_DIR)/common/boot_picoboot_headers/include \ - $(SDK_DIR)/common/pico_usb_reset_interface_headers/include \ - $(SDK_DIR)/common/pico_time/include \ - $(SDK_DIR)/common/boot_uf2_headers/include \ - $(SDK_DIR)/common/pico_divider_headers/include \ - $(SDK_DIR)/common/boot_picobin_headers/include \ - $(SDK_DIR)/common/pico_util/include \ - $(SDK_DIR)/common/pico_stdlib_headers/include \ - $(SDK_DIR)/common/hardware_claim/include \ - $(SDK_DIR)/common/pico_binary_info/include \ - $(SDK_DIR)/common/pico_sync/include \ - $(SDK_DIR)/rp2_common/pico_stdio_uart/include \ - $(SDK_DIR)/rp2_common/pico_stdio_usb/include \ - $(SDK_DIR)/rp2_common/pico_stdio_rtt/include \ - $(SDK_DIR)/rp2_common/tinyusb/include \ - $(SDK_DIR)/rp2_common/hardware_rtc/include \ - $(SDK_DIR)/rp2_common/hardware_boot_lock/include \ - $(SDK_DIR)/rp2_common/pico_mem_ops/include \ - $(SDK_DIR)/rp2_common/hardware_exception/include \ - $(SDK_DIR)/rp2_common/hardware_sync_spin_lock/include \ - $(SDK_DIR)/rp2_common/pico_runtime_init/include \ - $(SDK_DIR)/rp2_common/pico_standard_link/include \ - $(SDK_DIR)/rp2_common/hardware_pio/include \ - $(SDK_DIR)/rp2_common/pico_platform_compiler/include \ - $(SDK_DIR)/rp2_common/hardware_divider/include \ - $(SDK_DIR)/rp2_common/pico_bootsel_via_double_reset/include \ - $(SDK_DIR)/rp2_common/hardware_powman/include \ - $(SDK_DIR)/rp2_common/pico_btstack/include \ - $(SDK_DIR)/rp2_common/pico_cyw43_driver/include \ - $(SDK_DIR)/rp2_common/hardware_flash/include \ - $(SDK_DIR)/rp2_common/hardware_ticks/include \ - $(SDK_DIR)/rp2_common/hardware_dma/include \ - $(SDK_DIR)/rp2_common/pico_bit_ops/include \ - $(SDK_DIR)/rp2_common/hardware_clocks/include \ - $(SDK_DIR)/rp2_common/pico_unique_id/include \ - $(SDK_DIR)/rp2_common/hardware_dcp/include \ - $(SDK_DIR)/rp2_common/hardware_watchdog/include \ - $(SDK_DIR)/rp2_common/pico_rand/include \ - $(SDK_DIR)/rp2_common/hardware_hazard3/include \ - $(SDK_DIR)/rp2_common/hardware_uart/include \ - $(SDK_DIR)/rp2_common/hardware_interp/include \ - $(SDK_DIR)/rp2_common/pico_printf/include \ - $(SDK_DIR)/rp2_common/pico_aon_timer/include \ - $(SDK_DIR)/rp2_common/hardware_riscv_platform_timer/include \ - $(SDK_DIR)/rp2_common/pico_double/include \ - $(SDK_DIR)/rp2_common/pico_cyw43_arch/include \ - $(SDK_DIR)/rp2_common/hardware_vreg/include \ - $(SDK_DIR)/rp2_common/pico_mbedtls/include \ - $(SDK_DIR)/rp2_common/hardware_spi/include \ - $(SDK_DIR)/rp2_common/hardware_rcp/include \ - $(SDK_DIR)/rp2_common/hardware_riscv/include \ - $(SDK_DIR)/rp2_common/pico_standard_binary_info/include \ - $(SDK_DIR)/rp2_common/pico_i2c_slave/include \ - $(SDK_DIR)/rp2_common/pico_int64_ops/include \ - $(SDK_DIR)/rp2_common/pico_sha256/include \ - $(SDK_DIR)/rp2_common/hardware_irq/include \ - $(SDK_DIR)/rp2_common/pico_divider/include \ - $(SDK_DIR)/rp2_common/pico_flash/include \ - $(SDK_DIR)/rp2_common/hardware_sync/include \ - $(SDK_DIR)/rp2_common/pico_bootrom/include \ - $(SDK_DIR)/rp2_common/pico_crt0/include \ - $(SDK_DIR)/rp2_common/pico_clib_interface/include \ - $(SDK_DIR)/rp2_common/pico_stdio/include \ - $(SDK_DIR)/rp2_common/pico_runtime/include \ - $(SDK_DIR)/rp2_common/pico_time_adapter/include \ - $(SDK_DIR)/rp2_common/pico_platform_panic/include \ - $(SDK_DIR)/rp2_common/hardware_adc/include \ - $(SDK_DIR)/rp2_common/cmsis/include \ - $(SDK_DIR)/rp2_common/hardware_pll/include \ - $(SDK_DIR)/rp2_common/pico_platform_sections/include \ - $(SDK_DIR)/rp2_common/boot_bootrom_headers/include \ - $(SDK_DIR)/rp2_common/pico_fix/include \ - $(SDK_DIR)/rp2_common/pico_lwip/include \ - $(SDK_DIR)/rp2_common/hardware_base/include \ - $(SDK_DIR)/rp2_common/hardware_xosc/include \ - $(SDK_DIR)/rp2_common/pico_async_context/include \ - $(SDK_DIR)/rp2_common/hardware_pwm/include \ - $(SDK_DIR)/rp2_common/pico_stdio_semihosting/include \ - $(SDK_DIR)/rp2_common/pico_float/include \ - $(SDK_DIR)/rp2_common/hardware_resets/include \ - $(SDK_DIR)/rp2_common/pico_cxx_options/include \ - $(SDK_DIR)/rp2_common/pico_stdlib/include \ - $(SDK_DIR)/rp2_common/hardware_sha256/include \ - $(SDK_DIR)/rp2_common/hardware_i2c/include \ - $(SDK_DIR)/rp2_common/pico_atomic/include \ - $(SDK_DIR)/rp2_common/pico_multicore/include \ - $(SDK_DIR)/rp2_common/hardware_gpio/include \ - $(SDK_DIR)/rp2_common/pico_malloc/include \ - $(SDK_DIR)/rp2_common/hardware_timer/include \ - $(CMSIS_DIR)/Core/Include \ - $(CMSIS_DIR)/Device/$(TARGET_MCU)/Include - -#Flags -ARCH_FLAGS = -mthumb -mcpu=cortex-m33 -march=armv8-m.main+fp+dsp -mfloat-abi=softfp -mcmse - -DEVICE_FLAGS = - -ifeq ($(TARGET_MCU),RP2350) -DEVICE_FLAGS += -DRP2350 -DLIB_BOOT_STAGE2_HEADERS=1 -DLIB_PICO_ATOMIC=1 -DLIB_PICO_BIT_OPS=1 -DLIB_PICO_BIT_OPS_PICO=1 -DLIB_PICO_CLIB_INTERFACE=1 -DLIB_PICO_CRT0=1 -DLIB_PICO_CXX_OPTIONS=1 -DLIB_PICO_DIVIDER=1 -DLIB_PICO_DIVIDER_COMPILER=1 -DLIB_PICO_DOUBLE=1 -DLIB_PICO_DOUBLE_PICO=1 -DLIB_PICO_FLOAT=1 -DLIB_PICO_FLOAT_PICO=1 -DLIB_PICO_FLOAT_PICO_VFP=1 -DLIB_PICO_INT64_OPS=1 -DLIB_PICO_INT64_OPS_COMPILER=1 -DLIB_PICO_MALLOC=1 -DLIB_PICO_MEM_OPS=1 -DLIB_PICO_MEM_OPS_COMPILER=1 -DLIB_PICO_NEWLIB_INTERFACE=1 -DLIB_PICO_PLATFORM=1 -DLIB_PICO_PLATFORM_COMPILER=1 -DLIB_PICO_PLATFORM_PANIC=1 -DLIB_PICO_PLATFORM_SECTIONS=1 -DLIB_PICO_PRINTF=1 -DLIB_PICO_PRINTF_PICO=1 -DLIB_PICO_RUNTIME=1 -DLIB_PICO_RUNTIME_INIT=1 -DLIB_PICO_STANDARD_BINARY_INFO=1 -DLIB_PICO_STANDARD_LINK=1 -DLIB_PICO_STDIO=1 -DLIB_PICO_STDIO_UART=1 -DLIB_PICO_STDLIB=1 -DLIB_PICO_SYNC=1 -DLIB_PICO_SYNC_CRITICAL_SECTION=1 -DLIB_PICO_SYNC_MUTEX=1 -DLIB_PICO_SYNC_SEM=1 -DLIB_PICO_TIME=1 -DLIB_PICO_TIME_ADAPTER=1 -DLIB_PICO_UTIL=1 -DPICO_32BIT=1 -DPICO_BUILD=1 -DPICO_COPY_TO_RAM=0 -DPICO_CXX_ENABLE_EXCEPTIONS=0 -DPICO_NO_FLASH=0 -DPICO_NO_HARDWARE=0 -DPICO_ON_DEVICE=1 -DPICO_RP2350=1 -DPICO_USE_BLOCKED_RAM=0 -LD_SCRIPT = $(LINKER_DIR)/pico_rp2350.ld -STARTUP_SRC = startup/bs2_default_padded_checksummed.S -MCU_FLASH_SIZE = 4096 -# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets. -# Performance is only slightly affected but around 50 kB of flash are saved. -OPTIMISE_SPEED = -O2 -else -$(error Unknown MCU for Raspberry PICO target) -endif - -DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DPICO - -MCU_COMMON_SRC = \ - - -DEVICE_FLAGS += diff --git a/src/platform/PICO/platform_mcu.h b/src/platform/PICO/platform_mcu.h deleted file mode 100644 index 253dddd054..0000000000 --- a/src/platform/PICO/platform_mcu.h +++ /dev/null @@ -1,67 +0,0 @@ -/* - * This file is part of Betaflight. - * - * Betaflight is 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. - * - * Betaflight 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 this software. - * - * If not, see . - */ - -#pragma once - -#if defined(RP2350) - -#include "RP2350.h" - -typedef enum {DISABLE = 0, ENABLE = !DISABLE} FunctionalState; - -#define I2C_TypeDef I2C0_Type -//#define I2C_HandleTypeDef -#define GPIO_TypeDef IO_BANK0_Type -//#define GPIO_InitTypeDef -#define TIM_TypeDef TIMER0_Type -//#define TIM_OCInitTypeDef -#define DMA_TypeDef DMA_Type -//#define DMA_InitTypeDef -//#define DMA_Channel_TypeDef -#define SPI_TypeDef SPI0_Type -#define ADC_TypeDef ADC_Type -#define USART_TypeDef UART0_Type -#define TIM_OCInitTypeDef TIMER0_Type -#define TIM_ICInitTypeDef TIMER0_Type -//#define TIM_OCStructInit -//#define TIM_Cmd -//#define TIM_CtrlPWMOutputs -//#define TIM_TimeBaseInit -//#define TIM_ARRPreloadConfig -//#define SystemCoreClock -//#define EXTI_TypeDef -//#define EXTI_InitTypeDef - - -#endif - -#define DEFAULT_CPU_OVERCLOCK 0 -#define TASK_GYROPID_DESIRED_PERIOD 125 // 125us = 8kHz -#define SCHEDULER_DELAY_LIMIT 10 - -#define IOCFG_OUT_PP 0 -#define IOCFG_OUT_OD 0 -#define IOCFG_AF_PP 0 -#define IOCFG_AF_OD 0 -#define IOCFG_IPD 0 -#define IOCFG_IPU 0 -#define IOCFG_IN_FLOATING 0 - 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/PICO/target/RP2350/.exclude b/src/platform/PICO/target/RP2350/.exclude deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/platform/PICO/target/RP2350/target.h b/src/platform/PICO/target/RP2350/target.h deleted file mode 100644 index f7b9076ccc..0000000000 --- a/src/platform/PICO/target/RP2350/target.h +++ /dev/null @@ -1,69 +0,0 @@ -/* - * This file is part of Betaflight. - * - * Betaflight is 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. - * - * Betaflight 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 this software. - * - * If not, see . - */ - -#pragma once - -#ifndef TARGET_BOARD_IDENTIFIER -#define TARGET_BOARD_IDENTIFIER "R235" -#endif - -#ifndef USBD_PRODUCT_STRING -#define USBD_PRODUCT_STRING "Betaflight RP2350" -#endif - -#undef USE_DMA -#undef USE_FLASH -#undef USE_FLASH_CHIP - -#undef USE_TIMER -#undef USE_SPI -#undef USE_I2C -#undef USE_UART -#undef USE_DSHOT -#undef USE_RCC - -#define GPIOA_BASE ((intptr_t)0x0001) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff - -#undef USE_FLASH -#undef USE_FLASH_CHIP -#undef USE_FLASH_M25P16 -#undef USE_FLASH_W25N01G -#undef USE_FLASH_W25N02K -#undef USE_FLASH_W25M -#undef USE_FLASH_W25M512 -#undef USE_FLASH_W25M02G -#undef USE_FLASH_W25Q128FV -#undef USE_FLASH_PY25Q128HA -#undef USE_FLASH_W25Q64FV - -#define FLASH_PAGE_SIZE 0x1000 -#define CONFIG_IN_RAM - -#define U_ID_0 0 -#define U_ID_1 1 -#define U_ID_2 2 diff --git a/src/platform/PICO/target/RP2350/target.mk b/src/platform/PICO/target/RP2350/target.mk deleted file mode 100644 index 94f4209a29..0000000000 --- a/src/platform/PICO/target/RP2350/target.mk +++ /dev/null @@ -1,2 +0,0 @@ -TARGET_MCU := RP2350 -TARGET_MCU_FAMILY := PICO diff --git a/src/platform/SIMULATOR/platform_mcu.h b/src/platform/SIMULATOR/include/platform/platform.h similarity index 91% rename from src/platform/SIMULATOR/platform_mcu.h rename to src/platform/SIMULATOR/include/platform/platform.h index be11284f04..4331c71989 100644 --- a/src/platform/SIMULATOR/platform_mcu.h +++ b/src/platform/SIMULATOR/include/platform/platform.h @@ -33,3 +33,7 @@ // no serial pins are defined for the simulator #define SERIAL_TRAIT_PIN_CONFIG 0 + +#define I2CDEV_COUNT 0 + +typedef void* ADC_TypeDef; // Dummy definition for ADC_TypeDef 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) \ diff --git a/src/platform/STM32/adc_stm32f4xx.c b/src/platform/STM32/adc_stm32f4xx.c index 1a9de8f69d..f8c46d83e6 100644 --- a/src/platform/STM32/adc_stm32f4xx.c +++ b/src/platform/STM32/adc_stm32f4xx.c @@ -31,7 +31,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/dma.h" #include "drivers/sensor.h" #include "drivers/adc.h" diff --git a/src/platform/STM32/adc_stm32f7xx.c b/src/platform/STM32/adc_stm32f7xx.c index f631543c47..0ef61b3f32 100644 --- a/src/platform/STM32/adc_stm32f7xx.c +++ b/src/platform/STM32/adc_stm32f7xx.c @@ -30,7 +30,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/sensor.h" #include "drivers/adc.h" diff --git a/src/platform/STM32/adc_stm32g4xx.c b/src/platform/STM32/adc_stm32g4xx.c index 26e6ac9e6b..c378d9cbbd 100644 --- a/src/platform/STM32/adc_stm32g4xx.c +++ b/src/platform/STM32/adc_stm32g4xx.c @@ -31,7 +31,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" #include "drivers/dma.h" diff --git a/src/platform/STM32/adc_stm32h7xx.c b/src/platform/STM32/adc_stm32h7xx.c index 643fff600e..96a3327628 100644 --- a/src/platform/STM32/adc_stm32h7xx.c +++ b/src/platform/STM32/adc_stm32h7xx.c @@ -31,7 +31,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" #include "drivers/dma.h" diff --git a/src/platform/STM32/bus_i2c_hal.c b/src/platform/STM32/bus_i2c_hal.c index bdb3c5fd39..915cc9a7cf 100644 --- a/src/platform/STM32/bus_i2c_hal.c +++ b/src/platform/STM32/bus_i2c_hal.c @@ -30,7 +30,7 @@ #include "drivers/io_impl.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/STM32/bus_i2c_hal_init.c b/src/platform/STM32/bus_i2c_hal_init.c index 650c034244..d41926a470 100644 --- a/src/platform/STM32/bus_i2c_hal_init.c +++ b/src/platform/STM32/bus_i2c_hal_init.c @@ -29,7 +29,7 @@ #include "drivers/io.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/STM32/bus_i2c_stm32f4xx.c b/src/platform/STM32/bus_i2c_stm32f4xx.c index 2d7be2dfb5..3a27d75edd 100644 --- a/src/platform/STM32/bus_i2c_stm32f4xx.c +++ b/src/platform/STM32/bus_i2c_stm32f4xx.c @@ -30,7 +30,7 @@ #include "drivers/io.h" #include "drivers/time.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/bus_i2c.h" #include "drivers/bus_i2c_impl.h" diff --git a/src/platform/STM32/bus_quadspi_hal.c b/src/platform/STM32/bus_quadspi_hal.c index bc119ee796..efb7226f93 100644 --- a/src/platform/STM32/bus_quadspi_hal.c +++ b/src/platform/STM32/bus_quadspi_hal.c @@ -33,7 +33,7 @@ #include "drivers/io.h" #include "drivers/io_impl.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "pg/bus_quadspi.h" diff --git a/src/platform/STM32/bus_spi_ll.c b/src/platform/STM32/bus_spi_ll.c index 9e3d3ea21c..2a12575335 100644 --- a/src/platform/STM32/bus_spi_ll.c +++ b/src/platform/STM32/bus_spi_ll.c @@ -34,7 +34,7 @@ #include "drivers/bus_spi_impl.h" #include "drivers/dma.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" // Use DMA if possible if this many bytes are to be transferred #define SPI_DMA_THRESHOLD 8 diff --git a/src/platform/STM32/bus_spi_stdperiph.c b/src/platform/STM32/bus_spi_stdperiph.c index 5fcf671528..9bb02fba80 100644 --- a/src/platform/STM32/bus_spi_stdperiph.c +++ b/src/platform/STM32/bus_spi_stdperiph.c @@ -35,7 +35,7 @@ #include "drivers/bus_spi_impl.h" #include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" // Use DMA if possible if this many bytes are to be transferred #define SPI_DMA_THRESHOLD 8 diff --git a/src/platform/STM32/dma_stm32f7xx.c b/src/platform/STM32/dma_stm32f7xx.c index 14ece8e35c..eb432a39d7 100644 --- a/src/platform/STM32/dma_stm32f7xx.c +++ b/src/platform/STM32/dma_stm32f7xx.c @@ -28,7 +28,7 @@ #include "drivers/nvic.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" /* diff --git a/src/platform/STM32/dma_stm32g4xx.c b/src/platform/STM32/dma_stm32g4xx.c index 6e0d805038..d8e9d25672 100644 --- a/src/platform/STM32/dma_stm32g4xx.c +++ b/src/platform/STM32/dma_stm32g4xx.c @@ -28,7 +28,7 @@ #include "drivers/nvic.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" /* diff --git a/src/platform/STM32/dma_stm32h7xx.c b/src/platform/STM32/dma_stm32h7xx.c index 52d7aa1a27..9ecbc185a9 100644 --- a/src/platform/STM32/dma_stm32h7xx.c +++ b/src/platform/STM32/dma_stm32h7xx.c @@ -28,7 +28,7 @@ #include "drivers/nvic.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/resource.h" /* diff --git a/src/platform/STM32/platform_mcu.h b/src/platform/STM32/include/platform/platform.h similarity index 96% rename from src/platform/STM32/platform_mcu.h rename to src/platform/STM32/include/platform/platform.h index f8c2e75d80..3f9e13e5a1 100644 --- a/src/platform/STM32/platform_mcu.h +++ b/src/platform/STM32/include/platform/platform.h @@ -39,7 +39,8 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) -#define USE_PIN_AF +#define SPI_TRAIT_AF_PIN 1 +#define I2C_TRAIT_AF_PIN 1 #ifndef STM32G4 #define STM32G4 @@ -64,7 +65,8 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) -#define USE_PIN_AF +#define SPI_TRAIT_AF_PIN 1 +#define I2C_TRAIT_AF_PIN 1 #ifndef STM32H7 #define STM32H7 @@ -89,7 +91,7 @@ #define U_ID_1 (*(uint32_t*)(UID_BASE + 4)) #define U_ID_2 (*(uint32_t*)(UID_BASE + 8)) -#define USE_PIN_AF +#define SPI_TRAIT_AF_PIN 1 #ifndef STM32F7 #define STM32F7 @@ -104,6 +106,11 @@ #define U_ID_1 (*(uint32_t*)0x1fff7a14) #define U_ID_2 (*(uint32_t*)0x1fff7a18) +#define SPI_TRAIT_AF_PORT 1 + +#define I2C_TRAIT_STATE 1 +#define I2C_TRAIT_AF_PIN 1 + #ifndef STM32F4 #define STM32F4 #endif @@ -419,3 +426,25 @@ extern uint8_t _dmaram_end__; #define SERIAL_TRAIT_PIN_CONFIG 1 #define USB_DP_PIN PA12 + +#if defined(USE_HAL_DRIVER) +#define I2C_TRAIT_HANDLE 1 + +#if defined(HAL_SPI_MODULE_ENABLED) +#define SPI_TRAIT_HANDLE 1 +#endif + +#endif + +#if defined(STM32F4) +#define I2CDEV_COUNT 3 +#else +#define I2CDEV_COUNT 4 +#endif + +// QUAD SPI +#if defined(STM32H7) +#define QUADSPI_TRAIT_AF_PIN 1 +#define QUADSPI_TRAIT_HANDLE 1 +#define MAX_QUADSPI_PIN_SEL 3 +#endif diff --git a/src/platform/STM32/io_stm32.c b/src/platform/STM32/io_stm32.c index 2557f09764..abcde9cf92 100644 --- a/src/platform/STM32/io_stm32.c +++ b/src/platform/STM32/io_stm32.c @@ -22,7 +22,7 @@ #include "drivers/io.h" #include "drivers/io_impl.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "common/utils.h" diff --git a/src/platform/STM32/light_ws2811strip_hal.c b/src/platform/STM32/light_ws2811strip_hal.c index bdb9487851..c5f885c1b2 100644 --- a/src/platform/STM32/light_ws2811strip_hal.c +++ b/src/platform/STM32/light_ws2811strip_hal.c @@ -31,7 +31,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/system.h" #include "drivers/timer.h" diff --git a/src/platform/STM32/light_ws2811strip_stdperiph.c b/src/platform/STM32/light_ws2811strip_stdperiph.c index 1b4dbf9017..13723de3f5 100644 --- a/src/platform/STM32/light_ws2811strip_stdperiph.c +++ b/src/platform/STM32/light_ws2811strip_stdperiph.c @@ -34,7 +34,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/light_ws2811strip.h" diff --git a/src/platform/STM32/mk/STM32_COMMON.mk b/src/platform/STM32/mk/STM32_COMMON.mk index a70deb0de2..f300fd3b32 100644 --- a/src/platform/STM32/mk/STM32_COMMON.mk +++ b/src/platform/STM32/mk/STM32_COMMON.mk @@ -5,8 +5,8 @@ MCU_COMMON_SRC += \ common/stm32/system.c \ common/stm32/config_flash.c \ common/stm32/bus_spi_pinconfig.c \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/bus_spi_hw.c \ common/stm32/io_impl.c \ common/stm32/serial_uart_hw.c \ @@ -16,8 +16,8 @@ MCU_COMMON_SRC += \ common/stm32/dshot_bitbang_shared.c SIZE_OPTIMISED_SRC += \ - drivers/bus_i2c_config.c \ drivers/bus_spi_config.c \ + common/stm32/bus_i2c_pinconfig.c \ common/stm32/config_flash.c \ common/stm32/bus_spi_pinconfig.c diff --git a/src/platform/STM32/pwm_output_dshot.c b/src/platform/STM32/pwm_output_dshot.c index dcf2bba859..506a147364 100644 --- a/src/platform/STM32/pwm_output_dshot.c +++ b/src/platform/STM32/pwm_output_dshot.c @@ -32,7 +32,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/time.h" #include "drivers/timer.h" #include "drivers/system.h" diff --git a/src/platform/STM32/pwm_output_dshot_hal.c b/src/platform/STM32/pwm_output_dshot_hal.c index 3e6fe722a3..0c82414916 100644 --- a/src/platform/STM32/pwm_output_dshot_hal.c +++ b/src/platform/STM32/pwm_output_dshot_hal.c @@ -40,7 +40,7 @@ #include "drivers/motor.h" #include "drivers/pwm_output.h" #include "pwm_output_dshot_shared.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/time.h" #include "drivers/timer.h" #include "drivers/system.h" diff --git a/src/platform/STM32/rcc_stm32.c b/src/platform/STM32/rcc_stm32.c index f8afd03f36..17f10fbb52 100644 --- a/src/platform/STM32/rcc_stm32.c +++ b/src/platform/STM32/rcc_stm32.c @@ -19,7 +19,7 @@ */ #include "platform.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" void RCC_ClockCmd(rccPeriphTag_t periphTag, FunctionalState NewState) { diff --git a/src/platform/STM32/sdio_f4xx.c b/src/platform/STM32/sdio_f4xx.c index ec64647c3f..3aba6decb5 100644 --- a/src/platform/STM32/sdio_f4xx.c +++ b/src/platform/STM32/sdio_f4xx.c @@ -44,7 +44,7 @@ #include "drivers/io_impl.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/dma.h" #include "drivers/light_led.h" diff --git a/src/platform/STM32/sdio_f7xx.c b/src/platform/STM32/sdio_f7xx.c index 2f1bc62b5c..112028e6f8 100644 --- a/src/platform/STM32/sdio_f7xx.c +++ b/src/platform/STM32/sdio_f7xx.c @@ -41,7 +41,7 @@ #include "drivers/io_impl.h" #include "drivers/nvic.h" #include "drivers/time.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/dma.h" #include "drivers/light_led.h" diff --git a/src/platform/STM32/serial_uart_hal.c b/src/platform/STM32/serial_uart_hal.c index f319bce78c..862bdb68d6 100644 --- a/src/platform/STM32/serial_uart_hal.c +++ b/src/platform/STM32/serial_uart_hal.c @@ -42,7 +42,7 @@ #include "drivers/nvic.h" #include "drivers/inverter.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/serial_uart_stdperiph.c b/src/platform/STM32/serial_uart_stdperiph.c index b65275c427..b028371dff 100644 --- a/src/platform/STM32/serial_uart_stdperiph.c +++ b/src/platform/STM32/serial_uart_stdperiph.c @@ -42,7 +42,7 @@ #include "common/utils.h" #include "drivers/inverter.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/serial_uart_stm32f4xx.c b/src/platform/STM32/serial_uart_stm32f4xx.c index d289a1e671..a2ab2fc714 100644 --- a/src/platform/STM32/serial_uart_stm32f4xx.c +++ b/src/platform/STM32/serial_uart_stm32f4xx.c @@ -35,7 +35,7 @@ #include "drivers/io.h" #include "drivers/dma.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/serial_uart_stm32f7xx.c b/src/platform/STM32/serial_uart_stm32f7xx.c index 3205cf8620..ad67a92f0e 100644 --- a/src/platform/STM32/serial_uart_stm32f7xx.c +++ b/src/platform/STM32/serial_uart_stm32f7xx.c @@ -33,7 +33,7 @@ #include "drivers/dma.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/serial_uart_stm32g4xx.c b/src/platform/STM32/serial_uart_stm32g4xx.c index 211e6f41fa..2042df06dd 100644 --- a/src/platform/STM32/serial_uart_stm32g4xx.c +++ b/src/platform/STM32/serial_uart_stm32g4xx.c @@ -31,7 +31,7 @@ #include "drivers/dma.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/serial_uart_stm32h7xx.c b/src/platform/STM32/serial_uart_stm32h7xx.c index bbed4b6ed0..898fdf0937 100644 --- a/src/platform/STM32/serial_uart_stm32h7xx.c +++ b/src/platform/STM32/serial_uart_stm32h7xx.c @@ -33,7 +33,7 @@ #include "drivers/dma.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/serial.h" #include "drivers/serial_uart.h" diff --git a/src/platform/STM32/timer_hal.c b/src/platform/STM32/timer_hal.c index c9e9180f6c..e4ea1a413a 100644 --- a/src/platform/STM32/timer_hal.c +++ b/src/platform/STM32/timer_hal.c @@ -36,7 +36,7 @@ #include "drivers/io.h" #include "drivers/dma.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/timer_impl.h" diff --git a/src/platform/STM32/timer_stdperiph.c b/src/platform/STM32/timer_stdperiph.c index 8e0c2bc95a..c5ecefba24 100644 --- a/src/platform/STM32/timer_stdperiph.c +++ b/src/platform/STM32/timer_stdperiph.c @@ -34,12 +34,13 @@ #include "drivers/nvic.h" #include "drivers/io.h" -#include "drivers/rcc.h" #include "drivers/system.h" #include "drivers/timer.h" #include "drivers/timer_impl.h" +#include "platform/rcc.h" + #define TIM_N(n) (1 << (n)) /* diff --git a/src/platform/STM32/timer_stm32f4xx.c b/src/platform/STM32/timer_stm32f4xx.c index 4bc5b1d2db..ed193e64f7 100644 --- a/src/platform/STM32/timer_stm32f4xx.c +++ b/src/platform/STM32/timer_stm32f4xx.c @@ -29,7 +29,7 @@ #include "timer_def.h" #include "stm32f4xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/STM32/timer_stm32f7xx.c b/src/platform/STM32/timer_stm32f7xx.c index 464873c89c..92f958929d 100644 --- a/src/platform/STM32/timer_stm32f7xx.c +++ b/src/platform/STM32/timer_stm32f7xx.c @@ -29,7 +29,7 @@ #include "timer_def.h" #include "stm32f7xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/STM32/timer_stm32g4xx.c b/src/platform/STM32/timer_stm32g4xx.c index e93f79fbe2..c2256e6c67 100644 --- a/src/platform/STM32/timer_stm32g4xx.c +++ b/src/platform/STM32/timer_stm32g4xx.c @@ -29,7 +29,7 @@ #include "timer_def.h" #include "stm32g4xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/STM32/timer_stm32h5xx.c b/src/platform/STM32/timer_stm32h5xx.c index e4d06b9335..c9edec4ba6 100644 --- a/src/platform/STM32/timer_stm32h5xx.c +++ b/src/platform/STM32/timer_stm32h5xx.c @@ -30,7 +30,7 @@ #include "timer_def.h" #include "stm32h5xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/STM32/timer_stm32h7xx.c b/src/platform/STM32/timer_stm32h7xx.c index 3462e9d7f2..4fa37a0423 100644 --- a/src/platform/STM32/timer_stm32h7xx.c +++ b/src/platform/STM32/timer_stm32h7xx.c @@ -29,7 +29,7 @@ #include "timer_def.h" #include "stm32h7xx.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" const timerDef_t timerDefinitions[HARDWARE_TIMER_DEFINITION_COUNT] = { diff --git a/src/platform/STM32/transponder_ir_io_hal.c b/src/platform/STM32/transponder_ir_io_hal.c index 1f3f203407..51ae36da97 100644 --- a/src/platform/STM32/transponder_ir_io_hal.c +++ b/src/platform/STM32/transponder_ir_io_hal.c @@ -30,7 +30,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/transponder_ir_arcitimer.h" #include "drivers/transponder_ir_erlt.h" diff --git a/src/platform/STM32/transponder_ir_io_stdperiph.c b/src/platform/STM32/transponder_ir_io_stdperiph.c index 0d4170cc0f..03d6c735c0 100644 --- a/src/platform/STM32/transponder_ir_io_stdperiph.c +++ b/src/platform/STM32/transponder_ir_io_stdperiph.c @@ -30,7 +30,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/timer.h" #include "drivers/transponder_ir_arcitimer.h" #include "drivers/transponder_ir_erlt.h" diff --git a/src/main/drivers/bus_i2c_config.c b/src/platform/common/stm32/bus_i2c_pinconfig.c similarity index 89% rename from src/main/drivers/bus_i2c_config.c rename to src/platform/common/stm32/bus_i2c_pinconfig.c index 4cf78c03ba..dfa1147c7d 100644 --- a/src/main/drivers/bus_i2c_config.c +++ b/src/platform/common/stm32/bus_i2c_pinconfig.c @@ -39,7 +39,7 @@ #include "pg/bus_i2c.h" -void i2cHardwareConfigure(const i2cConfig_t *i2cConfig) +void i2cPinConfigure(const i2cConfig_t *i2cConfig) { for (int index = 0 ; index < I2CDEV_COUNT ; index++) { const i2cHardware_t *hardware = &i2cHardware[index]; @@ -56,13 +56,13 @@ void i2cHardwareConfigure(const i2cConfig_t *i2cConfig) for (int pindex = 0 ; pindex < I2C_PIN_SEL_MAX ; pindex++) { if (i2cConfig[device].ioTagScl == hardware->sclPins[pindex].ioTag) { pDev->scl = IOGetByTag(i2cConfig[device].ioTagScl); -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN pDev->sclAF = hardware->sclPins[pindex].af; #endif } if (i2cConfig[device].ioTagSda == hardware->sdaPins[pindex].ioTag) { pDev->sda = IOGetByTag(i2cConfig[device].ioTagSda); -#if defined(STM32F4) || defined(STM32H7) || defined(STM32G4) || defined(AT32F4) || defined(APM32F4) +#if I2C_TRAIT_AF_PIN pDev->sdaAF = hardware->sdaPins[pindex].af; #endif } diff --git a/src/platform/common/stm32/bus_spi_pinconfig.c b/src/platform/common/stm32/bus_spi_pinconfig.c index 59c68b214a..52d2d456c2 100644 --- a/src/platform/common/stm32/bus_spi_pinconfig.c +++ b/src/platform/common/stm32/bus_spi_pinconfig.c @@ -33,7 +33,7 @@ #include "drivers/dma.h" #include "drivers/exti.h" #include "drivers/io.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "pg/bus_spi.h" @@ -348,21 +348,20 @@ const spiHardware_t spiHardware[] = { .device = SPIDEV_1, .reg = SPI1, .sckPins = { - { DEFIO_TAG_E(PA5) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PB3) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PE13),GPIO_MUX_4}, + { DEFIO_TAG_E(PA5), GPIO_MUX_5}, + { DEFIO_TAG_E(PB3), GPIO_MUX_5}, + { DEFIO_TAG_E(PE13), GPIO_MUX_4}, }, .misoPins = { - { DEFIO_TAG_E(PA6) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PB4) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PE14),GPIO_MUX_4} + { DEFIO_TAG_E(PA6), GPIO_MUX_5}, + { DEFIO_TAG_E(PB4), GPIO_MUX_5}, + { DEFIO_TAG_E(PE14), GPIO_MUX_4} }, .mosiPins = { - { DEFIO_TAG_E(PA7) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PB5) ,GPIO_MUX_5}, - { DEFIO_TAG_E(PE15),GPIO_MUX_4}, + { DEFIO_TAG_E(PA7), GPIO_MUX_5}, + { DEFIO_TAG_E(PB5), GPIO_MUX_5}, + { DEFIO_TAG_E(PE15), GPIO_MUX_4}, }, - .af= 0x00, .rcc = RCC_APB2(SPI1), }, { @@ -370,7 +369,7 @@ const spiHardware_t spiHardware[] = { .reg = SPI2, .sckPins = { { DEFIO_TAG_E(PB10), GPIO_MUX_5}, - { DEFIO_TAG_E(PB13) ,GPIO_MUX_5}, + { DEFIO_TAG_E(PB13), GPIO_MUX_5}, { DEFIO_TAG_E(PC7), GPIO_MUX_5}, { DEFIO_TAG_E(PD1), GPIO_MUX_6}, @@ -387,7 +386,6 @@ const spiHardware_t spiHardware[] = { { DEFIO_TAG_E(PC3), GPIO_MUX_5}, { DEFIO_TAG_E(PD4), GPIO_MUX_6}, }, - .af= 0x00, .rcc = RCC_APB1(SPI2), }, { @@ -409,7 +407,6 @@ const spiHardware_t spiHardware[] = { { DEFIO_TAG_E(PC12), GPIO_MUX_6}, { DEFIO_TAG_E(PD0), GPIO_MUX_6}, }, - .af= 0x00, .rcc = RCC_APB1(SPI3), }, { @@ -428,7 +425,6 @@ const spiHardware_t spiHardware[] = { { DEFIO_TAG_E(PA1), GPIO_MUX_5}, { DEFIO_TAG_E(PB9), GPIO_MUX_6}, }, - .af= 0x00, .rcc = RCC_APB2(SPI4), }, #endif @@ -505,19 +501,19 @@ void spiPinConfigure(const spiPinConfig_t *pConfig) for (int pindex = 0 ; pindex < MAX_SPI_PIN_SEL ; pindex++) { if (pConfig[device].ioTagSck == hw->sckPins[pindex].pin) { pDev->sck = hw->sckPins[pindex].pin; -#if defined(USE_PIN_AF) +#if SPI_TRAIT_AF_PIN pDev->sckAF = hw->sckPins[pindex].af; #endif } if (pConfig[device].ioTagMiso == hw->misoPins[pindex].pin) { pDev->miso = hw->misoPins[pindex].pin; -#if defined(USE_PIN_AF) +#if SPI_TRAIT_AF_PIN pDev->misoAF = hw->misoPins[pindex].af; #endif } if (pConfig[device].ioTagMosi == hw->mosiPins[pindex].pin) { pDev->mosi = hw->mosiPins[pindex].pin; -#if defined(USE_PIN_AF) +#if SPI_TRAIT_AF_PIN pDev->mosiAF = hw->mosiPins[pindex].af; #endif } @@ -525,7 +521,7 @@ void spiPinConfigure(const spiPinConfig_t *pConfig) if (pDev->sck && pDev->miso && pDev->mosi) { pDev->dev = hw->reg; -#if !defined(USE_PIN_AF) +#if SPI_TRAIT_AF_PORT pDev->af = hw->af; #endif pDev->rcc = hw->rcc; diff --git a/src/platform/common/stm32/io_impl.c b/src/platform/common/stm32/io_impl.c index c2a98ad40f..a7fabbd3f8 100644 --- a/src/platform/common/stm32/io_impl.c +++ b/src/platform/common/stm32/io_impl.c @@ -76,3 +76,36 @@ int IO_GPIOPortIdx(IO_t io) } return (((size_t)IO_GPIO(io) - GPIOA_BASE) >> 10); } + +#if defined(STM32F4) || defined(APM32F4) +int IO_EXTI_PortSourceGPIO(IO_t io) +{ + return IO_GPIOPortIdx(io); +} +#endif + +int IO_GPIO_PortSource(IO_t io) +{ + return IO_GPIOPortIdx(io); +} + +// zero based pin index +int IO_GPIOPinIdx(IO_t io) +{ + if (!io) { + return -1; + } + return 31 - __builtin_clz(IO_Pin(io)); +} + +#if defined(STM32F4) || defined(APM32F4) +int IO_EXTI_PinSource(IO_t io) +{ + return IO_GPIOPinIdx(io); +} +#endif + +int IO_GPIO_PinSource(IO_t io) +{ + return IO_GPIOPinIdx(io); +} diff --git a/src/main/drivers/rcc.h b/src/platform/common/stm32/platform/rcc.h similarity index 99% rename from src/main/drivers/rcc.h rename to src/platform/common/stm32/platform/rcc.h index cdd2e3d1dd..69641b5e2d 100644 --- a/src/main/drivers/rcc.h +++ b/src/platform/common/stm32/platform/rcc.h @@ -20,7 +20,7 @@ #pragma once -#include "rcc_types.h" +#include "platform/rcc_types.h" enum rcc_reg { RCC_EMPTY = 0, // make sure that default value (0) does not enable anything diff --git a/src/main/drivers/rcc_types.h b/src/platform/common/stm32/platform/rcc_types.h similarity index 100% rename from src/main/drivers/rcc_types.h rename to src/platform/common/stm32/platform/rcc_types.h diff --git a/src/platform/common/stm32/pwm_output_dshot_shared.c b/src/platform/common/stm32/pwm_output_dshot_shared.c index ccf2ab661d..1bf57ee98d 100644 --- a/src/platform/common/stm32/pwm_output_dshot_shared.c +++ b/src/platform/common/stm32/pwm_output_dshot_shared.c @@ -33,7 +33,7 @@ #include "drivers/dma_reqmap.h" #include "drivers/io.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/time.h" #include "drivers/timer.h" #if defined(STM32F4) diff --git a/src/platform/common/stm32/serial_uart_hw.c b/src/platform/common/stm32/serial_uart_hw.c index 74e32147cf..1103a80db6 100644 --- a/src/platform/common/stm32/serial_uart_hw.c +++ b/src/platform/common/stm32/serial_uart_hw.c @@ -33,7 +33,7 @@ #include "build/build_config.h" #include "drivers/nvic.h" -#include "drivers/rcc.h" +#include "platform/rcc.h" #include "drivers/inverter.h" #include "drivers/serial.h" #include "drivers/serial_impl.h" diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h index dd03dce802..8f59e69f76 100644 --- a/src/test/unit/platform.h +++ b/src/test/unit/platform.h @@ -124,6 +124,8 @@ typedef struct } ADC_TypeDef; #define SPIDEV_COUNT 0 +#define I2CDEV_COUNT 0 + #define WS2811_DMA_TC_FLAG (void *)1 #define WS2811_DMA_HANDLER_IDENTIFER 0 #define NVIC_PriorityGroup_2 0x500 diff --git a/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h b/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h index b822be69bf..954add5c7d 100644 --- a/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h +++ b/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h @@ -1,5 +1,5 @@ #define I2CDEV_2 (1) int i2cConfig(int); -void i2cHardwareConfigure(int); +void i2cPinConfigure(int); void i2cInit(int);