mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-26 01:35:35 +03:00
Merge remote-tracking branch 'origin/development' into dzikuvx-yaw-handling-cleanup
This commit is contained in:
commit
aa9ae4bf6e
84 changed files with 455320 additions and 240 deletions
169
Makefile
169
Makefile
|
@ -11,6 +11,11 @@
|
|||
#
|
||||
###############################################################################
|
||||
|
||||
# Root directory
|
||||
ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
|
||||
|
||||
# developer preferences, edit these at will, they'll be gitignored
|
||||
-include $(ROOT)/make/local.mk
|
||||
|
||||
# Things that the user might override on the commandline
|
||||
#
|
||||
|
@ -24,6 +29,8 @@ OPTIONS ?=
|
|||
# Debugger optons, must be empty or GDB
|
||||
DEBUG ?=
|
||||
|
||||
SEMIHOSTING ?=
|
||||
|
||||
# Build suffix
|
||||
BUILD_SUFFIX ?=
|
||||
|
||||
|
@ -60,7 +67,6 @@ endif
|
|||
FORKNAME = inav
|
||||
|
||||
# Working directories
|
||||
ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST))))
|
||||
SRC_DIR := $(ROOT)/src/main
|
||||
OBJECT_DIR := $(ROOT)/obj/main
|
||||
BIN_DIR := $(ROOT)/obj
|
||||
|
@ -72,9 +78,6 @@ LINKER_DIR := $(ROOT)/src/main/target/link
|
|||
# import macros common to all supported build systems
|
||||
include $(ROOT)/make/system-id.mk
|
||||
|
||||
# developer preferences, edit these at will, they'll be gitignored
|
||||
-include $(ROOT)/make/local.mk
|
||||
|
||||
# default xtal value for F4 targets
|
||||
HSE_VALUE = 8000000
|
||||
MHZ_VALUE ?=
|
||||
|
@ -82,59 +85,7 @@ MHZ_VALUE ?=
|
|||
# used for turning on features like VCP and SDCARD
|
||||
FEATURES =
|
||||
|
||||
ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
|
||||
|
||||
VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
|
||||
VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
|
||||
VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
|
||||
VALID_TARGETS := $(sort $(VALID_TARGETS))
|
||||
|
||||
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
|
||||
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
|
||||
STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) )
|
||||
|
||||
ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
|
||||
BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
|
||||
else
|
||||
BASE_TARGET := $(TARGET)
|
||||
endif
|
||||
|
||||
# silently ignore if the file is not present. Allows for target specific.
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
||||
|
||||
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS)
|
||||
F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)
|
||||
|
||||
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
||||
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
|
||||
endif
|
||||
|
||||
ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
|
||||
$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?)
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
TARGET_MCU := STM32F3
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS)))
|
||||
TARGET_MCU := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS)))
|
||||
TARGET_MCU := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F1_TARGETS)))
|
||||
TARGET_MCU := STM32F1
|
||||
else
|
||||
$(error Unknown target MCU specified.)
|
||||
endif
|
||||
|
||||
GROUP_1_TARGETS := ALIENFLIGHTF3 ALIENFLIGHTF4 AIRHEROF3 AIRHEROF3_QUAD COLIBRI_RACE LUX_RACE SPARKY REVO SPARKY2 COLIBRI KISSFC FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD
|
||||
GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX
|
||||
GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
|
||||
GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7 ALIENFLIGHTNGF7 PIXRACER YUPIF4 YUPIF4MINI YUPIF4R2 YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX
|
||||
GROUP_5_TARGETS := ASGARD32F7 CHEBUZZF3 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
|
||||
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
|
||||
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV KROOZX MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
|
||||
GROUP_8_TARGETS := MATEKF765
|
||||
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS))
|
||||
include $(ROOT)/make/targets.mk
|
||||
|
||||
REVISION = $(shell git rev-parse --short HEAD)
|
||||
|
||||
|
@ -158,7 +109,8 @@ VPATH := $(VPATH):$(ROOT)/make
|
|||
CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
|
||||
|
||||
# start specific includes
|
||||
include $(ROOT)/make/mcu/$(TARGET_MCU).mk
|
||||
include $(ROOT)/make/mcu/STM32.mk
|
||||
include $(ROOT)/make/mcu/$(TARGET_MCU_GROUP).mk
|
||||
|
||||
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
|
||||
ifeq ($(FLASH_SIZE),)
|
||||
|
@ -171,7 +123,7 @@ endif
|
|||
|
||||
# Configure devide and target-specific defines and compiler flags
|
||||
DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE)
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) -D$(TARGET)
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) -D$(TARGET_MCU_GROUP) -D$(TARGET)
|
||||
|
||||
ifneq ($(HSE_VALUE),)
|
||||
DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE)
|
||||
|
@ -230,6 +182,14 @@ OPTIMIZE = -Os
|
|||
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
|
||||
endif
|
||||
|
||||
ifneq ($(SEMIHOSTING),)
|
||||
SEMIHOSTING_CFLAGS = -DSEMIHOSTING
|
||||
SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon
|
||||
else
|
||||
SEMIHOSTING_CFLAGS =
|
||||
SEMIHOSTING_LDFLAGS =
|
||||
endif
|
||||
|
||||
DEBUG_FLAGS = -ggdb3 -DDEBUG
|
||||
|
||||
CFLAGS += $(ARCH_FLAGS) \
|
||||
|
@ -237,6 +197,7 @@ CFLAGS += $(ARCH_FLAGS) \
|
|||
$(addprefix -D,$(OPTIONS)) \
|
||||
$(addprefix -I,$(INCLUDE_DIRS)) \
|
||||
$(DEBUG_FLAGS) \
|
||||
$(SEMIHOSTING_CFLAGS) \
|
||||
-std=gnu99 \
|
||||
-Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \
|
||||
-Wstrict-prototypes \
|
||||
|
@ -267,6 +228,7 @@ LDFLAGS = -lm \
|
|||
$(ARCH_FLAGS) \
|
||||
$(LTO_FLAGS) \
|
||||
$(DEBUG_FLAGS) \
|
||||
$(SEMIHOSTING_LDFLAGS) \
|
||||
-static \
|
||||
-Wl,-gc-sections,-Map,$(TARGET_MAP) \
|
||||
-Wl,-L$(LINKER_DIR) \
|
||||
|
@ -307,41 +269,16 @@ TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
|||
|
||||
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
||||
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
||||
CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP)
|
||||
CLEAN_ARTIFACTS += $(TARGET_ELF)
|
||||
CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP)
|
||||
|
||||
include $(ROOT)/make/stamp.mk
|
||||
include $(ROOT)/make/settings.mk
|
||||
include $(ROOT)/make/svd.mk
|
||||
|
||||
# Make sure build date and revision is updated on every incremental build
|
||||
$(TARGET_OBJ_DIR)/build/version.o : $(TARGET_SRC)
|
||||
|
||||
# Settings generator
|
||||
.PHONY: .FORCE settings clean-settings
|
||||
UTILS_DIR = $(ROOT)/src/utils
|
||||
SETTINGS_GENERATOR = $(UTILS_DIR)/settings.rb
|
||||
BUILD_STAMP = $(UTILS_DIR)/build_stamp.rb
|
||||
STAMP = $(TARGET_OBJ_DIR)/build.stamp
|
||||
|
||||
GENERATED_SETTINGS = $(TARGET_OBJ_DIR)/settings_generated.h $(TARGET_OBJ_DIR)/settings_generated.c
|
||||
SETTINGS_FILE = $(SRC_DIR)/fc/settings.yaml
|
||||
GENERATED_FILES = $(GENERATED_SETTINGS)
|
||||
$(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP)
|
||||
|
||||
# Make sure the generated files are in the include path
|
||||
CFLAGS += -I$(TARGET_OBJ_DIR)
|
||||
|
||||
$(STAMP): .FORCE
|
||||
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP)
|
||||
|
||||
# Use a pattern rule, since they're different than normal rules.
|
||||
# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples
|
||||
%generated.h %generated.c:
|
||||
$(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)"
|
||||
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR)
|
||||
|
||||
settings-json:
|
||||
$(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json
|
||||
|
||||
clean-settings:
|
||||
$(V1) $(RM) $(GENERATED_SETTINGS)
|
||||
|
||||
# CFLAGS used for ASM generation. These can't include the LTO related options
|
||||
# since they prevent proper ASM generation. Since $(LTO_FLAGS) includes the
|
||||
# optization level, we have to add it back. -g is required to make interleaved
|
||||
|
@ -352,7 +289,7 @@ ASM_CFLAGS=-g $(OPTIMZE) $(filter-out $(LTO_FLAGS) -save-temps=obj, $(CFLAGS))
|
|||
# It would be nice to compute these lists, but that seems to be just beyond make.
|
||||
|
||||
$(TARGET_HEX): $(TARGET_ELF)
|
||||
$(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@
|
||||
$(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@
|
||||
|
||||
$(TARGET_BIN): $(TARGET_ELF)
|
||||
$(V0) $(OBJCOPY) -O binary $< $@
|
||||
|
@ -395,33 +332,6 @@ $(TOOLS_DIR):
|
|||
## all : Build all valid targets
|
||||
all: $(VALID_TARGETS)
|
||||
|
||||
## targets-group-1 : build some targets
|
||||
targets-group-1: $(GROUP_1_TARGETS)
|
||||
|
||||
## targets-group-2 : build some targets
|
||||
targets-group-2: $(GROUP_2_TARGETS)
|
||||
|
||||
## targets-group-3 : build some targets
|
||||
targets-group-3: $(GROUP_3_TARGETS)
|
||||
|
||||
## targets-group-4 : build some targets
|
||||
targets-group-4: $(GROUP_4_TARGETS)
|
||||
|
||||
## targets-group-5 : build some targets
|
||||
targets-group-5: $(GROUP_5_TARGETS)
|
||||
|
||||
## targets-group-6 : build some targets
|
||||
targets-group-6: $(GROUP_6_TARGETS)
|
||||
|
||||
## targets-group-7 : build some targets
|
||||
targets-group-7: $(GROUP_7_TARGETS)
|
||||
|
||||
## targets-group-8 : build some targets
|
||||
targets-group-8: $(GROUP_8_TARGETS)
|
||||
|
||||
## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3)
|
||||
targets-group-rest: $(GROUP_OTHER_TARGETS)
|
||||
|
||||
## targets-group-rest: build targets specified in release-targets list
|
||||
release: $(RELEASE_TARGETS)
|
||||
|
||||
|
@ -469,8 +379,9 @@ $(STFLASH_TARGETS) :
|
|||
|
||||
## st-flash : flash firmware (.bin) onto flight controller
|
||||
st-flash: $(TARGET_BIN)
|
||||
$(V0) st-flash --reset write $< 0x08000000
|
||||
$(V0) st-flash --reset write $< $(FLASH_ORIGIN)
|
||||
|
||||
elf: $(TARGET_ELF)
|
||||
binary: $(TARGET_BIN)
|
||||
hex: $(TARGET_HEX)
|
||||
|
||||
|
@ -502,22 +413,6 @@ help: Makefile
|
|||
$(V0) @echo ""
|
||||
$(V0) @sed -n 's/^## //p' $<
|
||||
|
||||
## targets : print a list of all valid target platforms (for consumption by scripts)
|
||||
targets:
|
||||
$(V0) @echo "Valid targets: $(VALID_TARGETS)"
|
||||
$(V0) @echo "Target: $(TARGET)"
|
||||
$(V0) @echo "Base target: $(BASE_TARGET)"
|
||||
$(V0) @echo "targets-group-1: $(GROUP_1_TARGETS)"
|
||||
$(V0) @echo "targets-group-2: $(GROUP_2_TARGETS)"
|
||||
$(V0) @echo "targets-group-3: $(GROUP_3_TARGETS)"
|
||||
$(V0) @echo "targets-group-4: $(GROUP_4_TARGETS)"
|
||||
$(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)"
|
||||
$(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)"
|
||||
$(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)"
|
||||
$(V0) @echo "targets-group-7: $(GROUP_8_TARGETS)"
|
||||
$(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)"
|
||||
$(V0) @echo "Release targets: $(RELEASE_TARGETS)"
|
||||
|
||||
## test : run the cleanflight test suite
|
||||
test:
|
||||
$(V0) cd src/test && $(MAKE) test
|
||||
|
@ -530,3 +425,7 @@ $(TARGET_OBJS) : Makefile | $(GENERATED_FILES) $(STAMP)
|
|||
|
||||
# include auto-generated dependencies
|
||||
-include $(TARGET_DEPS)
|
||||
|
||||
# Developer tools
|
||||
include $(ROOT)/make/openocd.mk
|
||||
include $(ROOT)/make/gdb.mk
|
||||
|
|
|
@ -29,7 +29,6 @@ doc_files=(
|
|||
'Migrating from baseflight.md'
|
||||
'Boards.md'
|
||||
'Board - AlienFlight.md'
|
||||
'Board - ChebuzzF3.md'
|
||||
'Board - ColibriRace.md'
|
||||
'Board - Motolab.md'
|
||||
'Board - Paris Air Hero 32.md'
|
||||
|
|
40381
dev/svd/STM32F303.svd
Normal file
40381
dev/svd/STM32F303.svd
Normal file
File diff suppressed because it is too large
Load diff
61681
dev/svd/STM32F405.svd
Normal file
61681
dev/svd/STM32F405.svd
Normal file
File diff suppressed because it is too large
Load diff
27110
dev/svd/STM32F411.svd
Normal file
27110
dev/svd/STM32F411.svd
Normal file
File diff suppressed because it is too large
Load diff
63121
dev/svd/STM32F427.svd
Normal file
63121
dev/svd/STM32F427.svd
Normal file
File diff suppressed because it is too large
Load diff
57155
dev/svd/STM32F446.svd
Normal file
57155
dev/svd/STM32F446.svd
Normal file
File diff suppressed because it is too large
Load diff
61861
dev/svd/STM32F7x2.svd
Normal file
61861
dev/svd/STM32F7x2.svd
Normal file
File diff suppressed because it is too large
Load diff
71136
dev/svd/STM32F7x5.svd
Normal file
71136
dev/svd/STM32F7x5.svd
Normal file
File diff suppressed because it is too large
Load diff
70681
dev/svd/STM32F7x6.svd
Normal file
70681
dev/svd/STM32F7x6.svd
Normal file
File diff suppressed because it is too large
Load diff
23
dev/vscode/launch.json
Normal file
23
dev/vscode/launch.json
Normal file
|
@ -0,0 +1,23 @@
|
|||
{
|
||||
// Use IntelliSense to learn about possible attributes.
|
||||
// Hover to view descriptions of existing attributes.
|
||||
// For more information, visit: https://go.microsoft.com/fwlink/?linkid=830387
|
||||
"version": "0.2.0",
|
||||
"configurations": [
|
||||
{
|
||||
"name": "Cortex Debug",
|
||||
"cwd": "${workspaceRoot}",
|
||||
"executable": "./obj/main/INAV_${config:TARGET}.elf",
|
||||
"request": "launch",
|
||||
"type": "cortex-debug",
|
||||
"servertype": "openocd",
|
||||
"device": "${config:TARGET}",
|
||||
"configFiles": [
|
||||
"./obj/main/${config:TARGET}/openocd.cfg"
|
||||
],
|
||||
"preLaunchCommands": ["monitor arm semihosting enable"],
|
||||
"preLaunchTask": "openocd-debug-prepare",
|
||||
"svdFile": "./obj/main/${config:TARGET}/svd.svd",
|
||||
}
|
||||
]
|
||||
}
|
70
dev/vscode/tasks.json
Normal file
70
dev/vscode/tasks.json
Normal file
|
@ -0,0 +1,70 @@
|
|||
{
|
||||
// See https://go.microsoft.com/fwlink/?LinkId=733558
|
||||
// for the documentation about the tasks.json format
|
||||
"version": "2.0.0",
|
||||
"options": {
|
||||
"env": {
|
||||
"TARGET": "${config:TARGET}",
|
||||
"SEMIHOSTING": "${config:SEMIHOSTING}"
|
||||
}
|
||||
},
|
||||
"tasks": [
|
||||
{
|
||||
"label": "hex",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["hex"],
|
||||
"problemMatcher": "$gcc",
|
||||
"group": {
|
||||
"kind": "build",
|
||||
"isDefault": true
|
||||
},
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "always",
|
||||
"focus": false,
|
||||
}
|
||||
},
|
||||
{
|
||||
"label": "elf",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["elf"],
|
||||
"problemMatcher": "$gcc",
|
||||
"group": "build",
|
||||
"presentation": {
|
||||
"echo": true,
|
||||
"reveal": "always",
|
||||
"focus": false,
|
||||
}
|
||||
},
|
||||
{
|
||||
"label": "openocd-flash",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["openocd-flash"],
|
||||
"dependsOn": "elf"
|
||||
},
|
||||
{
|
||||
"label": "clean",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["clean"],
|
||||
"problemMatcher": []
|
||||
},
|
||||
{
|
||||
"label": "svd",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["svd"],
|
||||
"problemMatcher": []
|
||||
},
|
||||
{
|
||||
"label": "openocd-cfg",
|
||||
"type": "shell",
|
||||
"command": "make", "args": ["openocd-cfg"],
|
||||
"problemMatcher": []
|
||||
},
|
||||
{
|
||||
"label": "openocd-debug-prepare",
|
||||
"type": "shell",
|
||||
"dependsOn": ["svd", "openocd-cfg", "openocd-flash"],
|
||||
"problemMatcher": []
|
||||
}
|
||||
]
|
||||
}
|
|
@ -58,7 +58,7 @@ The following parameters can be used to enable and configure this in the related
|
|||
|
||||
```
|
||||
// Define your esc hardware
|
||||
#if defined(STM32F3DISCOVERY) && !(defined(CHEBUZZF3))
|
||||
#if defined(STM32F3DISCOVERY)
|
||||
const escHardware_t escHardware[ESC_COUNT] = {
|
||||
{ GPIOD, 12 },
|
||||
{ GPIOD, 13 },
|
||||
|
|
|
@ -1,10 +1,3 @@
|
|||
# Board - ChebuzzF3
|
||||
|
||||
The ChebuzzF3 is a daugter board which connects to the bottom of an STM32F3Discovery board and provides pin headers and ports for various FC connections.
|
||||
|
||||
All connections were traced using a multimeter and then verified against the TauLabs source code using the revision linked.
|
||||
|
||||
https://github.com/TauLabs/TauLabs/blob/816760dec2a20db7fb9ec1a505add240e696c31f/flight/targets/flyingf3/board-info/board_hw_defs.c
|
||||
|
||||
## Connections
|
||||
|
||||
|
|
|
@ -50,7 +50,7 @@ from another BEC. Just ensure that the GROUND is the same for all BEC outputs a
|
|||
|
||||
| Target | Pin | LED Strip | Signal |
|
||||
| --------------------- | ---- | --------- | -------|
|
||||
| ChebuzzF3/F3Discovery | PB8 | Data In | PB8 |
|
||||
| F3Discovery | PB8 | Data In | PB8 |
|
||||
| Sparky | PWM5 | Data In | PA6 |
|
||||
|
||||
If you have LEDs that are intermittent, flicker or show the wrong colors then drop the VIN to less than 4.7v, e.g. by using an inline
|
||||
|
|
|
@ -1,106 +1,160 @@
|
|||
# Hardware debugging
|
||||
# Hardware Debugging
|
||||
|
||||
The code can be compiled with debugging information, you can then upload a debug version to a board via a JLink/St-Link debug adapter and step through the code in your IDE.
|
||||
Hardware debugging allows debugging the firmware with GDB, including most of its
|
||||
features that you can find while debugging software for a computer like setting
|
||||
breakpoins or printing variables or stepping through the code.
|
||||
|
||||
More information about the necessary hardware and setting up the eclipse IDE can be found [here](Hardware Debugging in Eclipse.md)
|
||||
Additionally, firmware can also be flashed directly either from the IDE or from GDB,
|
||||
significanly reducing the time required for the compile/flash/test cycle.
|
||||
|
||||
A guide for visual studio can be found here:
|
||||
http://visualgdb.com/tutorials/arm/st-link/
|
||||
## Required Hardware
|
||||
|
||||
This video is also helpful in understanding the proces:
|
||||
https://www.youtube.com/watch?v=kjvqySyNw20
|
||||
Although more complex and expensive solutions exists, an STLink V2 clone will let you
|
||||
use all the features of hardware debugging. They can be purchased on any of the typical
|
||||
Chinese sites.
|
||||
|
||||
## Hardware
|
||||
[ST Link V2 Clone](https://inavflight.com/shop/s/bg/1177014)
|
||||
[Original ST Link V2](https://inavflight.com/shop/s/bg/1099119)
|
||||
|
||||
Various debugging hardware solutions exist, the Segger J-Link clones are cheap and are known to work on Windows.
|
||||
Additionally, most nucleo boards from ST come with a brekable part that contains an
|
||||
STLink V2.1 or V3. These can also be used to debug an FC, but can be more difficult to
|
||||
source.
|
||||
|
||||
### J-Link devices
|
||||
To connect it a flight controller, you need to locate the SWDIO and SWCLK pins from the
|
||||
MCU. These correspond to PA13 (SWDIO) and PA14 (SWCLK). Be aware that not all manufacturers
|
||||
break out these pins, but a lot of them put them in small pads available somewhere.
|
||||
Connect SWDIO, SWCLK and GND from the FC to pins with the FC
|
||||
|
||||
Segger make excellent debuggers and debug software.
|
||||
TODO: Add pictures of several FCs with SWDIO and SWCLK highlighted.
|
||||
|
||||
The Segger J-Link GDB server can be obtained from here.
|
||||
## Required software
|
||||
|
||||
http://www.segger.com/jlink-software.html
|
||||
Besides an ARM toolchain, [OpenOCD](http://openocd.org) is required. Note that at the
|
||||
time of this writing, OpenOCD hasn't had a release in almost 3 years, so you might
|
||||
need to look for unofficial releases or compile from source.
|
||||
|
||||
#### Segger J-Link EDU EDU version, for hobbyists and educational use.
|
||||
[stlink](https://github.com/texane/stlink), while not strictly required, can be handy
|
||||
for quickly testing the SWD connection or flashing or erasing. To avoid ambiguities
|
||||
between the hardware and the software, the former will be referred as `ST Link` while
|
||||
we'll use `stlink` for the latter.
|
||||
|
||||

|
||||
Please, follow the installation instructions for your operating system.
|
||||
|
||||
https://www.segger.com/j-link-edu.html
|
||||
### Windows
|
||||
|
||||
#### USB-MiniJTAG J-Link JTAG/SWD Debugger/Emulator
|
||||
Install the Windows Subsystem for Linux, then follow the Linux instructions.
|
||||
|
||||
http://www.hotmcu.com/usbminijtag-jlink-jtagswd-debuggeremula%E2%80%8Btor-p-29.html?cPath=3_25&zenid=fdefvpnod186umrhsek225dc10
|
||||
### macOS
|
||||
|
||||

|
||||
Install [Homebrew](https://brew.sh) (a package manager) first.
|
||||
|
||||
##### ARM-JTAG-20-10 adapter
|
||||
To install OpenOCD type `brew install open-ocd --HEAD` in a terminal. Note the `--HEAD`
|
||||
command line switch.
|
||||
|
||||
https://www.olimex.com/Products/ARM/JTAG/ARM-JTAG-20-10/
|
||||
http://uk.farnell.com/jsp/search/productdetail.jsp?sku=2144328
|
||||
For stlink, use `brew install stlink`.
|
||||
|
||||

|
||||
### Linux
|
||||
|
||||
#### CJMCU-STM32 Singlechip Development Board Jlink Downloader Jlink ARM Programmer
|
||||
Install [Homebrew for Linux](https://docs.brew.sh/Homebrew-on-Linux), since versions
|
||||
provided by your distro's package manager might be out of date. Homebrew can cohexist
|
||||
with your existing package manager without any problems.
|
||||
|
||||

|
||||
Then, follow the same instructions for installing OpenOCD and stlink for macOS.
|
||||
|
||||

|
||||
## Hardware setup
|
||||
|
||||
http://www.goodluckbuy.com/cjmcu-stm32-singlechip-development-board-jlink-downloader-jlink-arm-programmer.html
|
||||
Connect SWDIO and SWCLK from the FC to pins with the same label on the ST Link. You must
|
||||
also connect one of the GND from FC to any of the GND pins to the ST Link. Note the
|
||||
following caveats:
|
||||
|
||||
- There are several ST Link clone types with different pinouts. Pay attention to the pin
|
||||
labels.
|
||||
- In some ST Link clones, some GND pins are actually floating and not connected to
|
||||
- anything. Use a multimeter to check the GND pins and use any of the valid ones.
|
||||
- Even if you're powering everything from the same computer, make sure to directly connect
|
||||
the grounds from the FC to the ST Link. Some FC/stlink combinations have a 0.1-0.2V
|
||||
difference between their grounds and if you don't connect them, stlink won't work.
|
||||
|
||||
### STLink V2 devices
|
||||
The FC can be powered by any power source that it supports (battery, USB, etc...), just
|
||||
make sure to not connect power from the ST Link (the pins labelled as 3.3V and 5V) to the
|
||||
FC if something else is powering it.
|
||||
|
||||
STLink V2 devices can be used too, via OpenOCD.
|
||||
Once you're wired everything, test the connections with a DMM before applying power. Then
|
||||
power both the FC and the stlink (the order doesn't matter) and run `st-info --probe`
|
||||
You should see something like:
|
||||
|
||||
#### CEPark STLink V2
|
||||
|
||||

|
||||
|
||||
http://www.goodluckbuy.com/cepark-stlink-st-link-v2-emulator-programmer-stm8-stm32-downloader.html
|
||||
```
|
||||
Found 1 stlink programmers
|
||||
serial: 0d0d09002a12354d314b4e00
|
||||
openocd: "\x0d\x0d\x09\x00\x2a\x12\x35\x4d\x31\x4b\x4e\x00"
|
||||
flash: 524288 (pagesize: 16384)
|
||||
sram: 131072
|
||||
chipid: 0x0431
|
||||
descr: F4 device (low power) - stm32f411re
|
||||
```
|
||||
|
||||
## Compilation options
|
||||
|
||||
use `DEBUG=GDB` make argument.
|
||||
INAV is compiled with debug symbols by default, since they're only stored in the locally
|
||||
generated `.elf` file and they never use flash space in the target. However, some
|
||||
optimizations like inlining and LTO might rearrange some sections of the code enough
|
||||
to interfere with debugging. All compile time optimizations can be disabled by
|
||||
using `DEBUG=GDB` when calling `make`.
|
||||
|
||||
You may find that if you compile all the files with debug information on that the program is too big to fit on the target device. If this happens you have some options:
|
||||
You may find that if you compile all the files without optimizations the program might
|
||||
too big to fit on the target device. In that case, one of the possible solutions is
|
||||
compiling all files with optimization (`make clean`, `make ...`) first, then re-save
|
||||
or `touch` the files you want to be able to step though and then run `make DEBUG=GDB`.
|
||||
This will then re-compile the files you're interested in debugging with debugging symbols and you will get a smaller binary file which should then fit on the device.
|
||||
|
||||
* Compile all files without debug information (`make clean`, `make ...`), then re-save or `touch` the files you want to be able to step though and then run `make DEBUG=GDB`. This will then re-compile the files you're interested in debugging with debugging symbols and you will get a smaller binary file which should then fit on the device.
|
||||
* You could use a development board such as an EUSTM32F103RB, development boards often have more flash rom.
|
||||
## Debugging
|
||||
|
||||
## OSX
|
||||
To run a debug session, you will need two terminal windows. One will run OpenOCD, while
|
||||
the other one will run gdb.
|
||||
|
||||
### Install OpenOCD via Brew
|
||||
Although not strictly required, it is recommended to set the target you're working on
|
||||
in `make/local.mk` (create it if it doesn't exist), by adding a line like e.g.
|
||||
`TARGET ?= SOME_VALID_TARGET`. This way you won't need to specify the target name in
|
||||
all commands.
|
||||
|
||||
ruby -e "$(curl -fsSL https://raw.githubusercontent.com/Homebrew/install/master/install)"
|
||||
From one of the terminals, type `make openocd-run`. This will start OpenOCD and connect
|
||||
to the MCU. Leave OpenOCD running in this terminal.
|
||||
|
||||
brew install openocd
|
||||
From another terminal, type `make gdb-openocd`. This will compile the `.elf` binary for
|
||||
the current target and start `gdb`. From there you will usually want to execute the gdb
|
||||
`load` command first, which will flash the binary to the target. Once it finishes, start
|
||||
running it by executing the `continue` command.
|
||||
|
||||
### GDB debug server
|
||||
For conveniency, you can invoke `make gdb-openocd` with the environment variable `$LOAD`
|
||||
set to a non-empty string (e.g. `LOAD=1 make gdb-openocd`), which will run the `load`
|
||||
command and flash the target as soon as gdb connects to it.
|
||||
|
||||
#### J-Link
|
||||
From there on, you can use any gdb commands like `b` for setting breakpoints, `p` for
|
||||
printing, etc... Check a gdb tutorial for more details if you're not already familiar
|
||||
with it.
|
||||
|
||||
##### Windows
|
||||
### Rebuilding and reflashing
|
||||
|
||||
Run the Launch the J-Link GDB Server program and configure using UI.
|
||||
To rebuild, flash and rerun the binary after doing any modifications, recompile it
|
||||
with `make`, then press `control+c` to interrupt gdb. Halt the target by entering the
|
||||
gdb command `monitor reset halt` and then type `load` to flash it. gdb will notice the
|
||||
binary has changed and re-read the debug symbols. Then you can restart the firmware with
|
||||
`continue`. This way, you can very quickly flash, upload and test since neither OpenOCD
|
||||
nor gdb need to be restarted.
|
||||
|
||||
#### OpenOCD
|
||||
### ST Link versions
|
||||
|
||||
##### Windows
|
||||
|
||||
STM32F103 targets
|
||||
|
||||
"C:\Program Files (x86)\UTILS\openocd-0.8.0\bin-x64\openocd-x64-0.8.0.exe" -f interface/stlink-v2.cfg -f target/stm32f1x_stlink.cfg
|
||||
|
||||
STM32F30x targets
|
||||
|
||||
"C:\Program Files (x86)\UTILS\openocd-0.8.0\bin-x64\openocd-x64-0.8.0.exe" -f scripts\board\stm32f3discovery.cfg
|
||||
|
||||
##### OSX/Linux
|
||||
|
||||
STM32F30x targets
|
||||
|
||||
openocd -f /usr/share/openocd/scripts/board/stm32vldiscovery.cfg
|
||||
By default, the Makefiles will assume an ST Link v2, which is the version found in the
|
||||
popular and cheap clones. However, other versions are also supported. Just set the
|
||||
`STLINK` environment variable (either via command line or either via `local.mk`) to
|
||||
`1` or `2` or `2.1`, according to your hardware.
|
||||
|
||||
### Semihosting
|
||||
|
||||
Semihosting is an ARM feature that allows printing messages via the SWD connection.
|
||||
The logging framework inside INAV can output its messages via semihosting. To enable
|
||||
it, make sure you've deleted all generated files (e.g. `make clean`) and set the
|
||||
environment variable `$SEMIHOSTING` to a non-empty string, either via command line
|
||||
or via `local.mk`. Once you start the target, log messages will appear on the openocd
|
||||
terminal. Note that even with semihosting enabled, logging has be explicitely enabled
|
||||
via settings.
|
||||
|
|
Binary file not shown.
Before Width: | Height: | Size: 4.8 KiB |
Binary file not shown.
Before Width: | Height: | Size: 72 KiB |
Binary file not shown.
Before Width: | Height: | Size: 16 KiB |
|
@ -2,8 +2,6 @@
|
|||
|
||||
targets=("PUBLISHMETA=True" \
|
||||
"RUNTESTS=True" \
|
||||
"TARGET=CHEBUZZF3" \
|
||||
"TARGET=COLIBRI_RACE" \
|
||||
"TARGET=SPRACINGF3" \
|
||||
"TARGET=SPRACINGF3EVO" \
|
||||
"TARGET=LUX_RACE" \
|
||||
|
@ -11,7 +9,6 @@ targets=("PUBLISHMETA=True" \
|
|||
"TARGET=RMDO" \
|
||||
"TARGET=SPARKY" \
|
||||
"TARGET=STM32F3DISCOVERY" \
|
||||
"TARGET=ALIENFLIGHTF3"\
|
||||
"TARGET=RCEXPLORERF3" )
|
||||
#fake a travis build environment
|
||||
export TRAVIS_BUILD_NUMBER=$(date +%s)
|
||||
|
|
14
make/gdb.mk
Normal file
14
make/gdb.mk
Normal file
|
@ -0,0 +1,14 @@
|
|||
GDB ?= $(ARM_SDK_PREFIX)gdb
|
||||
GDB_REMOTE ?= localhost:3333
|
||||
|
||||
GDB_OPENOCD_INIT_CMDS ?=
|
||||
GDB_OPENOCD_INIT_CMDS += -ex "monitor reset halt"
|
||||
ifneq ($(LOAD),)
|
||||
GDB_OPENOCD_INIT_CMDS += -ex load
|
||||
endif
|
||||
ifneq ($(SEMIHOSTING),)
|
||||
GDB_OPENOCD_INIT_CMDS += -ex "monitor arm semihosting enable"
|
||||
endif
|
||||
|
||||
gdb-openocd: $(TARGET_ELF)
|
||||
$(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS)
|
1
make/mcu/STM32.mk
Normal file
1
make/mcu/STM32.mk
Normal file
|
@ -0,0 +1 @@
|
|||
FLASH_ORIGIN ?= 0x08000000
|
49
make/openocd.mk
Normal file
49
make/openocd.mk
Normal file
|
@ -0,0 +1,49 @@
|
|||
.PHONY: .FORCE openocd-cfg $(OPENOCD_CFG) openocd-run openocd-flash
|
||||
|
||||
OPENOCD_CFG ?= $(TARGET_OBJ_DIR)/openocd.cfg
|
||||
CLEAN_ARTIFACTS += $(OPENOCD_CFG)
|
||||
OPENOCD_CMD ?= openocd
|
||||
|
||||
STLINK ?= 2
|
||||
|
||||
ifeq ($(OPENOCD_INTERFACE),)
|
||||
ifeq ($(STLINK),1)
|
||||
OPENOCD_INTERFACE := stlink-v1
|
||||
else ifeq ($(STLINK),2)
|
||||
OPENOCD_INTERFACE := stlink-v2
|
||||
else ifeq ($(STLINK),2.1)
|
||||
OPENOCD_INTERFACE := stlink-v2-1
|
||||
else
|
||||
$(error Uknown ST Link version $(STLINK))
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(OPENOCD_TARGET),)
|
||||
ifeq ($(TARGET_MCU_GROUP),STM32F3)
|
||||
OPENOCD_TARGET := stm32f3x
|
||||
else ifeq ($(TARGET_MCU_GROUP),STM32F4)
|
||||
OPENOCD_TARGET := stm32f4x
|
||||
else ifeq ($(TARGET_MCU_GROUP),STM32F7)
|
||||
OPENOCD_TARGET := stm32f7x
|
||||
endif
|
||||
endif
|
||||
|
||||
ifeq ($(OPENOCD_TARGET),)
|
||||
$(warning Unknown OPENOCD_TARGET)
|
||||
endif
|
||||
|
||||
OPENOCD_CMDLINE := $(OPENOCD_CMD) -f $(OPENOCD_CFG)
|
||||
|
||||
openocd-cfg: $(OPENOCD_CFG)
|
||||
|
||||
$(OPENOCD_CFG): .FORCE
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo "source [find interface/$(OPENOCD_INTERFACE).cfg]" > $@
|
||||
$(V1) echo "source [find target/$(OPENOCD_TARGET).cfg]" >> $@
|
||||
|
||||
openocd-run: $(OPENOCD_CFG)
|
||||
$(OPENOCD_CMDLINE)
|
||||
|
||||
openocd-flash: $(TARGET_ELF) $(OPENOCD_CFG)
|
||||
(echo "halt; program $(realpath $<) verify reset" | nc -4 localhost 4444 2>/dev/null) || \
|
||||
$(OPENOCD_CMDLINE) -c "program $< verify reset exit"
|
|
@ -1,7 +1,7 @@
|
|||
RELEASE_TARGETS = AIRHEROF3 AIRHEROF3_QUAD
|
||||
|
||||
RELEASE_TARGETS += COLIBRI_RACE LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405
|
||||
RELEASE_TARGETS += QUANTON REVO SPARKY2 YUPIF4 YUPIF4R2 YUPIF4MINI KROOZX PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO ANYFCM7
|
||||
RELEASE_TARGETS += LUX_RACE FURYF3 FURYF3_SPIFLASH RCEXPLORERF3 RMDO SPARKY KFC32F3_INAV FALCORE MOTOLAB ANYFC BLUEJAYF4 COLIBRI F4BY DALRCF405
|
||||
RELEASE_TARGETS += QUANTON REVO SPARKY2 PIKOBLX CLRACINGF4AIR CLRACINGF4AIRV2 PIXRACER BEEROTORF4 ANYFCF7 ANYFCF7_EXTERNAL_BARO
|
||||
RELEASE_TARGETS += ALIENFLIGHTNGF7
|
||||
|
||||
RELEASE_TARGETS += BETAFLIGHTF3 BETAFLIGHTF4
|
||||
|
@ -15,7 +15,7 @@ RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4
|
|||
RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
|
||||
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
|
||||
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765
|
||||
RELEASE_TARGETS += MATEKF405 MATEKF405_SERVOS6 MATEKF405OSD MATEKF722 MATEKF722_HEXSERVO MATEKF722SE MATEKF722MINI MATEKF405SE MATEKF411 MATEKF411_SFTSRL2 MATEKF411_FD_SFTSRL MATEKF411_RSSI MATEKF411SE MATEKF765 MATEKF722PX
|
||||
|
||||
RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL
|
||||
|
||||
|
|
26
make/settings.mk
Normal file
26
make/settings.mk
Normal file
|
@ -0,0 +1,26 @@
|
|||
# Settings generator
|
||||
.PHONY: settings clean-settings
|
||||
UTILS_DIR = $(ROOT)/src/utils
|
||||
SETTINGS_GENERATOR = $(UTILS_DIR)/settings.rb
|
||||
|
||||
GENERATED_SETTINGS = $(TARGET_OBJ_DIR)/settings_generated.h $(TARGET_OBJ_DIR)/settings_generated.c
|
||||
SETTINGS_FILE = $(SRC_DIR)/fc/settings.yaml
|
||||
GENERATED_FILES = $(GENERATED_SETTINGS)
|
||||
$(GENERATED_SETTINGS): $(SETTINGS_GENERATOR) $(SETTINGS_FILE) $(STAMP)
|
||||
|
||||
CLEAN_ARTIFACTS += $(GENERATED_SETTINGS)
|
||||
|
||||
# Make sure the generated files are in the include path
|
||||
CFLAGS += -I$(TARGET_OBJ_DIR)
|
||||
|
||||
# Use a pattern rule, since they're different than normal rules.
|
||||
# See https://www.gnu.org/software/make/manual/make.html#Pattern-Examples
|
||||
%generated.h %generated.c:
|
||||
$(V1) echo "settings.yaml -> settings_generated.h, settings_generated.c" "$(STDOUT)"
|
||||
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) -o $(TARGET_OBJ_DIR)
|
||||
|
||||
settings-json:
|
||||
$(V0) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(SETTINGS_GENERATOR) . $(SETTINGS_FILE) --json settings.json
|
||||
|
||||
clean-settings:
|
||||
$(V1) $(RM) $(GENERATED_SETTINGS)
|
|
@ -97,6 +97,7 @@ COMMON_SRC = \
|
|||
flight/servos.c \
|
||||
flight/wind_estimator.c \
|
||||
flight/gyroanalyse.c \
|
||||
flight/rpm_filter.c \
|
||||
io/beeper.c \
|
||||
io/esc_serialshot.c \
|
||||
io/frsky_osd.c \
|
||||
|
|
7
make/stamp.mk
Normal file
7
make/stamp.mk
Normal file
|
@ -0,0 +1,7 @@
|
|||
.PHONY: .FORCE
|
||||
|
||||
BUILD_STAMP = $(UTILS_DIR)/build_stamp.rb
|
||||
STAMP = $(TARGET_OBJ_DIR)/build.stamp
|
||||
|
||||
$(STAMP): .FORCE
|
||||
$(V1) CPP_PATH="$(ARM_SDK_DIR)/bin" CFLAGS="$(CFLAGS)" TARGET=$(TARGET) ruby $(BUILD_STAMP) $(SETTINGS_FILE) $(STAMP)
|
32
make/svd.mk
Normal file
32
make/svd.mk
Normal file
|
@ -0,0 +1,32 @@
|
|||
|
||||
SVDFILE := $(TARGET_OBJ_DIR)/svd.svd
|
||||
CLEAN_ARTIFACTS += $(SVDFILE)
|
||||
|
||||
.PHONY: $(SVDFILE)
|
||||
|
||||
ifeq ($(TARGET_MCU),STM32F303)
|
||||
SVD := STM32F303
|
||||
else ifeq ($(TARGET_MCU),STM32F405)
|
||||
SVD := STM32F405
|
||||
else ifeq ($(TARGET_MCU),STM32F411)
|
||||
SVD := STM32F411
|
||||
else ifeq ($(TARGET_MCU),STM32F427)
|
||||
SVD := STM32F427
|
||||
else ifeq ($(TARGET_MCU),STM32F446)
|
||||
SVD := STM32F446
|
||||
else ifeq ($(TARGET_MCU),STM32F7X2RE)
|
||||
SVD := STM32F7x2
|
||||
else ifeq ($(TARGET_MCU),STM32F7X5XE)
|
||||
SVD := STM32F7x5
|
||||
else ifeq ($(TARGET_MCU),STM32F7X5XG)
|
||||
SVD := STM32F7x5
|
||||
else ifeq ($(TARGET_MCU),STM32F7X5XI)
|
||||
SVD := STM32F7x5
|
||||
else ifeq ($(TARGET_MCU),STM32F7X6XG)
|
||||
SVD := STM32F7x6
|
||||
endif
|
||||
|
||||
svd: .FORCE $(SVDFILE)
|
||||
$(SVDFILE): $(ROOT)/dev/svd/$(SVD).svd
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) cat $< > $@
|
118
make/targets.mk
Normal file
118
make/targets.mk
Normal file
|
@ -0,0 +1,118 @@
|
|||
ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk)))))
|
||||
|
||||
VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))
|
||||
VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
|
||||
VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
|
||||
VALID_TARGETS := $(sort $(VALID_TARGETS))
|
||||
|
||||
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
|
||||
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
|
||||
STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) )
|
||||
|
||||
ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET))
|
||||
BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk)))))
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk
|
||||
else
|
||||
BASE_TARGET := $(TARGET)
|
||||
endif
|
||||
|
||||
# silently ignore if the file is not present. Allows for target specific.
|
||||
-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk
|
||||
|
||||
F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) $(F427_TARGETS) $(F446_TARGETS)
|
||||
F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS)
|
||||
|
||||
ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
||||
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?)
|
||||
endif
|
||||
|
||||
ifeq ($(filter $(TARGET),$(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),)
|
||||
$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F3, F405, F411, F427 or F7x. Have you prepared a valid target.mk?)
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
TARGET_MCU := STM32F303
|
||||
TARGET_MCU_GROUP := STM32F3
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F405_TARGETS)))
|
||||
TARGET_MCU := STM32F405
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
|
||||
TARGET_MCU := STM32F411
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS)))
|
||||
TARGET_MCU := STM32F427
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS)))
|
||||
TARGET_MCU := STM32F446
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X2RE_TARGETS)))
|
||||
TARGET_MCU := STM32F7X2RE
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XE_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XE
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XG_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XG
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XI_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XI
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X6XG_TARGETS)))
|
||||
TARGET_MCU := STM32F7X6XG
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else
|
||||
$(error Unknown target MCU specified.)
|
||||
endif
|
||||
|
||||
GROUP_1_TARGETS := AIRHEROF3 AIRHEROF3_QUAD LUX_RACE SPARKY REVO SPARKY2 COLIBRI FALCORE FF_F35_LIGHTNING FF_FORTINIF4 FF_PIKOF4 FF_PIKOF4OSD
|
||||
GROUP_2_TARGETS := SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO CLRACINGF4AIR CLRACINGF4AIRV2 BEEROTORF4 BETAFLIGHTF3 BETAFLIGHTF4 PIKOBLX
|
||||
GROUP_3_TARGETS := OMNIBUS AIRBOTF4 BLUEJAYF4 OMNIBUSF4 OMNIBUSF4PRO FIREWORKSV2 SPARKY2 MATEKF405 OMNIBUSF7 DYSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 OMNIBUSF7NXT OMNIBUSF7V2 ASGARD32F4
|
||||
GROUP_4_TARGETS := ANYFC ANYFCF7 ANYFCF7_EXTERNAL_BARO ALIENFLIGHTNGF7 PIXRACER YUPIF7 MATEKF405SE MATEKF411 MATEKF722 MATEKF405OSD MATEKF405_SERVOS6 NOX
|
||||
GROUP_5_TARGETS := ASGARD32F7 CLRACINGF4AIRV3 DALRCF405 DALRCF722DUAL DYSF4PROV2 F4BY FISHDRONEF4 FOXEERF405 FOXEERF722DUAL FRSKYF3 FRSKYF4 FURYF3 FURYF3_SPIFLASH FURYF4OSD
|
||||
GROUP_6_TARGETS := MAMBAF405 OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS AIKONF4
|
||||
GROUP_7_TARGETS := KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KFC32F3_INAV MATEKF411_RSSI MATEKF411_SFTSRL2 MATEKF722MINI MATEKF722SE MATEKF722_HEXSERVO
|
||||
GROUP_8_TARGETS := MATEKF765 MATEKF722PX
|
||||
GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS) $(GROUP_5_TARGETS) $(GROUP_6_TARGETS) $(GROUP_7_TARGETS) $(GROUP_8_TARGETS), $(VALID_TARGETS))
|
||||
|
||||
## targets-group-1 : build some targets
|
||||
targets-group-1: $(GROUP_1_TARGETS)
|
||||
|
||||
## targets-group-2 : build some targets
|
||||
targets-group-2: $(GROUP_2_TARGETS)
|
||||
|
||||
## targets-group-3 : build some targets
|
||||
targets-group-3: $(GROUP_3_TARGETS)
|
||||
|
||||
## targets-group-4 : build some targets
|
||||
targets-group-4: $(GROUP_4_TARGETS)
|
||||
|
||||
## targets-group-5 : build some targets
|
||||
targets-group-5: $(GROUP_5_TARGETS)
|
||||
|
||||
## targets-group-6 : build some targets
|
||||
targets-group-6: $(GROUP_6_TARGETS)
|
||||
|
||||
## targets-group-7 : build some targets
|
||||
targets-group-7: $(GROUP_7_TARGETS)
|
||||
|
||||
## targets-group-8 : build some targets
|
||||
targets-group-8: $(GROUP_8_TARGETS)
|
||||
|
||||
## targets-group-rest: build the rest of the targets (not listed in group 1, 2 or 3)
|
||||
targets-group-rest: $(GROUP_OTHER_TARGETS)
|
||||
|
||||
## targets : print a list of all valid target platforms (for consumption by scripts)
|
||||
targets:
|
||||
$(V0) @echo "Valid targets: $(VALID_TARGETS)"
|
||||
$(V0) @echo "Target: $(TARGET)"
|
||||
$(V0) @echo "Base target: $(BASE_TARGET)"
|
||||
$(V0) @echo "targets-group-1: $(GROUP_1_TARGETS)"
|
||||
$(V0) @echo "targets-group-2: $(GROUP_2_TARGETS)"
|
||||
$(V0) @echo "targets-group-3: $(GROUP_3_TARGETS)"
|
||||
$(V0) @echo "targets-group-4: $(GROUP_4_TARGETS)"
|
||||
$(V0) @echo "targets-group-5: $(GROUP_5_TARGETS)"
|
||||
$(V0) @echo "targets-group-6: $(GROUP_6_TARGETS)"
|
||||
$(V0) @echo "targets-group-7: $(GROUP_7_TARGETS)"
|
||||
$(V0) @echo "targets-group-8: $(GROUP_8_TARGETS)"
|
||||
$(V0) @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)"
|
||||
$(V0) @echo "Release targets: $(RELEASE_TARGETS)"
|
|
@ -58,6 +58,7 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/beeper.h"
|
||||
#include "io/gps.h"
|
||||
|
@ -1711,6 +1712,16 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw);
|
||||
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw);
|
||||
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitRollPitch", "%d", pidProfile()->axisAccelerationLimitRollPitch);
|
||||
#ifdef USE_RPM_FILTER
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_filter_enabled", "%d", rpmFilterConfig()->gyro_filter_enabled);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_harmonics", "%d", rpmFilterConfig()->gyro_harmonics);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_min_hz", "%d", rpmFilterConfig()->gyro_min_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_gyro_q", "%d", rpmFilterConfig()->gyro_q);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_filter_enabled", "%d", rpmFilterConfig()->dterm_filter_enabled);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_harmonics", "%d", rpmFilterConfig()->dterm_harmonics);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_min_hz", "%d", rpmFilterConfig()->dterm_min_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("rpm_dterm_q", "%d", rpmFilterConfig()->dterm_q);
|
||||
#endif
|
||||
default:
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -65,5 +65,7 @@ typedef enum {
|
|||
DEBUG_ACC,
|
||||
DEBUG_ITERM_RELAX,
|
||||
DEBUG_ERPM,
|
||||
DEBUG_RPM_FILTER,
|
||||
DEBUG_RPM_FREQ,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -16,7 +16,7 @@
|
|||
*/
|
||||
|
||||
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
|
||||
#define FC_VERSION_MINOR 3 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
|
||||
|
||||
#define STR_HELPER(x) #x
|
||||
|
|
|
@ -20,6 +20,10 @@
|
|||
#include <stdarg.h>
|
||||
#include <ctype.h>
|
||||
|
||||
#if defined(SEMIHOSTING)
|
||||
#include <stdio.h>
|
||||
#endif
|
||||
|
||||
#include "build/version.h"
|
||||
|
||||
#include "drivers/serial.h"
|
||||
|
@ -103,6 +107,18 @@ static void logPutcp(void *p, char ch)
|
|||
|
||||
static void logPrint(const char *buf, size_t size)
|
||||
{
|
||||
#if defined(SEMIHOSTING)
|
||||
static bool semihostingInitialized = false;
|
||||
extern void initialise_monitor_handles(void);
|
||||
|
||||
if (!semihostingInitialized) {
|
||||
initialise_monitor_handles();
|
||||
semihostingInitialized = true;
|
||||
}
|
||||
for (size_t ii = 0; ii < size; ii++) {
|
||||
fputc(buf[ii], stdout);
|
||||
}
|
||||
#endif
|
||||
if (logPort) {
|
||||
// Send data via UART (if configured & connected - a safeguard against zombie VCP)
|
||||
if (serialIsConnected(logPort)) {
|
||||
|
@ -121,7 +137,11 @@ static size_t logFormatPrefix(char *buf, const timeMs_t timeMs)
|
|||
|
||||
static bool logHasOutput(void)
|
||||
{
|
||||
#if defined(SEMIHOSTING)
|
||||
return true;
|
||||
#else
|
||||
return logPort || mspLogPort;
|
||||
#endif
|
||||
}
|
||||
|
||||
static bool logIsEnabled(logTopic_e topic, unsigned level)
|
||||
|
|
|
@ -109,7 +109,8 @@
|
|||
#define PG_GENERAL_SETTINGS 1019
|
||||
#define PG_GLOBAL_FUNCTIONS 1020
|
||||
#define PG_ESC_SENSOR_CONFIG 1021
|
||||
#define PG_INAV_END 1021
|
||||
#define PG_RPM_FILTER_CONFIG 1022
|
||||
#define PG_INAV_END 1022
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
//#define PG_OSD_FONT_CONFIG 2047
|
||||
|
|
348
src/main/drivers/barometer/barometer_bmp388.c
Normal file
348
src/main/drivers/barometer/barometer_bmp388.c
Normal file
|
@ -0,0 +1,348 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* BMP388 Driver author: Dominic Clifton
|
||||
* iNav port: Michel Pastor
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "build/build_config.h"
|
||||
#include "build/debug.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/log.h" // XXX
|
||||
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/barometer/barometer_bmp388.h"
|
||||
|
||||
#if defined(USE_BARO) && (defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388))
|
||||
|
||||
#define BMP388_I2C_ADDR (0x76) // same as BMP280/BMP180
|
||||
#define BMP388_DEFAULT_CHIP_ID (0x50) // from https://github.com/BoschSensortec/BMP3-Sensor-API/blob/master/bmp3_defs.h#L130
|
||||
|
||||
#define BMP388_CMD_REG (0x7E)
|
||||
#define BMP388_RESERVED_UPPER_REG (0x7D)
|
||||
// everything between BMP388_RESERVED_UPPER_REG and BMP388_RESERVED_LOWER_REG is reserved.
|
||||
#define BMP388_RESERVED_LOWER_REG (0x20)
|
||||
#define BMP388_CONFIG_REG (0x1F)
|
||||
#define BMP388_RESERVED_0x1E_REG (0x1E)
|
||||
#define BMP388_ODR_REG (0x1D)
|
||||
#define BMP388_OSR_REG (0x1C)
|
||||
#define BMP388_PWR_CTRL_REG (0x1B)
|
||||
#define BMP388_IF_CONFIG_REG (0x1A)
|
||||
#define BMP388_INT_CTRL_REG (0x19)
|
||||
#define BMP388_FIFO_CONFIG_2_REG (0x18)
|
||||
#define BMP388_FIFO_CONFIG_1_REG (0x17)
|
||||
#define BMP388_FIFO_WTM_1_REG (0x16)
|
||||
#define BMP388_FIFO_WTM_0_REG (0x15)
|
||||
#define BMP388_FIFO_DATA_REG (0x14)
|
||||
#define BMP388_FIFO_LENGTH_1_REG (0x13)
|
||||
#define BMP388_FIFO_LENGTH_0_REG (0x12)
|
||||
#define BMP388_INT_STATUS_REG (0x11)
|
||||
#define BMP388_EVENT_REG (0x10)
|
||||
#define BMP388_SENSORTIME_3_REG (0x0F) // BME780 only
|
||||
#define BMP388_SENSORTIME_2_REG (0x0E)
|
||||
#define BMP388_SENSORTIME_1_REG (0x0D)
|
||||
#define BMP388_SENSORTIME_0_REG (0x0C)
|
||||
#define BMP388_RESERVED_0x0B_REG (0x0B)
|
||||
#define BMP388_RESERVED_0x0A_REG (0x0A)
|
||||
|
||||
// see friendly register names below
|
||||
#define BMP388_DATA_5_REG (0x09)
|
||||
#define BMP388_DATA_4_REG (0x08)
|
||||
#define BMP388_DATA_3_REG (0x07)
|
||||
#define BMP388_DATA_2_REG (0x06)
|
||||
#define BMP388_DATA_1_REG (0x05)
|
||||
#define BMP388_DATA_0_REG (0x04)
|
||||
|
||||
#define BMP388_STATUS_REG (0x03)
|
||||
#define BMP388_ERR_REG (0x02)
|
||||
#define BMP388_RESERVED_0x01_REG (0x01)
|
||||
#define BMP388_CHIP_ID_REG (0x00)
|
||||
|
||||
// friendly register names, from datasheet 4.3.4
|
||||
#define BMP388_PRESS_MSB_23_16_REG BMP388_DATA_2_REG
|
||||
#define BMP388_PRESS_LSB_15_8_REG BMP388_DATA_1_REG
|
||||
#define BMP388_PRESS_XLSB_7_0_REG BMP388_DATA_0_REG
|
||||
|
||||
// friendly register names, from datasheet 4.3.5
|
||||
#define BMP388_TEMP_MSB_23_16_REG BMP388_DATA_5_REG
|
||||
#define BMP388_TEMP_LSB_15_8_REG BMP388_DATA_4_REG
|
||||
#define BMP388_TEMP_XLSB_7_0_REG BMP388_DATA_3_REG
|
||||
|
||||
#define BMP388_DATA_FRAME_SIZE ((BMP388_DATA_5_REG - BMP388_DATA_0_REG) + 1) // +1 for inclusive
|
||||
|
||||
// from Datasheet 3.3
|
||||
#define BMP388_MODE_SLEEP (0x00)
|
||||
#define BMP388_MODE_FORCED (0x01)
|
||||
#define BMP388_MODE_NORMAL (0x02)
|
||||
|
||||
#define BMP388_CALIRATION_LOWER_REG (0x30) // See datasheet 4.3.19, "calibration data"
|
||||
#define BMP388_TRIMMING_NVM_PAR_T1_LSB_REG (0x31) // See datasheet 3.11.1 "Memory map trimming coefficients"
|
||||
#define BMP388_TRIMMING_NVM_PAR_P11_REG (0x45) // See datasheet 3.11.1 "Memory map trimming coefficients"
|
||||
#define BMP388_CALIRATION_UPPER_REG (0x57)
|
||||
|
||||
#define BMP388_TRIMMING_DATA_LENGTH ((BMP388_TRIMMING_NVM_PAR_P11_REG - BMP388_TRIMMING_NVM_PAR_T1_LSB_REG) + 1) // +1 for inclusive
|
||||
|
||||
#define BMP388_OVERSAMP_1X (0x00)
|
||||
#define BMP388_OVERSAMP_2X (0x01)
|
||||
#define BMP388_OVERSAMP_4X (0x02)
|
||||
#define BMP388_OVERSAMP_8X (0x03)
|
||||
#define BMP388_OVERSAMP_16X (0x04)
|
||||
#define BMP388_OVERSAMP_32X (0x05)
|
||||
|
||||
// INT_CTRL register
|
||||
#define BMP388_INT_OD_BIT 0
|
||||
#define BMP388_INT_LEVEL_BIT 1
|
||||
#define BMP388_INT_LATCH_BIT 2
|
||||
#define BMP388_INT_FWTM_EN_BIT 3
|
||||
#define BMP388_INT_FFULL_EN_BIT 4
|
||||
#define BMP388_INT_RESERVED_5_BIT 5
|
||||
#define BMP388_INT_DRDY_EN_BIT 6
|
||||
#define BMP388_INT_RESERVED_7_BIT 7
|
||||
|
||||
// OSR register
|
||||
#define BMP388_OSR_P_BIT 0 // to 2
|
||||
#define BMP388_OSR4_T_BIT 3 // to 5
|
||||
#define BMP388_OSR_P_MASK (0x03) // -----111
|
||||
#define BMP388_OSR4_T_MASK (0x38) // --111---
|
||||
|
||||
// configure pressure and temperature oversampling, forced sampling mode
|
||||
#define BMP388_PRESSURE_OSR (BMP388_OVERSAMP_8X)
|
||||
#define BMP388_TEMPERATURE_OSR (BMP388_OVERSAMP_1X)
|
||||
|
||||
// see Datasheet 3.11.1 Memory Map Trimming Coefficients
|
||||
typedef struct bmp388_calib_param_s {
|
||||
uint16_t T1;
|
||||
uint16_t T2;
|
||||
int8_t T3;
|
||||
int16_t P1;
|
||||
int16_t P2;
|
||||
int8_t P3;
|
||||
int8_t P4;
|
||||
uint16_t P5;
|
||||
uint16_t P6;
|
||||
int8_t P7;
|
||||
int8_t P8;
|
||||
int16_t P9;
|
||||
int8_t P10;
|
||||
int8_t P11;
|
||||
} __attribute__((packed)) bmp388_calib_param_t;
|
||||
|
||||
STATIC_ASSERT(sizeof(bmp388_calib_param_t) == BMP388_TRIMMING_DATA_LENGTH, bmp388_calibration_structure_incorrectly_packed);
|
||||
|
||||
static bmp388_calib_param_t bmp388_cal;
|
||||
// uncompensated pressure and temperature
|
||||
static uint32_t bmp388_up = 0;
|
||||
static uint32_t bmp388_ut = 0;
|
||||
static uint8_t sensor_data[BMP388_DATA_FRAME_SIZE+1];
|
||||
|
||||
static int64_t t_lin = 0;
|
||||
|
||||
static bool bmp388StartUT(baroDev_t *baro);
|
||||
static bool bmp388GetUT(baroDev_t *baro);
|
||||
static bool bmp388StartUP(baroDev_t *baro);
|
||||
static bool bmp388GetUP(baroDev_t *baro);
|
||||
|
||||
static bool bmp388Calculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature);
|
||||
|
||||
static bool bmp388BeginForcedMeasurement(busDevice_t *busdev)
|
||||
{
|
||||
// enable pressure measurement, temperature measurement, set power mode and start sampling
|
||||
uint8_t mode = BMP388_MODE_FORCED << 4 | 1 << 1 | 1 << 0;
|
||||
return busWrite(busdev, BMP388_PWR_CTRL_REG, mode);
|
||||
}
|
||||
|
||||
static bool bmp388StartUT(baroDev_t *baro)
|
||||
{
|
||||
UNUSED(baro);
|
||||
// dummy
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool bmp388GetUT(baroDev_t *baro)
|
||||
{
|
||||
UNUSED(baro);
|
||||
// dummy
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool bmp388StartUP(baroDev_t *baro)
|
||||
{
|
||||
// start measurement
|
||||
return bmp388BeginForcedMeasurement(baro->busDev);
|
||||
}
|
||||
|
||||
static bool bmp388GetUP(baroDev_t *baro)
|
||||
{
|
||||
busReadBuf(baro->busDev, BMP388_DATA_0_REG, sensor_data, BMP388_DATA_FRAME_SIZE + 1);
|
||||
|
||||
bmp388_up = sensor_data[1] << 0 | sensor_data[2] << 8 | sensor_data[3] << 16;
|
||||
bmp388_ut = sensor_data[4] << 0 | sensor_data[5] << 8 | sensor_data[6] << 16;
|
||||
return true;
|
||||
}
|
||||
|
||||
// Returns temperature in DegC, resolution is 0.01 DegC. Output value of "5123" equals 51.23 DegC
|
||||
static int64_t bmp388CompensateTemperature(uint32_t uncomp_temperature)
|
||||
{
|
||||
uint64_t partial_data1;
|
||||
uint64_t partial_data2;
|
||||
uint64_t partial_data3;
|
||||
int64_t partial_data4;
|
||||
int64_t partial_data5;
|
||||
int64_t partial_data6;
|
||||
int64_t comp_temp;
|
||||
|
||||
partial_data1 = uncomp_temperature - (256 * bmp388_cal.T1);
|
||||
partial_data2 = bmp388_cal.T2 * partial_data1;
|
||||
partial_data3 = partial_data1 * partial_data1;
|
||||
partial_data4 = (int64_t)partial_data3 * bmp388_cal.T3;
|
||||
partial_data5 = ((int64_t)(partial_data2 * 262144) + partial_data4);
|
||||
partial_data6 = partial_data5 / 4294967296;
|
||||
/* Update t_lin, needed for pressure calculation */
|
||||
t_lin = partial_data6;
|
||||
comp_temp = (int64_t)((partial_data6 * 25) / 16384);
|
||||
|
||||
return comp_temp;
|
||||
}
|
||||
|
||||
static uint64_t bmp388CompensatePressure(uint32_t uncomp_pressure)
|
||||
{
|
||||
int64_t partial_data1;
|
||||
int64_t partial_data2;
|
||||
int64_t partial_data3;
|
||||
int64_t partial_data4;
|
||||
int64_t partial_data5;
|
||||
int64_t partial_data6;
|
||||
int64_t offset;
|
||||
int64_t sensitivity;
|
||||
uint64_t comp_press;
|
||||
|
||||
partial_data1 = t_lin * t_lin;
|
||||
partial_data2 = partial_data1 / 64;
|
||||
partial_data3 = (partial_data2 * t_lin) / 256;
|
||||
partial_data4 = (bmp388_cal.P8 * partial_data3) / 32;
|
||||
partial_data5 = (bmp388_cal.P7 * partial_data1) * 16;
|
||||
partial_data6 = (bmp388_cal.P6 * t_lin) * 4194304;
|
||||
offset = (bmp388_cal.P5 * 140737488355328) + partial_data4 + partial_data5 + partial_data6;
|
||||
|
||||
partial_data2 = (bmp388_cal.P4 * partial_data3) / 32;
|
||||
partial_data4 = (bmp388_cal.P3 * partial_data1) * 4;
|
||||
partial_data5 = (bmp388_cal.P2 - 16384) * t_lin * 2097152;
|
||||
sensitivity = ((bmp388_cal.P1 - 16384) * 70368744177664) + partial_data2 + partial_data4 + partial_data5;
|
||||
|
||||
partial_data1 = (sensitivity / 16777216) * uncomp_pressure;
|
||||
partial_data2 = bmp388_cal.P10 * t_lin;
|
||||
partial_data3 = partial_data2 + (65536 * bmp388_cal.P9);
|
||||
partial_data4 = (partial_data3 * uncomp_pressure) / 8192;
|
||||
partial_data5 = (partial_data4 * uncomp_pressure) / 512;
|
||||
partial_data6 = (int64_t)((uint64_t)uncomp_pressure * (uint64_t)uncomp_pressure);
|
||||
partial_data2 = (bmp388_cal.P11 * partial_data6) / 65536;
|
||||
partial_data3 = (partial_data2 * uncomp_pressure) / 128;
|
||||
partial_data4 = (offset / 4) + partial_data1 + partial_data5 + partial_data3;
|
||||
comp_press = (((uint64_t)partial_data4 * 25) / (uint64_t)1099511627776);
|
||||
|
||||
return comp_press;
|
||||
}
|
||||
|
||||
STATIC_UNIT_TESTED bool bmp388Calculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature)
|
||||
{
|
||||
UNUSED(baro);
|
||||
|
||||
// calculate
|
||||
int64_t t;
|
||||
int64_t p;
|
||||
|
||||
t = bmp388CompensateTemperature(bmp388_ut);
|
||||
p = bmp388CompensatePressure(bmp388_up);
|
||||
|
||||
if (pressure)
|
||||
*pressure = (int32_t)(p / 256);
|
||||
if (temperature)
|
||||
*temperature = t;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#define DETECTION_MAX_RETRY_COUNT 5
|
||||
static bool deviceDetect(busDevice_t * busDev)
|
||||
{
|
||||
for (int retry = 0; retry < DETECTION_MAX_RETRY_COUNT; retry++) {
|
||||
uint8_t chipId[2];
|
||||
|
||||
delay(100);
|
||||
|
||||
bool ack = busReadBuf(busDev, BMP388_CHIP_ID_REG, chipId, 2);
|
||||
|
||||
if (ack && chipId[1] == BMP388_DEFAULT_CHIP_ID) {
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool bmp388Detect(baroDev_t *baro)
|
||||
{
|
||||
baro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_BMP388, 0, OWNER_BARO);
|
||||
if (baro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
busSetSpeed(baro->busDev, BUS_SPEED_STANDARD);
|
||||
|
||||
if (!deviceDetect(baro->busDev)) {
|
||||
busDeviceDeInit(baro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
uint8_t calibration_buf[sizeof(bmp388_calib_param_t) + 1];
|
||||
|
||||
// read calibration
|
||||
busReadBuf(baro->busDev, BMP388_TRIMMING_NVM_PAR_T1_LSB_REG, calibration_buf, sizeof(bmp388_calib_param_t) + 1);
|
||||
memcpy(&bmp388_cal, calibration_buf + 1, sizeof(bmp388_calib_param_t));
|
||||
|
||||
// set oversampling + power mode (forced), and start sampling
|
||||
busWrite(baro->busDev, BMP388_OSR_REG,
|
||||
((BMP388_PRESSURE_OSR << BMP388_OSR_P_BIT) & BMP388_OSR_P_MASK) |
|
||||
((BMP388_TEMPERATURE_OSR << BMP388_OSR4_T_BIT) & BMP388_OSR4_T_MASK)
|
||||
);
|
||||
|
||||
bmp388BeginForcedMeasurement(baro->busDev);
|
||||
|
||||
baro->ut_delay = 0;
|
||||
baro->get_ut = bmp388GetUT;
|
||||
baro->start_ut = bmp388StartUT;
|
||||
|
||||
baro->up_delay = 234 + (392 + ((1 << (BMP388_PRESSURE_OSR + 1)) * 2000)) + (313 + ((1 << (BMP388_TEMPERATURE_OSR + 1)) * 2000));
|
||||
baro->start_up = bmp388StartUP;
|
||||
baro->get_up = bmp388GetUP;
|
||||
|
||||
baro->calculate = bmp388Calculate;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
30
src/main/drivers/barometer/barometer_bmp388.h
Normal file
30
src/main/drivers/barometer/barometer_bmp388.h
Normal file
|
@ -0,0 +1,30 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*
|
||||
* BMP388 Driver author: Dominic Clifton
|
||||
*
|
||||
* References:
|
||||
* BMP388 datasheet - https://ae-bst.resource.bosch.com/media/_tech/media/datasheets/BST-BMP388-DS001.pdf
|
||||
* BMP3-Sensor-API - https://github.com/BoschSensortec/BMP3-Sensor-API
|
||||
* BMP280 Cleanflight driver
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
bool bmp388Detect(baroDev_t *baro);
|
|
@ -103,6 +103,7 @@ typedef enum {
|
|||
DEVHW_MS5607,
|
||||
DEVHW_LPS25H,
|
||||
DEVHW_SPL06,
|
||||
DEVHW_BMP388,
|
||||
|
||||
/* Compass chips */
|
||||
DEVHW_HMC5883,
|
||||
|
|
|
@ -144,7 +144,7 @@ static bool commandBatchError = false;
|
|||
// sync this with features_e
|
||||
static const char * const featureNames[] = {
|
||||
"THR_VBAT_COMP", "VBAT", "TX_PROF_SEL", "BAT_PROF_AUTOSWITCH", "MOTOR_STOP",
|
||||
"DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "",
|
||||
"DYNAMIC_FILTERS", "SOFTSERIAL", "GPS", "RPM_FILTERS",
|
||||
"", "TELEMETRY", "CURRENT_METER", "3D", "",
|
||||
"", "RSSI_ADC", "LED_STRIP", "DASHBOARD", "",
|
||||
"BLACKBOX", "", "TRANSPONDER", "AIRMODE",
|
||||
|
|
|
@ -90,6 +90,7 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/servos.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
#include "io/beeper.h"
|
||||
|
@ -218,11 +219,7 @@ void init(void)
|
|||
// Latch active features to be used for feature() in the remainder of init().
|
||||
latchActiveFeatures();
|
||||
|
||||
#ifdef ALIENFLIGHTF3
|
||||
ledInit(hardwareRevision == AFF3_REV_1 ? false : true);
|
||||
#else
|
||||
ledInit(false);
|
||||
#endif
|
||||
|
||||
#ifdef USE_EXTI
|
||||
EXTIInit();
|
||||
|
@ -648,5 +645,13 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_RPM_FILTER
|
||||
disableRpmFilters();
|
||||
if (STATE(ESC_SENSOR_ENABLED) && (rpmFilterConfig()->gyro_filter_enabled || rpmFilterConfig()->dterm_filter_enabled)) {
|
||||
rpmFiltersInit();
|
||||
setTaskEnabled(TASK_RPM_FILTER, true);
|
||||
}
|
||||
#endif
|
||||
|
||||
systemState |= SYSTEM_STATE_READY;
|
||||
}
|
||||
|
|
|
@ -47,6 +47,7 @@
|
|||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
#include "flight/wind_estimator.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "navigation/navigation.h"
|
||||
|
||||
|
@ -561,4 +562,12 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_RPM_FILTER
|
||||
[TASK_RPM_FILTER] = {
|
||||
.taskName = "RPM",
|
||||
.taskFunc = rpmFilterUpdateTask,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(RPM_FILTER_UPDATE_RATE_HZ), // 300Hz @3,33ms
|
||||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
};
|
||||
|
|
|
@ -9,6 +9,7 @@
|
|||
#include "fc/settings.h"
|
||||
|
||||
#include "config/general_settings.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "settings_generated.c"
|
||||
|
||||
static bool settingGetWord(char *buf, int idx)
|
||||
|
|
|
@ -16,7 +16,7 @@ tables:
|
|||
values: ["NONE", "PMW3901", "CXOF", "MSP", "FAKE"]
|
||||
enum: opticalFlowSensor_e
|
||||
- name: baro_hardware
|
||||
values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "FAKE"]
|
||||
values: ["NONE", "AUTO", "BMP085", "MS5611", "BMP280", "MS5607", "LPS25H", "SPL06", "BMP388", "FAKE"]
|
||||
enum: baroSensor_e
|
||||
- name: pitot_hardware
|
||||
values: ["NONE", "AUTO", "MS4525", "ADC", "VIRTUAL", "FAKE"]
|
||||
|
@ -81,7 +81,7 @@ tables:
|
|||
values: ["NONE", "GYRO", "AGL", "FLOW_RAW",
|
||||
"FLOW", "SBUS", "FPORT", "ALWAYS", "SAG_COMP_VOLTAGE",
|
||||
"VIBE", "CRUISE", "REM_FLIGHT_TIME", "SMARTAUDIO", "ACC", "ITERM_RELAX",
|
||||
"ERPM"]
|
||||
"ERPM", "RPM_FILTER", "RPM_FREQ"]
|
||||
- name: async_mode
|
||||
values: ["NONE", "GYRO", "ALL"]
|
||||
- name: aux_operator
|
||||
|
@ -868,6 +868,46 @@ groups:
|
|||
min: 0
|
||||
max: 3
|
||||
|
||||
- name: PG_RPM_FILTER_CONFIG
|
||||
condition: USE_RPM_FILTER
|
||||
type: rpmFilterConfig_t
|
||||
members:
|
||||
- name: rpm_gyro_filter_enabled
|
||||
field: gyro_filter_enabled
|
||||
type: bool
|
||||
- name: rpm_dterm_filter_enabled
|
||||
field: dterm_filter_enabled
|
||||
type: bool
|
||||
- name: rpm_gyro_harmonics
|
||||
field: gyro_harmonics
|
||||
type: uint8_t
|
||||
min: 1
|
||||
max: 3
|
||||
- name: rpm_gyro_min_hz
|
||||
field: gyro_min_hz
|
||||
type: uint8_t
|
||||
min: 50
|
||||
max: 200
|
||||
- name: rpm_gyro_q
|
||||
field: gyro_q
|
||||
type: uint16_t
|
||||
min: 1
|
||||
max: 3000
|
||||
- name: dterm_gyro_harmonics
|
||||
field: dterm_harmonics
|
||||
type: uint8_t
|
||||
min: 1
|
||||
max: 3
|
||||
- name: rpm_dterm_min_hz
|
||||
field: dterm_min_hz
|
||||
type: uint8_t
|
||||
min: 50
|
||||
max: 200
|
||||
- name: rpm_dterm_q
|
||||
field: dterm_q
|
||||
type: uint16_t
|
||||
min: 1
|
||||
max: 3000
|
||||
- name: PG_GPS_CONFIG
|
||||
type: gpsConfig_t
|
||||
condition: USE_GPS
|
||||
|
|
|
@ -41,6 +41,7 @@
|
|||
#include "flight/pid.h"
|
||||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
|
@ -684,6 +685,10 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
|
|||
// Apply D-term notch
|
||||
deltaFiltered = notchFilterApplyFn(&pidState->deltaNotchFilter, deltaFiltered);
|
||||
|
||||
#ifdef USE_RPM_FILTER
|
||||
deltaFiltered = rpmFilterDtermApply((uint8_t)axis, deltaFiltered);
|
||||
#endif
|
||||
|
||||
// Apply additional lowpass
|
||||
deltaFiltered = dTermLpfFilterApplyFn(&pidState->deltaLpfState, deltaFiltered);
|
||||
|
||||
|
@ -1044,7 +1049,7 @@ void pidInit(void)
|
|||
}
|
||||
|
||||
if (pidProfile()->pidControllerType == PID_TYPE_AUTO) {
|
||||
if (STATE(FIXED_WING)) {
|
||||
if (mixerConfig()->platformType == PLATFORM_AIRPLANE) {
|
||||
usedPidControllerType = PID_TYPE_PIFF;
|
||||
} else {
|
||||
usedPidControllerType = PID_TYPE_PID;
|
||||
|
@ -1067,3 +1072,10 @@ void pidInit(void)
|
|||
pidControllerApplyFn = nullRateController;
|
||||
}
|
||||
}
|
||||
|
||||
const pidBank_t FAST_CODE NOINLINE * pidBank(void) {
|
||||
return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc;
|
||||
}
|
||||
pidBank_t FAST_CODE NOINLINE * pidBankMutable(void) {
|
||||
return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc;
|
||||
}
|
||||
|
|
|
@ -155,10 +155,8 @@ typedef struct pidAutotuneConfig_s {
|
|||
PG_DECLARE_PROFILE(pidProfile_t, pidProfile);
|
||||
PG_DECLARE(pidAutotuneConfig_t, pidAutotuneConfig);
|
||||
|
||||
static uint8_t usedPidControllerType;
|
||||
|
||||
static inline const pidBank_t * pidBank(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfile()->bank_fw : &pidProfile()->bank_mc; }
|
||||
static inline pidBank_t * pidBankMutable(void) { return usedPidControllerType == PID_TYPE_PIFF ? &pidProfileMutable()->bank_fw : &pidProfileMutable()->bank_mc; }
|
||||
const pidBank_t * pidBank(void);
|
||||
pidBank_t * pidBankMutable(void);
|
||||
|
||||
extern int16_t axisPID[];
|
||||
extern int32_t axisPID_P[], axisPID_I[], axisPID_D[], axisPID_Setpoint[];
|
||||
|
|
232
src/main/flight/rpm_filter.c
Normal file
232
src/main/flight/rpm_filter.c
Normal file
|
@ -0,0 +1,232 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file 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 program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "build/debug.h"
|
||||
|
||||
#include "common/axis.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/filter.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "sensors/esc_sensor.h"
|
||||
#include "fc/config.h"
|
||||
|
||||
#ifdef USE_RPM_FILTER
|
||||
|
||||
#define RPM_TO_HZ 60.0f
|
||||
#define RPM_FILTER_RPM_LPF_HZ 150
|
||||
#define RPM_FILTER_HARMONICS 3
|
||||
|
||||
PG_REGISTER_WITH_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig, PG_RPM_FILTER_CONFIG, 0);
|
||||
|
||||
PG_RESET_TEMPLATE(rpmFilterConfig_t, rpmFilterConfig,
|
||||
.gyro_filter_enabled = 0,
|
||||
.dterm_filter_enabled = 0,
|
||||
.gyro_harmonics = 1,
|
||||
.gyro_min_hz = 100,
|
||||
.gyro_q = 500,
|
||||
.dterm_harmonics = 1,
|
||||
.dterm_min_hz = 100,
|
||||
.dterm_q = 500, );
|
||||
|
||||
typedef struct
|
||||
{
|
||||
float q;
|
||||
float minHz;
|
||||
float maxHz;
|
||||
uint8_t harmonics;
|
||||
biquadFilter_t filters[XYZ_AXIS_COUNT][MAX_SUPPORTED_MOTORS][RPM_FILTER_HARMONICS];
|
||||
} rpmFilterBank_t;
|
||||
|
||||
typedef float (*rpmFilterApplyFnPtr)(rpmFilterBank_t *filter, uint8_t axis, float input);
|
||||
typedef void (*rpmFilterUpdateFnPtr)(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency);
|
||||
|
||||
static EXTENDED_FASTRAM pt1Filter_t motorFrequencyFilter[MAX_SUPPORTED_MOTORS];
|
||||
static EXTENDED_FASTRAM float erpmToHz;
|
||||
static EXTENDED_FASTRAM rpmFilterBank_t gyroRpmFilters;
|
||||
static EXTENDED_FASTRAM rpmFilterBank_t dtermRpmFilters;
|
||||
static EXTENDED_FASTRAM rpmFilterApplyFnPtr rpmGyroApplyFn;
|
||||
static EXTENDED_FASTRAM rpmFilterApplyFnPtr rpmDtermApplyFn;
|
||||
static EXTENDED_FASTRAM rpmFilterUpdateFnPtr rpmGyroUpdateFn;
|
||||
static EXTENDED_FASTRAM rpmFilterUpdateFnPtr rpmDtermUpdateFn;
|
||||
|
||||
float nullRpmFilterApply(rpmFilterBank_t *filter, uint8_t axis, float input)
|
||||
{
|
||||
UNUSED(filter);
|
||||
UNUSED(axis);
|
||||
return input;
|
||||
}
|
||||
|
||||
void nullRpmFilterUpdate(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency) {
|
||||
UNUSED(filterBank);
|
||||
UNUSED(motor);
|
||||
UNUSED(baseFrequency);
|
||||
}
|
||||
|
||||
float FAST_CODE rpmFilterApply(rpmFilterBank_t *filterBank, uint8_t axis, float input)
|
||||
{
|
||||
float output = input;
|
||||
|
||||
for (uint8_t motor = 0; motor < getMotorCount(); motor++)
|
||||
{
|
||||
for (int harmonicIndex = 0; harmonicIndex < filterBank->harmonics; harmonicIndex++)
|
||||
{
|
||||
output = biquadFilterApplyDF1(
|
||||
&filterBank->filters[axis][motor][harmonicIndex],
|
||||
output
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
return output;
|
||||
}
|
||||
|
||||
static void rpmFilterInit(rpmFilterBank_t *filter, uint16_t q, uint8_t minHz, uint8_t harmonics)
|
||||
{
|
||||
filter->q = q / 100.0f;
|
||||
filter->minHz = minHz;
|
||||
filter->harmonics = harmonics;
|
||||
/*
|
||||
* Max frequency has to be lower than Nyquist frequency for looptime
|
||||
*/
|
||||
filter->maxHz = 0.48f * 1000000.0f / getLooptime();
|
||||
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++)
|
||||
{
|
||||
for (int motor = 0; motor < getMotorCount(); motor++)
|
||||
{
|
||||
|
||||
/*
|
||||
* Harmonics are indexed from 1 where 1 means base frequency
|
||||
* C indexes arrays from 0, so we need to shift
|
||||
*/
|
||||
for (int harmonicIndex = 0; harmonicIndex < harmonics; harmonicIndex++)
|
||||
{
|
||||
biquadFilterInit(
|
||||
&filter->filters[axis][motor][harmonicIndex],
|
||||
filter->minHz * (harmonicIndex + 1),
|
||||
getLooptime(),
|
||||
filter->q,
|
||||
FILTER_NOTCH);
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void disableRpmFilters(void) {
|
||||
rpmGyroApplyFn = (rpmFilterApplyFnPtr)nullRpmFilterApply;
|
||||
rpmDtermApplyFn = (rpmFilterApplyFnPtr)nullRpmFilterApply;
|
||||
}
|
||||
|
||||
void FAST_CODE NOINLINE rpmFilterUpdate(rpmFilterBank_t *filterBank, uint8_t motor, float baseFrequency)
|
||||
{
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++)
|
||||
{
|
||||
for (int harmonicIndex = 0; harmonicIndex < filterBank->harmonics; harmonicIndex++)
|
||||
{
|
||||
float harmonicFrequency = baseFrequency * (harmonicIndex + 1);
|
||||
harmonicFrequency = constrainf(harmonicFrequency, filterBank->minHz, filterBank->maxHz);
|
||||
|
||||
biquadFilterUpdate(
|
||||
&filterBank->filters[axis][motor][harmonicIndex],
|
||||
harmonicFrequency,
|
||||
getLooptime(),
|
||||
filterBank->q,
|
||||
FILTER_NOTCH);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void rpmFiltersInit(void)
|
||||
{
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++)
|
||||
{
|
||||
pt1FilterInit(&motorFrequencyFilter[i], RPM_FILTER_RPM_LPF_HZ, RPM_FILTER_UPDATE_RATE_US * 1e-6f);
|
||||
}
|
||||
erpmToHz = ERPM_PER_LSB / (motorConfig()->motorPoleCount / 2) / RPM_TO_HZ;
|
||||
|
||||
rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate;
|
||||
rpmDtermUpdateFn = (rpmFilterUpdateFnPtr)nullRpmFilterUpdate;
|
||||
|
||||
if (rpmFilterConfig()->gyro_filter_enabled)
|
||||
{
|
||||
rpmFilterInit(
|
||||
&gyroRpmFilters,
|
||||
rpmFilterConfig()->gyro_q,
|
||||
rpmFilterConfig()->gyro_min_hz,
|
||||
rpmFilterConfig()->gyro_harmonics);
|
||||
rpmGyroApplyFn = (rpmFilterApplyFnPtr)rpmFilterApply;
|
||||
rpmGyroUpdateFn = (rpmFilterUpdateFnPtr)rpmFilterUpdate;
|
||||
}
|
||||
|
||||
if (rpmFilterConfig()->dterm_filter_enabled)
|
||||
{
|
||||
rpmFilterInit(
|
||||
&dtermRpmFilters,
|
||||
rpmFilterConfig()->dterm_q,
|
||||
rpmFilterConfig()->dterm_min_hz,
|
||||
rpmFilterConfig()->dterm_harmonics);
|
||||
rpmDtermApplyFn = (rpmFilterApplyFnPtr)rpmFilterApply;
|
||||
rpmDtermUpdateFn = (rpmFilterUpdateFnPtr)rpmFilterUpdate;
|
||||
}
|
||||
}
|
||||
|
||||
void FAST_CODE NOINLINE rpmFilterUpdateTask(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
uint8_t motorCount = getMotorCount();
|
||||
/*
|
||||
* For each motor, read ERPM, filter it and update motor frequency
|
||||
*/
|
||||
for (uint8_t i = 0; i < motorCount; i++)
|
||||
{
|
||||
const escSensorData_t *escState = getEscTelemetry(i); //Get ESC telemetry
|
||||
const float baseFrequency = pt1FilterApply(&motorFrequencyFilter[i], escState->rpm * erpmToHz); //Filter motor frequency
|
||||
|
||||
if (i < 4) {
|
||||
DEBUG_SET(DEBUG_RPM_FREQ, i, (int)baseFrequency);
|
||||
}
|
||||
|
||||
rpmGyroUpdateFn(&gyroRpmFilters, i, baseFrequency);
|
||||
rpmDtermUpdateFn(&dtermRpmFilters, i, baseFrequency);
|
||||
}
|
||||
}
|
||||
|
||||
float FAST_CODE rpmFilterGyroApply(uint8_t axis, float input)
|
||||
{
|
||||
return rpmGyroApplyFn(&gyroRpmFilters, axis, input);
|
||||
}
|
||||
|
||||
float FAST_CODE rpmFilterDtermApply(uint8_t axis, float input)
|
||||
{
|
||||
return rpmDtermApplyFn(&dtermRpmFilters, axis, input);
|
||||
}
|
||||
|
||||
#endif
|
53
src/main/flight/rpm_filter.h
Normal file
53
src/main/flight/rpm_filter.h
Normal file
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* This file is part of INAV Project.
|
||||
*
|
||||
* This Source Code Form is subject to the terms of the Mozilla Public
|
||||
* License, v. 2.0. If a copy of the MPL was not distributed with this file,
|
||||
* You can obtain one at http://mozilla.org/MPL/2.0/.
|
||||
*
|
||||
* Alternatively, the contents of this file may be used under the terms
|
||||
* of the GNU General Public License Version 3, as described below:
|
||||
*
|
||||
* This file is free software: you may copy, redistribute and/or modify
|
||||
* it under the terms of the GNU General Public License as published by the
|
||||
* Free Software Foundation, either version 3 of the License, or (at your
|
||||
* option) any later version.
|
||||
*
|
||||
* This file 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 program. If not, see http://www.gnu.org/licenses/.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "common/time.h"
|
||||
|
||||
typedef struct rpmFilterConfig_s {
|
||||
uint8_t gyro_filter_enabled;
|
||||
uint8_t dterm_filter_enabled;
|
||||
|
||||
uint8_t gyro_harmonics;
|
||||
uint8_t gyro_min_hz;
|
||||
uint16_t gyro_q;
|
||||
|
||||
uint8_t dterm_harmonics;
|
||||
uint8_t dterm_min_hz;
|
||||
uint16_t dterm_q;
|
||||
|
||||
} rpmFilterConfig_t;
|
||||
|
||||
PG_DECLARE(rpmFilterConfig_t, rpmFilterConfig);
|
||||
|
||||
#define RPM_FILTER_UPDATE_RATE_HZ 500
|
||||
#define RPM_FILTER_UPDATE_RATE_US (1000000.0f / RPM_FILTER_UPDATE_RATE_HZ)
|
||||
|
||||
void disableRpmFilters(void);
|
||||
void rpmFiltersInit(void);
|
||||
void rpmFilterUpdateTask(timeUs_t currentTimeUs);
|
||||
float rpmFilterGyroApply(uint8_t axis, float input);
|
||||
float rpmFilterDtermApply(uint8_t axis, float input);
|
|
@ -2084,7 +2084,8 @@ float getFinalRTHAltitude(void)
|
|||
static void updateDesiredRTHAltitude(void)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
if (!(navGetStateFlags(posControl.navState) & NAV_AUTO_RTH)) {
|
||||
if (!((navGetStateFlags(posControl.navState) & NAV_AUTO_RTH)
|
||||
|| ((navGetStateFlags(posControl.navState) & NAV_AUTO_WP) && posControl.waypointList[posControl.activeWaypointIndex].action == NAV_WP_ACTION_RTH))) {
|
||||
switch (navConfig()->general.flags.rth_alt_control_mode) {
|
||||
case NAV_RTH_NO_ALT:
|
||||
posControl.rthState.rthInitialAltitude = posControl.actualState.abs.pos.z;
|
||||
|
|
|
@ -115,6 +115,9 @@ typedef enum {
|
|||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
TASK_GLOBAL_FUNCTIONS,
|
||||
#endif
|
||||
#ifdef USE_RPM_FILTER
|
||||
TASK_RPM_FILTER,
|
||||
#endif
|
||||
/* Count of real tasks */
|
||||
TASK_COUNT,
|
||||
|
|
|
@ -33,6 +33,7 @@
|
|||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/barometer/barometer_bmp085.h"
|
||||
#include "drivers/barometer/barometer_bmp280.h"
|
||||
#include "drivers/barometer/barometer_bmp388.h"
|
||||
#include "drivers/barometer/barometer_lps25h.h"
|
||||
#include "drivers/barometer/barometer_fake.h"
|
||||
#include "drivers/barometer/barometer_ms56xx.h"
|
||||
|
@ -132,6 +133,19 @@ bool baroDetect(baroDev_t *dev, baroSensor_e baroHardwareToUse)
|
|||
}
|
||||
FALLTHROUGH;
|
||||
|
||||
case BARO_BMP388:
|
||||
#if defined(USE_BARO_BMP388) || defined(USE_BARO_SPI_BMP388)
|
||||
if (bmp388Detect(dev)) {
|
||||
baroHardware = BARO_BMP388;
|
||||
break;
|
||||
}
|
||||
#endif
|
||||
/* If we are asked for a specific sensor - break out, otherwise - fall through and continue */
|
||||
if (baroHardwareToUse != BARO_AUTODETECT) {
|
||||
break;
|
||||
}
|
||||
FALLTHROUGH;
|
||||
|
||||
case BARO_SPL06:
|
||||
#if defined(USE_BARO_SPL06) || defined(USE_BARO_SPI_SPL06)
|
||||
if (spl06Detect(dev)) {
|
||||
|
|
|
@ -30,7 +30,8 @@ typedef enum {
|
|||
BARO_MS5607 = 5,
|
||||
BARO_LPS25H = 6,
|
||||
BARO_SPL06 = 7,
|
||||
BARO_FAKE = 8,
|
||||
BARO_BMP388 = 8,
|
||||
BARO_FAKE = 9,
|
||||
BARO_MAX = BARO_FAKE
|
||||
} baroSensor_e;
|
||||
|
||||
|
|
|
@ -130,6 +130,15 @@ static bool escSensorDecodeFrame(void)
|
|||
return ESC_SENSOR_FRAME_PENDING;
|
||||
}
|
||||
|
||||
uint32_t FAST_CODE computeRpm(int16_t erpm) {
|
||||
return lrintf((float)erpm * ERPM_PER_LSB / (motorConfig()->motorPoleCount / 2));
|
||||
}
|
||||
|
||||
escSensorData_t NOINLINE * getEscTelemetry(uint8_t esc)
|
||||
{
|
||||
return &escSensorData[esc];
|
||||
}
|
||||
|
||||
escSensorData_t * escSensorGetData(void)
|
||||
{
|
||||
if (!escSensorPort) {
|
||||
|
@ -160,7 +169,7 @@ escSensorData_t * escSensorGetData(void)
|
|||
if (usedEscSensorCount) {
|
||||
escSensorDataCombined.current = (uint32_t)escSensorDataCombined.current * getMotorCount() / usedEscSensorCount + escSensorConfig()->currentOffset;
|
||||
escSensorDataCombined.voltage = (uint32_t)escSensorDataCombined.voltage / usedEscSensorCount;
|
||||
escSensorDataCombined.rpm = lrintf(((float)escSensorDataCombined.rpm / usedEscSensorCount) * 100.0f / (motorConfig()->motorPoleCount / 2));
|
||||
escSensorDataCombined.rpm = computeRpm((float)escSensorDataCombined.rpm / usedEscSensorCount);
|
||||
}
|
||||
else {
|
||||
escSensorDataCombined.dataAge = ESC_DATA_INVALID;
|
||||
|
|
|
@ -40,7 +40,10 @@ PG_DECLARE(escSensorConfig_t, escSensorConfig);
|
|||
|
||||
#define ESC_DATA_MAX_AGE 10
|
||||
#define ESC_DATA_INVALID 255
|
||||
#define ERPM_PER_LSB 100.0f
|
||||
|
||||
bool escSensorInitialize(void);
|
||||
void escSensorUpdate(timeUs_t currentTimeUs);
|
||||
escSensorData_t * escSensorGetData(void);
|
||||
escSensorData_t * getEscTelemetry(uint8_t esc);
|
||||
uint32_t computeRpm(int16_t erpm);
|
||||
|
|
|
@ -68,6 +68,7 @@
|
|||
#include "sensors/sensors.h"
|
||||
|
||||
#include "flight/gyroanalyse.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
|
||||
#ifdef USE_HARDWARE_REVISION_DETECTION
|
||||
#include "hardware_revision.h"
|
||||
|
@ -464,6 +465,12 @@ void FAST_CODE NOINLINE gyroUpdate()
|
|||
|
||||
DEBUG_SET(DEBUG_GYRO, axis, lrintf(gyroADCf));
|
||||
|
||||
#ifdef USE_RPM_FILTER
|
||||
DEBUG_SET(DEBUG_RPM_FILTER, axis, gyroADCf);
|
||||
gyroADCf = rpmFilterGyroApply(axis, gyroADCf);
|
||||
DEBUG_SET(DEBUG_RPM_FILTER, axis + 3, gyroADCf);
|
||||
#endif
|
||||
|
||||
gyroADCf = gyroFilterStage2ApplyFn(stage2Filter[axis], gyroADCf);
|
||||
gyroADCf = softLpfFilterApplyFn(softLpfFilter[axis], gyroADCf);
|
||||
gyroADCf = notchFilter1ApplyFn(notchFilter1[axis], gyroADCf);
|
||||
|
@ -484,6 +491,7 @@ void FAST_CODE NOINLINE gyroUpdate()
|
|||
gyroDataAnalyse(&gyroAnalyseState, notchFilterDyn, notchFilterDyn2);
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool gyroReadTemperature(void)
|
||||
|
|
|
@ -17,9 +17,13 @@
|
|||
|
||||
#pragma once
|
||||
|
||||
#ifdef MAMBAF405
|
||||
#define TARGET_BOARD_IDENTIFIER "MBF4"
|
||||
#define USBD_PRODUCT_STRING "MAMBAF405"
|
||||
#else
|
||||
#define TARGET_BOARD_IDENTIFIER "FYF4"
|
||||
|
||||
#define USBD_PRODUCT_STRING "FuryF4"
|
||||
#endif
|
||||
|
||||
#define LED0 PB5
|
||||
#define LED1 PB4
|
||||
|
|
53
src/main/target/MAMBAF405US/config.c
Normal file
53
src/main/target/MAMBAF405US/config.c
Normal file
|
@ -0,0 +1,53 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
// MSP @ 19200 on SERIAL4
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_19200;
|
||||
}
|
38
src/main/target/MAMBAF405US/target.c
Normal file
38
src/main/target/MAMBAF405US/target.c
Normal file
|
@ -0,0 +1,38 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7)
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7)
|
||||
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3)
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
188
src/main/target/MAMBAF405US/target.h
Normal file
188
src/main/target/MAMBAF405US/target.h
Normal file
|
@ -0,0 +1,188 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MBUS"
|
||||
#define USBD_PRODUCT_STRING "MAMBAF405US"
|
||||
|
||||
// ******** Board LEDs **********************
|
||||
#define LED0 PC15
|
||||
#define LED1 PC14
|
||||
|
||||
// ******* Beeper ***********
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
||||
// ******* GYRO and ACC ********
|
||||
#define USE_EXTI
|
||||
#define USE_GYRO_EXTI
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_CS_PIN PA4
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
// *************** Baro **************************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
|
||||
#define I2C2_SCL PB10 // SCL pad TX3
|
||||
#define I2C2_SDA PB11 // SDA pad RX3
|
||||
#define DEFAULT_I2C_BUS BUS_I2C2
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
/*
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_TX_PIN PA2
|
||||
#define SOFTSERIAL_1_RX_PIN PA2
|
||||
*/
|
||||
|
||||
#define SERIAL_PORT_COUNT 7
|
||||
|
||||
#define USE_UART_INVERTER
|
||||
#define INVERTER_PIN_UART1_RX PC0
|
||||
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PB0
|
||||
|
||||
|
||||
// ******* SPI ********
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
// ******* ADC ********
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC2
|
||||
#define ADC_CHANNEL_3_PIN PC3
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define VBAT_SCALE_DEFAULT 1100
|
||||
|
||||
// ******* OSD ********
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN PB12
|
||||
|
||||
//******* FLASH ********
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
#define M25P16_CS_PIN PA15
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
//************ LEDSTRIP *****************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB3
|
||||
|
||||
// ******* FEATURES ********
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART1
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY)
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
|
||||
// ESC-related features
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
//#define USE_ESC_SENSOR
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
13
src/main/target/MAMBAF405US/target.mk
Normal file
13
src/main/target/MAMBAF405US/target.mk
Normal file
|
@ -0,0 +1,13 @@
|
|||
F405_TARGETS += $(TARGET)
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/max7456.c
|
56
src/main/target/MAMBAF722/config.c
Normal file
56
src/main/target/MAMBAF722/config.c
Normal file
|
@ -0,0 +1,56 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
|
||||
#include "drivers/sensor.h"
|
||||
#include "drivers/pwm_esc_detect.h"
|
||||
#include "drivers/pwm_output.h"
|
||||
#include "drivers/serial.h"
|
||||
|
||||
#include "fc/rc_controls.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/pid.h"
|
||||
|
||||
#include "rx/rx.h"
|
||||
|
||||
#include "io/serial.h"
|
||||
|
||||
#include "sensors/battery.h"
|
||||
#include "sensors/sensors.h"
|
||||
|
||||
#include "telemetry/telemetry.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
// RX6 is hard-wired to ESC-telemetry
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART6)].functionMask = FUNCTION_ESCSERIAL;
|
||||
|
||||
// Built-in bluetooth on SERIAL4
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].functionMask = FUNCTION_MSP;
|
||||
serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_USART4)].msp_baudrateIndex = BAUD_19200;
|
||||
}
|
38
src/main/target/MAMBAF722/target.c
Normal file
38
src/main/target/MAMBAF722/target.c
Normal file
|
@ -0,0 +1,38 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/timer.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/bus.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
DEF_TIM(TIM11, CH1, PB9, TIM_USE_PPM, 0, 0 ), // PPM IN
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR, 0, 0 ), // S1_OUT – D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR, 0, 0 ), // S2_OUT – D(2, 7, 7)
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_MC_MOTOR, 0, 1 ), // S3_OUT – D(2, 1, 6)
|
||||
DEF_TIM(TIM1, CH2, PA9, TIM_USE_MC_MOTOR, 0, 0 ), // S4_OUT – D(2, 6, 0)
|
||||
|
||||
DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0 ), // LED_STRIP – D(1, 6, 3)
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
176
src/main/target/MAMBAF722/target.h
Normal file
176
src/main/target/MAMBAF722/target.h
Normal file
|
@ -0,0 +1,176 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#define USE_TARGET_CONFIG
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MBF7"
|
||||
#define USBD_PRODUCT_STRING "MAMBAF722"
|
||||
|
||||
// ******** Board LEDs **********************
|
||||
#define LED0 PC15
|
||||
#define LED1 PC14
|
||||
|
||||
// ******* Beeper ***********
|
||||
#define BEEPER PB2
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
|
||||
// ******* GYRO and ACC ********
|
||||
#define USE_EXTI
|
||||
#define USE_GYRO_EXTI
|
||||
#define GYRO_INT_EXTI PC4
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define MPU6000_CS_PIN SPI1_NSS_PIN
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
|
||||
#define USE_GYRO
|
||||
#define USE_GYRO_MPU6000
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_ACC_MPU6000
|
||||
#define ACC_MPU6500_ALIGN CW180_DEG
|
||||
|
||||
// *************** Baro **************************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_2
|
||||
|
||||
#define I2C2_SCL PB10 // SCL pad TX3
|
||||
#define I2C2_SDA PB11 // SDA pad RX3
|
||||
#define DEFAULT_I2C_BUS BUS_I2C2
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
//*********** Magnetometer / Compass *************
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS DEFAULT_I2C_BUS
|
||||
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
// ******* SERIAL ********
|
||||
#define USE_VCP
|
||||
#define USE_UART1
|
||||
#define USE_UART2
|
||||
#define USE_UART3
|
||||
#define USE_UART4
|
||||
#define USE_UART5
|
||||
#define USE_UART6
|
||||
#define USE_SOFTSERIAL1
|
||||
|
||||
#define UART1_TX_PIN PB6
|
||||
#define UART1_RX_PIN PB7
|
||||
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define UART3_TX_PIN PB10
|
||||
#define UART3_RX_PIN PB11
|
||||
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define SOFTSERIAL_1_TX_PIN PA2
|
||||
#define SOFTSERIAL_1_RX_PIN PA2
|
||||
|
||||
#define SERIAL_PORT_COUNT 8
|
||||
|
||||
// ******* SPI ********
|
||||
#define USE_SPI
|
||||
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_NSS_PIN PA4
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_NSS_PIN PB12
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PB15
|
||||
|
||||
#define USE_SPI_DEVICE_3
|
||||
#define SPI3_NSS_PIN PA15
|
||||
#define SPI3_SCK_PIN PC10
|
||||
#define SPI3_MISO_PIN PC11
|
||||
#define SPI3_MOSI_PIN PB5
|
||||
|
||||
// ******* ADC ********
|
||||
#define USE_ADC
|
||||
#define ADC_CHANNEL_1_PIN PC1
|
||||
#define ADC_CHANNEL_2_PIN PC2
|
||||
#define ADC_CHANNEL_3_PIN PC3
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_2
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_3
|
||||
|
||||
#define VBAT_SCALE_DEFAULT 1100
|
||||
|
||||
// ******* OSD ********
|
||||
#define USE_OSD
|
||||
#define USE_MAX7456
|
||||
#define MAX7456_SPI_BUS BUS_SPI2
|
||||
#define MAX7456_CS_PIN SPI2_NSS_PIN
|
||||
|
||||
//******* FLASH ********
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_CS_PIN SPI3_NSS_PIN
|
||||
#define M25P16_SPI_BUS BUS_SPI3
|
||||
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
//************ LEDSTRIP *****************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PB3
|
||||
|
||||
// ******* FEATURES ********
|
||||
#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_SOFTSERIAL)
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD (BIT(2))
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 8
|
||||
#define TARGET_MOTOR_COUNT 4
|
||||
|
||||
// ESC-related features
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
14
src/main/target/MAMBAF722/target.mk
Normal file
14
src/main/target/MAMBAF722/target.mk
Normal file
|
@ -0,0 +1,14 @@
|
|||
F7X2RE_TARGETS += $(TARGET)
|
||||
FEATURES += VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/barometer/barometer_bmp085.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/max7456.c
|
32
src/main/target/MATEKF722PX/config.c
Executable file
32
src/main/target/MATEKF722PX/config.c
Executable file
|
@ -0,0 +1,32 @@
|
|||
/*
|
||||
* This file is part of Cleanflight.
|
||||
*
|
||||
* Cleanflight is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* Cleanflight is distributed in the hope that it will be useful,
|
||||
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||
* GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
#include "io/piniobox.h"
|
||||
#include "config/config_master.h"
|
||||
#include "config/feature.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/frsky_osd.h"
|
||||
|
||||
void targetConfiguration(void)
|
||||
{
|
||||
pinioBoxConfigMutable()->permanentId[0] = 47;
|
||||
pinioBoxConfigMutable()->permanentId[1] = 48;
|
||||
|
||||
serialConfigMutable()->portConfigs[6].functionMask = FUNCTION_FRSKY_OSD;
|
||||
}
|
50
src/main/target/MATEKF722PX/target.c
Executable file
50
src/main/target/MATEKF722PX/target.c
Executable file
|
@ -0,0 +1,50 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
#include "platform.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/pwm_mapping.h"
|
||||
#include "drivers/timer.h"
|
||||
|
||||
const timerHardware_t timerHardware[] = {
|
||||
|
||||
DEF_TIM(TIM8, CH3, PC8, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S1 UP2-1 D(2, 4, 7)
|
||||
DEF_TIM(TIM8, CH4, PC9, TIM_USE_MC_MOTOR | TIM_USE_FW_MOTOR, 0, 0), // S2 UP2-1 D(2, 7, 7)
|
||||
|
||||
DEF_TIM(TIM3, CH1, PB4, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S3 UP1-2 D(1, 4, 5)
|
||||
DEF_TIM(TIM3, CH2, PB5, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S4 UP1-2 D(1, 5, 5)
|
||||
DEF_TIM(TIM3, CH3, PB0, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S5 UP1-2 D(1, 7, 5)
|
||||
DEF_TIM(TIM3, CH4, PB1, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S6 UP1-2 D(1, 2, 5)
|
||||
|
||||
DEF_TIM(TIM2, CH3, PB10, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 0), // S7 UP1-7 D(1, 1, 3)
|
||||
DEF_TIM(TIM2, CH4, PB11, TIM_USE_MC_MOTOR | TIM_USE_FW_SERVO, 0, 1), // S8 UP1-7 D(1, 6, 3)
|
||||
|
||||
DEF_TIM(TIM4, CH1, PB6, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S9 UP1-6 D(1, 0, 2)
|
||||
DEF_TIM(TIM4, CH2, PB7, TIM_USE_MC_SERVO | TIM_USE_FW_SERVO, 0, 0), // S10 UP1-6 D(1, 3, 2)
|
||||
|
||||
DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 2), // LED D(2, 3, 6)
|
||||
|
||||
DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // RX2, PPM
|
||||
DEF_TIM(TIM5, CH3, PA2, TIM_USE_PWM, 0, 0), // TX2, softserial1_tx
|
||||
|
||||
DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0), // Cam_ctrl reserved
|
||||
|
||||
};
|
||||
|
||||
const int timerHardwareCount = sizeof(timerHardware) / sizeof(timerHardware[0]);
|
177
src/main/target/MATEKF722PX/target.h
Executable file
177
src/main/target/MATEKF722PX/target.h
Executable file
|
@ -0,0 +1,177 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* INAV is free software: you can redistribute it and/or modify
|
||||
* it under the terms of the GNU General Public License as published by
|
||||
* the Free Software Foundation, either version 3 of the License, or
|
||||
* (at your option) any later version.
|
||||
*
|
||||
* INAV 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 INAV. If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
|
||||
#pragma once
|
||||
|
||||
#define TARGET_BOARD_IDENTIFIER "MF7P"
|
||||
#define USBD_PRODUCT_STRING "MATEKF722PX"
|
||||
|
||||
#define LED0 PA14 //Blue SWCLK
|
||||
#define LED1 PA13 //Green SWDIO
|
||||
|
||||
#define BEEPER PC13
|
||||
#define BEEPER_INVERTED
|
||||
|
||||
// *************** SPI1 Gyro & ACC *******************
|
||||
#define USE_SPI
|
||||
#define USE_SPI_DEVICE_1
|
||||
#define SPI1_SCK_PIN PA5
|
||||
#define SPI1_MISO_PIN PA6
|
||||
#define SPI1_MOSI_PIN PA7
|
||||
|
||||
#define USE_ACC
|
||||
#define USE_GYRO
|
||||
#define USE_EXTI
|
||||
#define USE_MPU_DATA_READY_SIGNAL
|
||||
|
||||
#define USE_ACC_MPU6000
|
||||
#define USE_GYRO_MPU6000
|
||||
#define MPU6000_CS_PIN PB2
|
||||
#define MPU6000_SPI_BUS BUS_SPI1
|
||||
#define MPU6000_EXTI_PIN PC4
|
||||
|
||||
#define GYRO_MPU6000_ALIGN CW180_DEG_FLIP
|
||||
#define ACC_MPU6000_ALIGN CW180_DEG_FLIP
|
||||
|
||||
// *************** I2C /Baro/Mag *********************
|
||||
#define USE_I2C
|
||||
#define USE_I2C_DEVICE_1
|
||||
#define I2C1_SCL PB8
|
||||
#define I2C1_SDA PB9
|
||||
|
||||
#define USE_BARO
|
||||
#define BARO_I2C_BUS BUS_I2C1
|
||||
#define USE_BARO_BMP280
|
||||
#define USE_BARO_MS5611
|
||||
|
||||
#define USE_MAG
|
||||
#define MAG_I2C_BUS BUS_I2C1
|
||||
#define USE_MAG_AK8975
|
||||
#define USE_MAG_HMC5883
|
||||
#define USE_MAG_QMC5883
|
||||
#define USE_MAG_IST8310
|
||||
#define USE_MAG_IST8308
|
||||
#define USE_MAG_MAG3110
|
||||
#define USE_MAG_LIS3MDL
|
||||
|
||||
#define TEMPERATURE_I2C_BUS BUS_I2C1
|
||||
|
||||
#define PITOT_I2C_BUS BUS_I2C1
|
||||
|
||||
#define USE_RANGEFINDER
|
||||
#define RANGEFINDER_I2C_BUS BUS_I2C1
|
||||
|
||||
// *************** SPI2 Flash ***********************
|
||||
#define USE_SPI_DEVICE_2
|
||||
#define SPI2_SCK_PIN PB13
|
||||
#define SPI2_MISO_PIN PB14
|
||||
#define SPI2_MOSI_PIN PC3
|
||||
|
||||
#define USE_FLASHFS
|
||||
#define USE_FLASH_M25P16
|
||||
#define M25P16_SPI_BUS BUS_SPI2
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT
|
||||
|
||||
#define USE_SDCARD
|
||||
#define USE_SDCARD_SPI
|
||||
#define SDCARD_SPI_BUS BUS_SPI2
|
||||
#define SDCARD_CS_PIN PC15
|
||||
|
||||
// *************** UART *****************************
|
||||
#define USE_VCP
|
||||
#define USB_DETECT_PIN PC14
|
||||
#define USE_USB_DETECT
|
||||
|
||||
#define USE_UART1
|
||||
#define UART1_TX_PIN PA9
|
||||
#define UART1_RX_PIN PA10
|
||||
|
||||
#define USE_UART2
|
||||
#define UART2_TX_PIN PA2
|
||||
#define UART2_RX_PIN PA3
|
||||
|
||||
#define USE_UART3
|
||||
#define UART3_TX_PIN PC10
|
||||
#define UART3_RX_PIN PC11
|
||||
|
||||
#define USE_UART4
|
||||
#define UART4_TX_PIN PA0
|
||||
#define UART4_RX_PIN PA1
|
||||
|
||||
#define USE_UART5
|
||||
#define UART5_TX_PIN PC12
|
||||
#define UART5_RX_PIN PD2
|
||||
|
||||
#define USE_UART6
|
||||
#define UART6_TX_PIN PC6
|
||||
#define UART6_RX_PIN PC7
|
||||
|
||||
#define USE_SOFTSERIAL1
|
||||
#define SOFTSERIAL_1_TX_PIN PA2 //TX2 pad
|
||||
#define SOFTSERIAL_1_RX_PIN PA2
|
||||
|
||||
#define SERIAL_PORT_COUNT 8
|
||||
|
||||
#define DEFAULT_RX_TYPE RX_TYPE_SERIAL
|
||||
#define SERIALRX_PROVIDER SERIALRX_SBUS
|
||||
#define SERIALRX_UART SERIAL_PORT_USART2
|
||||
|
||||
// *************** ADC *****************************
|
||||
#define USE_ADC
|
||||
#define ADC_INSTANCE ADC1
|
||||
#define ADC1_DMA_STREAM DMA2_Stream0
|
||||
|
||||
#define ADC_CHANNEL_1_PIN PC2
|
||||
#define ADC_CHANNEL_2_PIN PC1
|
||||
#define ADC_CHANNEL_3_PIN PC0
|
||||
#define ADC_CHANNEL_4_PIN PA4
|
||||
|
||||
#define VBAT_ADC_CHANNEL ADC_CHN_1
|
||||
#define CURRENT_METER_ADC_CHANNEL ADC_CHN_2
|
||||
#define RSSI_ADC_CHANNEL ADC_CHN_3
|
||||
#define AIRSPEED_ADC_CHANNEL ADC_CHN_4
|
||||
|
||||
// *************** PINIO ***************************
|
||||
#define USE_PINIO
|
||||
#define USE_PINIOBOX
|
||||
#define PINIO1_PIN PA15 // Power switch
|
||||
#define PINIO2_PIN PB3 // Camera switch
|
||||
|
||||
// *************** LEDSTRIP ************************
|
||||
#define USE_LED_STRIP
|
||||
#define WS2811_PIN PA8
|
||||
|
||||
#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY | FEATURE_CURRENT_METER | FEATURE_VBAT | FEATURE_TX_PROF_SEL | FEATURE_SOFTSERIAL)
|
||||
#define CURRENT_METER_SCALE 250
|
||||
|
||||
#define USE_SERIAL_4WAY_BLHELI_INTERFACE
|
||||
|
||||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC 0xffff
|
||||
#define TARGET_IO_PORTD 0xffff
|
||||
|
||||
#define MAX_PWM_OUTPUT_PORTS 10
|
||||
#define USE_OSD
|
||||
#define USE_DSHOT
|
||||
#define USE_SERIALSHOT
|
||||
#define USE_ESC_SENSOR
|
||||
|
||||
//#define USE_CAMERA_CONTROL
|
||||
//#define CAMERA_CONTROL_PIN PB15
|
17
src/main/target/MATEKF722PX/target.mk
Executable file
17
src/main/target/MATEKF722PX/target.mk
Executable file
|
@ -0,0 +1,17 @@
|
|||
F7X2RE_TARGETS += $(TARGET)
|
||||
FEATURES += SDCARD VCP ONBOARDFLASH
|
||||
|
||||
TARGET_SRC = \
|
||||
drivers/accgyro/accgyro_mpu6000.c \
|
||||
drivers/barometer/barometer_bmp280.c \
|
||||
drivers/barometer/barometer_ms56xx.c \
|
||||
drivers/compass/compass_ak8975.c \
|
||||
drivers/compass/compass_hmc5883l.c \
|
||||
drivers/compass/compass_qmc5883l.c \
|
||||
drivers/compass/compass_ist8310.c \
|
||||
drivers/compass/compass_ist8308.c \
|
||||
drivers/compass/compass_mag3110.c \
|
||||
drivers/compass/compass_lis3mdl.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/pitotmeter_adc.c \
|
||||
|
|
@ -154,5 +154,3 @@
|
|||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
#undef USE_PWM_SERVO_DRIVER
|
|
@ -113,7 +113,6 @@
|
|||
#undef USE_VTX_FFPV
|
||||
#undef USE_VTX_SMARTAUDIO // Disabled due to flash size
|
||||
#undef USE_VTX_TRAMP // Disabled due to flash size
|
||||
#undef USE_PWM_SERVO_DRIVER // Disabled due to RAM size
|
||||
|
||||
#undef USE_PITOT // Disabled due to RAM size
|
||||
#undef USE_PITOT_ADC // Disabled due to RAM size
|
||||
|
|
|
@ -97,6 +97,17 @@
|
|||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_BARO_BMP388)
|
||||
#if defined(BMP388_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_bmp388, DEVHW_BMP388, BMP388_SPI_BUS, BMP388_CS_PIN, NONE, DEVFLAGS_NONE);
|
||||
#elif defined(BMP388_I2C_BUS) || defined(BARO_I2C_BUS)
|
||||
#if !defined(BMP388_I2C_BUS)
|
||||
#define BMP388_I2C_BUS BARO_I2C_BUS
|
||||
#endif
|
||||
BUSDEV_REGISTER_I2C(busdev_bmp388, DEVHW_BMP388, BMP388_I2C_BUS, 0x76, NONE, DEVFLAGS_NONE);
|
||||
#endif
|
||||
#endif
|
||||
|
||||
#if defined(USE_BARO_SPL06)
|
||||
#if defined(SPL06_SPI_BUS)
|
||||
BUSDEV_REGISTER_SPI(busdev_spl06, DEVHW_SPL06, SPL06_SPI_BUS, SPL06_CS_PIN, NONE, DEVFLAGS_NONE);
|
||||
|
|
|
@ -40,6 +40,10 @@
|
|||
#define USE_CANVAS
|
||||
#endif
|
||||
|
||||
#ifdef USE_ESC_SENSOR
|
||||
#define USE_RPM_FILTER
|
||||
#endif
|
||||
|
||||
#ifdef USE_ITCM_RAM
|
||||
#define FAST_CODE __attribute__((section(".tcm_code")))
|
||||
#define NOINLINE __NOINLINE
|
||||
|
@ -54,6 +58,7 @@
|
|||
#undef USE_SERIALRX_SUMH
|
||||
#undef USE_SERIALRX_XBUS
|
||||
#undef USE_SERIALRX_JETIEXBUS
|
||||
#undef USE_PWM_SERVO_DRIVER
|
||||
#endif
|
||||
|
||||
#if defined(SIMULATOR_BUILD) || defined(UNIT_TEST)
|
||||
|
|
|
@ -413,11 +413,11 @@ uint32_t hse_value = HSE_VALUE;
|
|||
#endif /* STM32F401xx */
|
||||
|
||||
#if defined(STM32F410xx) || defined(STM32F411xE)
|
||||
#define PLL_N 336
|
||||
#define PLL_N 192
|
||||
/* SYSCLK = PLL_VCO / PLL_P */
|
||||
#define PLL_P 4
|
||||
#define PLL_P 2
|
||||
/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
|
||||
#define PLL_Q 7
|
||||
#define PLL_Q 4
|
||||
#endif /* STM32F410xx || STM32F411xE */
|
||||
|
||||
/******************************************************************************/
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue