mirror of
https://github.com/iNavFlight/inav.git
synced 2025-07-20 06:45:14 +03:00
Merge branch 'master' into dragnea_autolaunch_refactor
This commit is contained in:
commit
0739e08855
226 changed files with 9493 additions and 32397 deletions
12
.github/no-response.yml
vendored
Normal file
12
.github/no-response.yml
vendored
Normal file
|
@ -0,0 +1,12 @@
|
|||
# Configuration for probot-no-response - https://github.com/probot/no-response
|
||||
|
||||
# Number of days of inactivity before an Issue is closed for lack of response
|
||||
daysUntilClose: 3
|
||||
# Label requiring a response
|
||||
responseRequiredLabel: Missing Information
|
||||
# Comment to post when closing an Issue for lack of response. Set to `false` to disable
|
||||
closeComment: >
|
||||
This issue has been automatically closed because the information we asked
|
||||
to be provided when opening it was not supplied by the original author.
|
||||
With only the information that is currently in the issue, we don't have
|
||||
enough information to take action.
|
9
.gitignore
vendored
9
.gitignore
vendored
|
@ -12,10 +12,11 @@ startup_stm32f10x_md_gcc.s
|
|||
.vagrant/
|
||||
.vscode/
|
||||
cov-int*
|
||||
obj/
|
||||
patches/
|
||||
tools/
|
||||
downloads/
|
||||
/build/
|
||||
/obj/
|
||||
/patches/
|
||||
/tools/
|
||||
/downloads/
|
||||
|
||||
# script-generated files
|
||||
docs/Manual.pdf
|
||||
|
|
51
CMakeLists.txt
Normal file
51
CMakeLists.txt
Normal file
|
@ -0,0 +1,51 @@
|
|||
cmake_minimum_required(VERSION 3.17)
|
||||
|
||||
set(TOOLCHAIN_OPTIONS "arm-none-eabi")
|
||||
set(TOOLCHAIN "arm-none-eabi" CACHE STRING "Toolchain to use. Available: ${TOOLCHAIN_OPTIONS}")
|
||||
set_property(CACHE TOOLCHAIN PROPERTY STRINGS ${TOOLCHAIN_OPTIONS})
|
||||
if (NOT ${TOOLCHAIN} IN_LIST TOOLCHAIN_OPTIONS)
|
||||
message(FATAL_ERROR "Invalid toolchain ${TOOLCHAIN}")
|
||||
endif()
|
||||
|
||||
set(CMAKE_TOOLCHAIN_FILE "${CMAKE_CURRENT_SOURCE_DIR}/cmake/${TOOLCHAIN}.cmake")
|
||||
|
||||
project(INAV VERSION 2.5.0)
|
||||
|
||||
ENABLE_LANGUAGE(ASM)
|
||||
|
||||
set(CMAKE_C_STANDARD 99)
|
||||
set(CMAKE_C_EXTENSIONS ON)
|
||||
set(CMAKE_C_STANDARD_REQUIRED ON)
|
||||
set(CMAKE_CXX_STANDARD 11)
|
||||
set(CMAKE_CXX_EXTENSIONS ON)
|
||||
set(CMAKE_CXX_STANDARD_REQUIRED ON)
|
||||
|
||||
find_program(RUBY_EXECUTABLE ruby)
|
||||
if (NOT RUBY_EXECUTABLE)
|
||||
message(FATAL_ERROR "Could not find ruby")
|
||||
endif()
|
||||
|
||||
execute_process(COMMAND git rev-parse --short HEAD
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
RESULT_VARIABLE NO_GIT_HASH
|
||||
OUTPUT_VARIABLE GIT_SHORT_HASH)
|
||||
if (NO_GIT_HASH)
|
||||
message(FATAL_ERROR "Could not find git revision. Is git installed?")
|
||||
endif()
|
||||
|
||||
set(INAV_DIR "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||
set(INAV_LIB_DIR "${CMAKE_CURRENT_SOURCE_DIR}/lib")
|
||||
set(INAV_UTILS_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/utils")
|
||||
set(INAV_MAIN_SRC_DIR "${CMAKE_CURRENT_SOURCE_DIR}/src/main")
|
||||
|
||||
list(APPEND CMAKE_MODULE_PATH "${CMAKE_CURRENT_SOURCE_DIR}/cmake")
|
||||
|
||||
include(settings)
|
||||
include(inav)
|
||||
include(stm32)
|
||||
|
||||
add_subdirectory(src)
|
||||
|
||||
collect_targets()
|
||||
|
||||
message("-- Build type: ${CMAKE_BUILD_TYPE}")
|
118
Makefile
118
Makefile
|
@ -66,7 +66,9 @@ endif
|
|||
|
||||
# Working directories
|
||||
SRC_DIR := $(ROOT)/src/main
|
||||
BL_SRC_DIR := $(ROOT)/src/bl
|
||||
OBJECT_DIR := $(ROOT)/obj/main
|
||||
BL_OBJECT_DIR := $(ROOT)/obj/bl
|
||||
BIN_DIR := $(ROOT)/obj
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
INCLUDE_DIRS := $(SRC_DIR) \
|
||||
|
@ -93,8 +95,9 @@ FATFS_DIR = $(ROOT)/lib/main/FatFS
|
|||
FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
|
||||
|
||||
VPATH := $(SRC_DIR):$(SRC_DIR)/startup
|
||||
VPATH := $(VPATH):$(ROOT)/make/mcu
|
||||
VPATH := $(VPATH):$(ROOT)/make
|
||||
VPATH := $(VPATH):$(ROOT)/make/mcu
|
||||
VPATH := $(VPATH):$(ROOT)/make
|
||||
VPATH := $(VPATH):$(BL_SRC_DIR)
|
||||
|
||||
CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
|
||||
|
||||
|
@ -102,6 +105,12 @@ CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
|
|||
include $(ROOT)/make/mcu/STM32.mk
|
||||
include $(ROOT)/make/mcu/$(TARGET_MCU_GROUP).mk
|
||||
|
||||
BL_LD_SCRIPT := $(basename $(LD_SCRIPT))_bl.ld
|
||||
|
||||
ifneq ($(FOR_BL),)
|
||||
LD_SCRIPT := $(basename $(LD_SCRIPT))_for_bl.ld
|
||||
endif
|
||||
|
||||
# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already.
|
||||
ifeq ($(FLASH_SIZE),)
|
||||
ifneq ($(TARGET_FLASH),)
|
||||
|
@ -159,6 +168,7 @@ include $(ROOT)/make/tools.mk
|
|||
CROSS_CC = $(ARM_SDK_PREFIX)gcc
|
||||
OBJCOPY = $(ARM_SDK_PREFIX)objcopy
|
||||
SIZE = $(ARM_SDK_PREFIX)size
|
||||
COMBINE_TOOL := src/utils/combine_tool
|
||||
|
||||
#
|
||||
# Tool options.
|
||||
|
@ -209,6 +219,12 @@ CFLAGS += $(ARCH_FLAGS) \
|
|||
-save-temps=obj \
|
||||
-MMD -MP
|
||||
|
||||
BL_CFLAGS = -DMSP_FIRMWARE_UPDATE -DBOOTLOADER
|
||||
|
||||
ifneq ($(FOR_BL),)
|
||||
CFLAGS += -DMSP_FIRMWARE_UPDATE
|
||||
endif
|
||||
|
||||
ASFLAGS = $(ARCH_FLAGS) \
|
||||
-x assembler-with-cpp \
|
||||
$(addprefix -I,$(INCLUDE_DIRS)) \
|
||||
|
@ -232,6 +248,23 @@ LDFLAGS = -lm \
|
|||
-Wl,--print-memory-usage \
|
||||
-T$(LD_SCRIPT)
|
||||
|
||||
BL_LDFLAGS = -lm \
|
||||
-nostartfiles \
|
||||
--specs=nano.specs \
|
||||
-lc \
|
||||
$(SYSLIB) \
|
||||
$(ARCH_FLAGS) \
|
||||
$(LTO_FLAGS) \
|
||||
$(DEBUG_FLAGS) \
|
||||
$(SEMIHOSTING_LDFLAGS) \
|
||||
-static \
|
||||
-Wl,-gc-sections,-Map,$(TARGET_BL_MAP) \
|
||||
-Wl,-L$(LINKER_DIR) \
|
||||
-Wl,--cref \
|
||||
-Wl,--no-wchar-size-warning \
|
||||
-Wl,--print-memory-usage \
|
||||
-T$(BL_LD_SCRIPT)
|
||||
|
||||
###############################################################################
|
||||
# No user-serviceable parts below
|
||||
###############################################################################
|
||||
|
@ -246,30 +279,41 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \
|
|||
#
|
||||
TARGET_BIN := $(BIN_DIR)/$(FORKNAME)_$(FC_VER)
|
||||
TARGET_BIN := $(TARGET_BIN)_$(TARGET)
|
||||
TARGET_BL_BIN := $(TARGET_BIN)_bl
|
||||
ifneq ($(BUILD_SUFFIX),)
|
||||
TARGET_BIN := $(TARGET_BIN)_$(BUILD_SUFFIX)
|
||||
TARGET_BL_BIN := $(TARGET_BL_BIN)_$(BUILD_SUFFIX)
|
||||
endif
|
||||
TARGET_BIN := $(TARGET_BIN).bin
|
||||
TARGET_BL_BIN := $(TARGET_BL_BIN).bin
|
||||
TARGET_HEX = $(TARGET_BIN:.bin=.hex)
|
||||
TARGET_BL_HEX = $(TARGET_BL_BIN:.bin=.hex)
|
||||
TARGET_COMBINED_HEX = $(basename $(TARGET_HEX))_combined.hex
|
||||
|
||||
TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET)
|
||||
TARGET_BL_OBJ_DIR = $(BL_OBJECT_DIR)/$(TARGET)
|
||||
TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
||||
TARGET_BL_ELF = $(BL_OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
||||
TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC))))
|
||||
TARGET_BL_OBJS = $(addsuffix .o,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC))))
|
||||
TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(TARGET_SRC))))
|
||||
TARGET_BL_DEPS = $(addsuffix .d,$(addprefix $(TARGET_BL_OBJ_DIR)/,$(basename $(TARGET_BL_SRC))))
|
||||
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||
TARGET_BL_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_bl.map
|
||||
|
||||
|
||||
CLEAN_ARTIFACTS := $(TARGET_BIN)
|
||||
CLEAN_ARTIFACTS += $(TARGET_HEX)
|
||||
CLEAN_ARTIFACTS += $(TARGET_ELF)
|
||||
CLEAN_ARTIFACTS += $(TARGET_OBJS) $(TARGET_MAP)
|
||||
CLEAN_ARTIFACTS += $(TARGET_BL_BIN) $(TARGET_BL_HEX) $(TARGET_BL_ELF) $(TARGET_BL_OBJS) $(TARGET_BL_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)
|
||||
$(TARGET_OBJ_DIR)/build/version.o $(TARGET_BL_OBJ_DIR)/build/version.o: $(TARGET_SRC)
|
||||
|
||||
# CFLAGS used for ASM generation. These can't include the LTO related options
|
||||
# since they prevent proper ASM generation. Since $(LTO_FLAGS) includes the
|
||||
|
@ -291,6 +335,17 @@ $(TARGET_ELF): $(TARGET_OBJS)
|
|||
$(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(LDFLAGS)
|
||||
$(V0) $(SIZE) $(TARGET_ELF)
|
||||
|
||||
$(TARGET_BL_HEX): $(TARGET_BL_ELF)
|
||||
$(V0) $(OBJCOPY) -O ihex --set-start $(FLASH_ORIGIN) $< $@
|
||||
|
||||
$(TARGET_BL_BIN): $(TARGET_BL_ELF)
|
||||
$(V0) $(OBJCOPY) -O binary $< $@
|
||||
|
||||
$(TARGET_BL_ELF): $(TARGET_BL_OBJS)
|
||||
$(V1) echo Linking $(TARGET) bl
|
||||
$(V1) $(CROSS_CC) -o $@ $(filter %.o, $^) $(BL_LDFLAGS)
|
||||
$(V0) $(SIZE) $(TARGET_BL_ELF)
|
||||
|
||||
OPTIMIZE_FLAG_SPEED := "-Os"
|
||||
OPTIMIZE_FLAG_SIZE := "-Os"
|
||||
OPTIMIZE_FLAG_NORMAL := "-Os"
|
||||
|
@ -306,6 +361,11 @@ define compile_file
|
|||
$(CROSS_CC) -c -o $@ $(CFLAGS) $(2) $<
|
||||
endef
|
||||
|
||||
define compile_bl_file
|
||||
echo "%% $(1) $(2) $<" "$(STDOUT)" && \
|
||||
$(CROSS_CC) -c -o $@ $(CFLAGS) $(BL_CFLAGS) $(2) $<
|
||||
endef
|
||||
|
||||
# Compile
|
||||
$(TARGET_OBJ_DIR)/%.o: %.c
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
|
@ -323,13 +383,29 @@ ifeq ($(GENERATE_ASM), 1)
|
|||
$(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $<
|
||||
endif
|
||||
|
||||
$(TARGET_BL_OBJ_DIR)/%.o: %.c
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
|
||||
$(V1) $(if $(findstring $<,$(SIZE_OPTIMISED_SRC)), \
|
||||
$(call compile_bl_file,(size),$(OPTIMIZE_FLAG_SIZE)) \
|
||||
, \
|
||||
$(if $(findstring $<,$(SPEED_OPTIMISED_SRC)), \
|
||||
$(call compile_bl_file,(speed),$(OPTIMIZE_FLAG_SPEED)) \
|
||||
, \
|
||||
$(call compile_bl_file,(normal),$(OPTIMIZE_FLAG_NORMAL)) \
|
||||
) \
|
||||
)
|
||||
ifeq ($(GENERATE_ASM), 1)
|
||||
$(V1) $(CROSS_CC) -S -fverbose-asm -Wa,-aslh -o $(patsubst %.o,%.txt.S,$@) -g $(ASM_CFLAGS) $(BL_CFLAGS) $<
|
||||
endif
|
||||
|
||||
# Assemble
|
||||
$(TARGET_OBJ_DIR)/%.o: %.s
|
||||
$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.s
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo %% $(notdir $<) "$(STDOUT)"
|
||||
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||
|
||||
$(TARGET_OBJ_DIR)/%.o: %.S
|
||||
$(TARGET_OBJ_DIR)/%.o $(TARGET_BL_OBJ_DIR)/%.o: %.S
|
||||
$(V1) mkdir -p $(dir $@)
|
||||
$(V1) echo %% $(notdir $<) "$(STDOUT)"
|
||||
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||
|
@ -355,6 +431,31 @@ $(VALID_TARGETS):
|
|||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$@ && \
|
||||
echo "Building $@ succeeded."
|
||||
|
||||
$(VALID_BL_TARGETS):
|
||||
$(V0) echo "" && \
|
||||
echo "Building $@" && \
|
||||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_bl=%) bl_binary bl_hex && \
|
||||
echo "Building $(@:%_bl=%) bl succeeded."
|
||||
|
||||
$(VALID_TARGETS_FOR_BL):
|
||||
$(V0) echo "" && \
|
||||
echo "Building $@" && \
|
||||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(@:%_for_bl=%) FOR_BL=1 binary hex && \
|
||||
echo "Building $(@:%_for_bl=%) for bl succeeded."
|
||||
|
||||
$(VALID_TARGETS_WITH_BL):
|
||||
$(V0) echo "" && \
|
||||
echo "Building $@ with bl" && \
|
||||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) TARGET=$(@:%_with_bl=%) combined_hex && \
|
||||
echo "Building $(@:%_with_bl=%) with bl succeeded."
|
||||
|
||||
combined_hex:
|
||||
$(V1) echo "Building combined BL+MAIN hex" && \
|
||||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) bl_binary && \
|
||||
CFLAGS=$(SAVED_CFLAGS) $(MAKE) -j 8 TARGET=$(TARGET) binary FOR_BL=1 && \
|
||||
echo "Combining MAIN+BL in $(TARGET_COMBINED_HEX)" && \
|
||||
$(COMBINE_TOOL) $(TARGET_BL_BIN) $(TARGET_BIN) $(TARGET_COMBINED_HEX)
|
||||
|
||||
## clean : clean up all temporary / machine-generated files
|
||||
clean:
|
||||
$(V0) echo "Cleaning $(TARGET)"
|
||||
|
@ -364,7 +465,7 @@ clean:
|
|||
|
||||
## clean_test : clean up all temporary / machine-generated files (tests)
|
||||
clean_test:
|
||||
$(V0) cd src/test && $(MAKE) clean
|
||||
$(V0) $(RM) -r src/test/build
|
||||
|
||||
## clean_<TARGET> : clean up one specific target
|
||||
$(CLEAN_TARGETS) :
|
||||
|
@ -398,6 +499,9 @@ st-flash: $(TARGET_BIN)
|
|||
elf: $(TARGET_ELF)
|
||||
binary: $(TARGET_BIN)
|
||||
hex: $(TARGET_HEX)
|
||||
bl_elf: $(TARGET_BL_ELF)
|
||||
bl_binary: $(TARGET_BL_BIN)
|
||||
bl_hex: $(TARGET_BL_HEX)
|
||||
|
||||
unbrick_$(TARGET): $(TARGET_HEX)
|
||||
$(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon
|
||||
|
@ -429,7 +533,7 @@ help: Makefile
|
|||
|
||||
## test : run the cleanflight test suite
|
||||
test:
|
||||
$(V0) cd src/test && $(MAKE) test
|
||||
$(V0) mkdir -p src/test/build && cd src/test/build && cmake .. && $(MAKE) check
|
||||
|
||||
# rebuild everything when makefile changes
|
||||
# Make the generated files and the build stamp order only prerequisites,
|
||||
|
|
63
cmake/arm-none-eabi.cmake
Normal file
63
cmake/arm-none-eabi.cmake
Normal file
|
@ -0,0 +1,63 @@
|
|||
set(CMAKE_SYSTEM_NAME Generic)
|
||||
set(CMAKE_SYSTEM_PROCESSOR arm)
|
||||
|
||||
if(WIN32)
|
||||
set(TOOL_EXECUTABLE_SUFFIX ".exe")
|
||||
endif()
|
||||
|
||||
set(TARGET_TRIPLET "arm-none-eabi")
|
||||
set(gcc "${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}")
|
||||
|
||||
find_program(GCC "${gcc}")
|
||||
if (NOT GCC)
|
||||
message(FATAL_ERROR "Could not find ${gcc}")
|
||||
endif()
|
||||
|
||||
set(ARM_NONE_EABI_GCC_VERSION 9.2.1)
|
||||
|
||||
execute_process(COMMAND "${GCC}" -dumpversion
|
||||
OUTPUT_STRIP_TRAILING_WHITESPACE
|
||||
OUTPUT_VARIABLE GCC_VERSION)
|
||||
|
||||
if (NOT ${ARM_NONE_EABI_GCC_VERSION} STREQUAL ${GCC_VERSION})
|
||||
# TODO: Show how to override on cmdline or install builtin compiler
|
||||
message(FATAL_ERROR "Expecting gcc version ${ARM_NONE_EABI_GCC_VERSION}, but found ${GCC_VERSION}")
|
||||
endif()
|
||||
|
||||
get_filename_component(TOOLCHAIN_BIN_DIR "${GCC}" DIRECTORY)
|
||||
|
||||
set(CMAKE_TRY_COMPILE_TARGET_TYPE STATIC_LIBRARY)
|
||||
set(CMAKE_ASM_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "asm compiler")
|
||||
set(CMAKE_C_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gcc${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c compiler")
|
||||
set(CMAKE_CXX_COMPILER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-g++${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++ compiler")
|
||||
set(CMAKE_OBJCOPY "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objcopy${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objcopy tool")
|
||||
set(CMAKE_OBJDUMP "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-objdump${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "objdump tool")
|
||||
set(CMAKE_SIZE "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-size${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "size tool")
|
||||
set(CMAKE_DEBUGER "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-gdb${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "debuger")
|
||||
set(CMAKE_CPPFILT "${TOOLCHAIN_BIN_DIR}/${TARGET_TRIPLET}-c++filt${TOOL_EXECUTABLE_SUFFIX}" CACHE INTERNAL "c++filt")
|
||||
set(CMAKE_FIND_ROOT_PATH_MODE_PROGRAM NEVER)
|
||||
set(CMAKE_FIND_ROOT_PATH_MODE_LIBRARY ONLY)
|
||||
set(CMAKE_FIND_ROOT_PATH_MODE_INCLUDE ONLY)
|
||||
set(CMAKE_EXECUTABLE_SUFFIX ".elf")
|
||||
|
||||
if(NOT CMAKE_CONFIGURATION_TYPES)
|
||||
set(CMAKE_CONFIGURATION_TYPES Debug Release RelWithDebInfo)
|
||||
endif()
|
||||
set(CMAKE_BUILD_TYPE RelWithDebInfo CACHE STRING "Build Type" FORCE)
|
||||
set_property(CACHE CMAKE_BUILD_TYPE PROPERTY STRINGS ${CMAKE_CONFIGURATION_TYPES})
|
||||
|
||||
set(arm_none_eabi_debug "-Og -g")
|
||||
set(arm_none_eabi_release "-O2 -DNDEBUG -flto -fuse-linker-plugin")
|
||||
set(arm_none_eabi_relwithdebinfo "-ggdb3 ${arm_none_eabi_release}")
|
||||
|
||||
SET(CMAKE_C_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c compiler flags debug")
|
||||
SET(CMAKE_CXX_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "c++ compiler flags debug")
|
||||
SET(CMAKE_ASM_FLAGS_DEBUG ${arm_none_eabi_debug} CACHE INTERNAL "asm compiler flags debug")
|
||||
|
||||
SET(CMAKE_C_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "c compiler flags release")
|
||||
SET(CMAKE_CXX_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "cxx compiler flags release")
|
||||
SET(CMAKE_ASM_FLAGS_RELEASE ${arm_none_eabi_release} CACHE INTERNAL "asm compiler flags release")
|
||||
|
||||
SET(CMAKE_C_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "c compiler flags release")
|
||||
SET(CMAKE_CXX_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "cxx compiler flags release")
|
||||
SET(CMAKE_ASM_FLAGS_RELWITHDEBINFO ${arm_none_eabi_relwithdebinfo} CACHE INTERNAL "asm compiler flags release")
|
65
cmake/inav.cmake
Normal file
65
cmake/inav.cmake
Normal file
|
@ -0,0 +1,65 @@
|
|||
set(INAV_INCLUDE_DIRS
|
||||
"${INAV_LIB_DIR}"
|
||||
"${INAV_MAIN_SRC_DIR}"
|
||||
"${INAV_LIB_DIR}/main/MAVLink"
|
||||
)
|
||||
|
||||
# TODO: We need a way to override HSE_VALUE
|
||||
set(INAV_DEFINITIONS
|
||||
__FORKNAME__=inav
|
||||
__REVISION__="${GIT_SHORT_HASH}"
|
||||
HSE_VALUE=8000000
|
||||
)
|
||||
|
||||
set(INAV_COMPILE_OPTIONS
|
||||
-Wall
|
||||
-Wextra
|
||||
-Wunsafe-loop-optimizations
|
||||
-Wdouble-promotion
|
||||
-Wstrict-prototypes
|
||||
-Werror=switch
|
||||
)
|
||||
|
||||
macro(main_sources) # list-var
|
||||
list(TRANSFORM ${ARGV0} PREPEND "${INAV_MAIN_SRC_DIR}/")
|
||||
endmacro()
|
||||
|
||||
macro(exclude_basenames) # list-var excludes-var
|
||||
set(_filtered "")
|
||||
foreach(item ${${ARGV0}})
|
||||
get_filename_component(basename ${item} NAME)
|
||||
if (NOT ${basename} IN_LIST ${ARGV1})
|
||||
list(APPEND _filtered ${item})
|
||||
endif()
|
||||
endforeach()
|
||||
set(${ARGV0} ${_filtered})
|
||||
endmacro()
|
||||
|
||||
macro(glob_except) # var-name pattern excludes-var
|
||||
file(GLOB ${ARGV0} ${ARGV1})
|
||||
exclude_basenames(${ARGV0} ${ARGV2})
|
||||
endmacro()
|
||||
|
||||
function(setup_firmware_target name)
|
||||
target_compile_options(${name} PRIVATE ${INAV_COMPILE_OPTIONS})
|
||||
target_include_directories(${name} PRIVATE ${INAV_INCLUDE_DIRS})
|
||||
target_compile_definitions(${name} PRIVATE ${INAV_DEFINITIONS} __TARGET__="${name}")
|
||||
enable_settings(${name})
|
||||
# XXX: Don't make SETTINGS_GENERATED_C part of the build,
|
||||
# since it's compiled via #include in settings.c. This will
|
||||
# change once we move off PGs
|
||||
target_sources(${name} PRIVATE "${CMAKE_CURRENT_BINARY_DIR}/${name}/${SETTINGS_GENERATED_H}")
|
||||
set_target_properties(${name} PROPERTIES
|
||||
RUNTIME_OUTPUT_DIRECTORY "${CMAKE_BINARY_DIR}/bin"
|
||||
)
|
||||
get_property(targets GLOBAL PROPERTY VALID_TARGETS)
|
||||
set_property(GLOBAL PROPERTY VALID_TARGETS "${targets} ${name}")
|
||||
endfunction()
|
||||
|
||||
function(collect_targets)
|
||||
get_property(targets GLOBAL PROPERTY VALID_TARGETS)
|
||||
list(SORT targets)
|
||||
add_custom_target("targets"
|
||||
COMMAND cmake -E echo "Valid targets: ${targets}")
|
||||
set_property(TARGET "targets" PROPERTY TARGET_MESSAGES OFF)
|
||||
endfunction()
|
25
cmake/settings.cmake
Normal file
25
cmake/settings.cmake
Normal file
|
@ -0,0 +1,25 @@
|
|||
set(SETTINGS_GENERATED "settings_generated")
|
||||
set(SETTINGS_GENERATED_C "${SETTINGS_GENERATED}.c")
|
||||
set(SETTINGS_GENERATED_H "${SETTINGS_GENERATED}.h")
|
||||
set(SETTINGS_FILE "${INAV_MAIN_SRC_DIR}/fc/settings.yaml")
|
||||
set(SETTINGS_GENERATOR "${INAV_UTILS_DIR}/settings.rb")
|
||||
|
||||
function(enable_settings target)
|
||||
set(dir "${CMAKE_CURRENT_BINARY_DIR}/${target}")
|
||||
target_include_directories(${target} PRIVATE ${dir})
|
||||
get_target_property(options ${target} COMPILE_OPTIONS)
|
||||
get_target_property(includes ${target} INCLUDE_DIRECTORIES)
|
||||
list(TRANSFORM includes PREPEND "-I")
|
||||
get_target_property(defs ${target} COMPILE_DEFINITIONS)
|
||||
list(TRANSFORM defs PREPEND "-D")
|
||||
list(APPEND cflags ${options})
|
||||
list(APPEND cflags ${includes})
|
||||
list(APPEND cflags ${defs})
|
||||
add_custom_command(
|
||||
OUTPUT ${dir}/${SETTINGS_GENERATED_H} ${dir}/${SETTINGS_GENERATED_C}
|
||||
COMMAND
|
||||
${CMAKE_COMMAND} -E env CFLAGS="${cflags}" TARGET=${target}
|
||||
${RUBY_EXECUTABLE} ${SETTINGS_GENERATOR} ${INAV_DIR} ${SETTINGS_FILE} -o "${dir}"
|
||||
DEPENDS ${SETTINGS_GENERATOR} ${SETTINGS_FILE}
|
||||
)
|
||||
endfunction()
|
65
cmake/stm32-usb.cmake
Normal file
65
cmake/stm32-usb.cmake
Normal file
|
@ -0,0 +1,65 @@
|
|||
set(STM32_STDPERIPH_USBOTG_DIR "${INAV_LIB_DIR}/main/STM32_USB_OTG_Driver")
|
||||
set(STM32_STDPERIPH_USBCORE_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Core")
|
||||
set(STM32_STDPERIPH_USBCDC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/cdc")
|
||||
set(STM32_STDPERIPH_USBHID_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid")
|
||||
set(STM32_STDPERIPH_USBWRAPPER_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper")
|
||||
set(STM32_STDPERIPH_USBMSC_DIR "${INAV_LIB_DIR}/main/STM32_USB_Device_Library/Class/msc")
|
||||
set(STM32_STDPERIPH_USBFS_DIR "${INAV_LIB_DIR}/main/STM32_USB-FS-Device_Driver")
|
||||
|
||||
set(STM32_STDPERIPH_USB_INCLUDE_DIRS
|
||||
"${STM32_STDPERIPH_USBOTG_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBCORE_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBCDC_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBHID_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBWRAPPER_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBMSC_DIR}/inc"
|
||||
"${STM32_STDPERIPH_USBFS_DIR}/inc"
|
||||
)
|
||||
|
||||
SET(STM32_STDPERIPH_USBOTG_SRC_EXCLUDES
|
||||
usb_bsp_template.c
|
||||
usb_conf_template.c
|
||||
usb_hcd_int.c
|
||||
usb_hcd.c
|
||||
usb_otg.c
|
||||
)
|
||||
set(STM32_STDPERIPH_USBOTG_SRC
|
||||
usb_core.c
|
||||
usb_dcd.c
|
||||
usb_dcd_int.c
|
||||
)
|
||||
list(TRANSFORM STM32_STDPERIPH_USBOTG_SRC PREPEND "${STM32_STDPERIPH_USBOTG_DIR}/src/")
|
||||
|
||||
set(STM32_STDPERIPH_USBCORE_SRC
|
||||
usbd_core.c
|
||||
usbd_ioreq.c
|
||||
usbd_req.c
|
||||
)
|
||||
list(TRANSFORM STM32_STDPERIPH_USBCORE_SRC PREPEND "${STM32_STDPERIPH_USBCORE_DIR}/src/")
|
||||
|
||||
set(STM32_STDPERIPH_USBCDC_SRC
|
||||
"${STM32_STDPERIPH_USBCDC_DIR}/src/usbd_cdc_core.c"
|
||||
)
|
||||
|
||||
set(STM32_STDPERIPH_USBHID_SRC
|
||||
"${STM32_STDPERIPH_USBHID_DIR}/src/usbd_hid_core.c"
|
||||
)
|
||||
|
||||
set(STM32_STDPERIPH_USBWRAPPER_SRC
|
||||
"${STM32_STDPERIPH_USBWRAPPER_DIR}/src/usbd_hid_cdc_wrapper.c"
|
||||
)
|
||||
|
||||
set(STM32_STDPERIPH_USBMSC_SRC
|
||||
usbd_msc_bot.c
|
||||
usbd_msc_core.c
|
||||
usbd_msc_data.c
|
||||
usbd_msc_scsi.c
|
||||
)
|
||||
list(TRANSFORM STM32_STDPERIPH_USBMSC_SRC PREPEND "${STM32_STDPERIPH_USBMSC_DIR}/src/")
|
||||
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBOTG_SRC})
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCORE_SRC})
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBCDC_SRC})
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBHID_SRC})
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBWRAPPER_SRC})
|
||||
list(APPEND STM32_STDPERIPH_USB_SRC ${STM32_STDPERIPH_USBMSC_SRC})
|
263
cmake/stm32.cmake
Normal file
263
cmake/stm32.cmake
Normal file
|
@ -0,0 +1,263 @@
|
|||
include(arm-none-eabi)
|
||||
include(stm32-usb)
|
||||
|
||||
set(CMSIS_DIR "${INAV_LIB_DIR}/main/CMSIS")
|
||||
set(CMSIS_INCLUDE_DIR "${CMSIS_DIR}/Core/Include")
|
||||
set(CMSIS_DSP_DIR "${INAV_LIB_DIR}/main/CMSIS/DSP")
|
||||
set(CMSIS_DSP_INCLUDE_DIR "${CMSIS_DSP_DIR}/Include")
|
||||
|
||||
set(CMSIS_DSP_SRC
|
||||
BasicMathFunctions/arm_mult_f32.c
|
||||
TransformFunctions/arm_rfft_fast_f32.c
|
||||
TransformFunctions/arm_cfft_f32.c
|
||||
TransformFunctions/arm_rfft_fast_init_f32.c
|
||||
TransformFunctions/arm_cfft_radix8_f32.c
|
||||
TransformFunctions/arm_bitreversal2.S
|
||||
CommonTables/arm_common_tables.c
|
||||
ComplexMathFunctions/arm_cmplx_mag_f32.c
|
||||
StatisticsFunctions/arm_max_f32.c
|
||||
)
|
||||
list(TRANSFORM CMSIS_DSP_SRC PREPEND "${CMSIS_DSP_DIR}/Source/")
|
||||
|
||||
set(STM32_STARTUP_DIR "${INAV_MAIN_SRC_DIR}/startup")
|
||||
|
||||
set(STM32_VCP_SRC
|
||||
drivers/serial_usb_vcp.c
|
||||
drivers/usb_io.c
|
||||
)
|
||||
main_sources(STM32_VCP_SRC)
|
||||
|
||||
set(STM32_MSC_SRC
|
||||
msc/usbd_msc_desc.c
|
||||
msc/usbd_storage.c
|
||||
)
|
||||
main_sources(STM32_MSC_SRC)
|
||||
|
||||
set(STM32_MSC_FLASH_SRC
|
||||
msc/usbd_storage_emfat.c
|
||||
msc/emfat.c
|
||||
msc/emfat_file.c
|
||||
)
|
||||
main_sources(STM32_MSC_FLASH_SRC)
|
||||
|
||||
set(STM32F4_STDPERIPH_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver")
|
||||
set(STM32F4_CMSIS_DEVICE_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx")
|
||||
set(STM32F4_CMSIS_DRIVERS_DIR "${INAV_LIB_DIR}/main/STM32F4/Drivers/CMSIS")
|
||||
set(STM32F4_VCP_DIR "${INAV_MAIN_SRC_DIR}/vcpf4")
|
||||
|
||||
set(STM32F4_STDPERIPH_SRC_EXCLUDES
|
||||
stm32f4xx_can.c
|
||||
stm32f4xx_cec.c
|
||||
stm32f4xx_crc.c
|
||||
stm32f4xx_cryp.c
|
||||
stm32f4xx_cryp_aes.c
|
||||
stm32f4xx_cryp_des.c
|
||||
stm32f4xx_cryp_tdes.c
|
||||
stm32f4xx_dbgmcu.c
|
||||
stm32f4xx_dsi.c
|
||||
stm32f4xx_flash_ramfunc.c
|
||||
stm32f4xx_fmpi2c.c
|
||||
stm32f4xx_fmc.c
|
||||
stm32f4xx_hash.c
|
||||
stm32f4xx_hash_md5.c
|
||||
stm32f4xx_hash_sha1.c
|
||||
stm32f4xx_lptim.c
|
||||
stm32f4xx_qspi.c
|
||||
stm32f4xx_sai.c
|
||||
stm32f4xx_spdifrx.c
|
||||
)
|
||||
|
||||
set(STM32F4_STDPERIPH_SRC_DIR "${STM32F4_STDPERIPH_DIR}/Src")
|
||||
glob_except(STM32F4_STDPERIPH_SRC "${STM32F4_STDPERIPH_SRC_DIR}/*.c" STM32F4_STDPERIPH_SRC_EXCLUDES)
|
||||
|
||||
set(STM32F4_VCP_SRC
|
||||
stm32f4xx_it.c
|
||||
usb_bsp.c
|
||||
usbd_desc.c
|
||||
usbd_usr.c
|
||||
usbd_cdc_vcp.c
|
||||
)
|
||||
list(TRANSFORM STM32F4_VCP_SRC PREPEND "${STM32F4_VCP_DIR}/")
|
||||
|
||||
set(STM32F4_MSC_SRC
|
||||
drivers/usb_msc_f4xx.c
|
||||
)
|
||||
main_sources(STM32F4_MSC_SRC)
|
||||
|
||||
set(STM32F4_INCLUDE_DIRS
|
||||
"${CMSIS_INCLUDE_DIR}"
|
||||
"${CMSIS_DSP_INCLUDE_DIR}"
|
||||
"${STM32F4_STDPERIPH_DIR}/inc"
|
||||
"${STM32F4_CMSIS_DEVICE_DIR}"
|
||||
"${STM32F4_CMSIS_DRIVERS_DIR}"
|
||||
"${STM32F4_VCP_DIR}"
|
||||
)
|
||||
|
||||
set(STM32_INCLUDE_DIRS
|
||||
"${INAV_MAIN_SRC_DIR}/target"
|
||||
)
|
||||
|
||||
set(STM32_LINKER_DIR "${INAV_MAIN_SRC_DIR}/target/link")
|
||||
|
||||
#if(SEMIHOSTING)
|
||||
# set(SEMIHOSTING_DEFINITIONS "SEMIHOSTING")
|
||||
# set(SEMIHOSTING_LDFLAGS
|
||||
# --specs=rdimon.specs
|
||||
# -lc
|
||||
# -lrdimon
|
||||
# )
|
||||
#else()
|
||||
# set(SYS)
|
||||
#endif()
|
||||
#ifneq ($(SEMIHOSTING),)
|
||||
#SEMIHOSTING_CFLAGS = -DSEMIHOSTING
|
||||
#SEMIHOSTING_LDFLAGS = --specs=rdimon.specs -lc -lrdimon
|
||||
#SYSLIB :=
|
||||
#else
|
||||
#SEMIHOSTING_LDFLAGS =
|
||||
#SEMIHOSTING_CFLAGS =
|
||||
#SYSLIB := -lnosys
|
||||
#endif
|
||||
|
||||
set(STM32_LINK_LIBRARIES
|
||||
-lm
|
||||
-lc
|
||||
)
|
||||
|
||||
set(STM32_LINK_OPTIONS
|
||||
-nostartfiles
|
||||
--specs=nano.specs
|
||||
-static
|
||||
-Wl,-gc-sections,-Map,target.map
|
||||
-Wl,-L${STM32_LINKER_DIR}
|
||||
-Wl,--cref
|
||||
-Wl,--no-wchar-size-warning
|
||||
-Wl,--print-memory-usage
|
||||
)
|
||||
|
||||
set(STM32F4_SRC
|
||||
target/system_stm32f4xx.c
|
||||
drivers/accgyro/accgyro.c
|
||||
drivers/accgyro/accgyro_mpu.c
|
||||
drivers/adc_stm32f4xx.c
|
||||
drivers/adc_stm32f4xx.c
|
||||
drivers/bus_i2c_stm32f40x.c
|
||||
drivers/serial_softserial.c
|
||||
drivers/serial_uart_stm32f4xx.c
|
||||
drivers/system_stm32f4xx.c
|
||||
drivers/timer.c
|
||||
drivers/timer_impl_stdperiph.c
|
||||
drivers/timer_stm32f4xx.c
|
||||
drivers/uart_inverter.c
|
||||
drivers/dma_stm32f4xx.c
|
||||
drivers/sdcard/sdmmc_sdio_f4xx.c
|
||||
)
|
||||
|
||||
main_sources(STM32F4_SRC)
|
||||
|
||||
set(STM32F4_DEFINITIONS
|
||||
STM32F4
|
||||
USE_STDPERIPH_DRIVER
|
||||
ARM_MATH_MATRIX_CHECK
|
||||
ARM_MATH_ROUNDING
|
||||
__FPU_PRESENT=1
|
||||
UNALIGNED_SUPPORT_DISABLE
|
||||
ARM_MATH_CM4
|
||||
)
|
||||
|
||||
set(STM32F4_COMMON_OPTIONS
|
||||
-mthumb
|
||||
-mcpu=cortex-m4
|
||||
-march=armv7e-m
|
||||
-mfloat-abi=hard
|
||||
-mfpu=fpv4-sp-d16
|
||||
-fsingle-precision-constant
|
||||
)
|
||||
|
||||
set(STM32F4_COMPILE_OPTIONS
|
||||
)
|
||||
|
||||
set(SETM32F4_LINK_OPTIONS
|
||||
)
|
||||
|
||||
set(STM32F411_STDPERIPH_SRC_EXCLUDES "stm32f4xx_fsmc.c")
|
||||
|
||||
set(STM32F411_COMPILE_DEFINITIONS
|
||||
FLASH_SIZE=512
|
||||
)
|
||||
|
||||
macro(get_stm32_target_features) # out-var dir
|
||||
file(READ "${ARGV1}/target.h" _contents)
|
||||
string(REGEX MATCH "#define[\t ]+USE_VCP" HAS_VCP ${_contents})
|
||||
if(HAS_VCP)
|
||||
list(APPEND ${ARGV0} VCP)
|
||||
endif()
|
||||
string(REGEX MATCH "define[\t ]+USE_FLASHFS" HAS_FLASHFS ${_contents})
|
||||
if(HAS_FLASHFS)
|
||||
list(APPEND ${ARGV0} FLASHFS)
|
||||
endif()
|
||||
if (HAS_FLASHFS) # || SDCARD
|
||||
list(APPEND ${ARGV0} MSC)
|
||||
endif()
|
||||
endmacro()
|
||||
|
||||
function(target_stm32 name)
|
||||
# Main .elf target
|
||||
add_executable(${name} ${COMMON_SRC} ${CMSIS_DSP_SRC})
|
||||
file(GLOB target_c_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.c")
|
||||
file(GLOB target_h_sources "${CMAKE_CURRENT_SOURCE_DIR}/*.h")
|
||||
target_sources(${name} PRIVATE ${target_c_sources} ${target_h_sources})
|
||||
target_include_directories(${name} PRIVATE . ${STM32_INCLUDE_DIRS})
|
||||
target_link_libraries(${name} PRIVATE ${STM32_LINK_LIBRARIES})
|
||||
target_link_options(${name} PRIVATE ${STM32_LINK_OPTIONS})
|
||||
get_stm32_target_features(features "${CMAKE_CURRENT_SOURCE_DIR}")
|
||||
set_property(TARGET ${name} PROPERTY FEATURES ${features})
|
||||
if(VCP IN_LIST features)
|
||||
target_sources(${name} PRIVATE ${STM32_VCP_SRC})
|
||||
endif()
|
||||
if(MSC IN_LIST features)
|
||||
target_sources(${name} PRIVATE ${STM32_MSC_SRC})
|
||||
if (FLASHFS IN_LIST features)
|
||||
target_sources(${name} PRIVATE ${STM32_MSC_FLASH_SRC})
|
||||
endif()
|
||||
endif()
|
||||
# Generate .hex
|
||||
set(hexdir "${CMAKE_BINARY_DIR}/hex")
|
||||
set(hex "${hexdir}/$<TARGET_FILE_PREFIX:${name}>.hex")
|
||||
add_custom_command(TARGET ${name} POST_BUILD
|
||||
COMMAND ${CMAKE_COMMAND} -E make_directory "${hexdir}"
|
||||
COMMAND ${CMAKE_OBJCOPY} -Oihex $<TARGET_FILE:${name}> "${hex}")
|
||||
# clean_<target>
|
||||
set(clean_target "clean_${name}")
|
||||
add_custom_target(${clean_target}
|
||||
COMMAND cmake -E rm -r "${CMAKE_CURRENT_BINARY_DIR}"
|
||||
COMMENT "Removeng intermediate files for ${name}")
|
||||
set_property(TARGET ${clean_target} PROPERTY TARGET_MESSAGES OFF)
|
||||
endfunction()
|
||||
|
||||
function(target_stm32f4xx name)
|
||||
target_stm32(${name})
|
||||
target_sources(${name} PRIVATE ${STM32F4_SRC})
|
||||
target_compile_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_COMPILE_OPTIONS})
|
||||
target_include_directories(${name} PRIVATE ${STM32_STDPERIPH_USB_INCLUDE_DIRS} ${STM32F4_INCLUDE_DIRS})
|
||||
target_compile_definitions(${name} PRIVATE ${STM32F4_DEFINITIONS})
|
||||
target_link_options(${name} PRIVATE ${STM32F4_COMMON_OPTIONS} ${STM32F4_LINK_OPTIONS})
|
||||
|
||||
get_property(features TARGET ${name} PROPERTY FEATURES)
|
||||
if(VCP IN_LIST features)
|
||||
target_sources(${name} PRIVATE ${STM32_STDPERIPH_USB_SRC} ${STM32F4_VCP_SRC})
|
||||
endif()
|
||||
if(MSC IN_LIST features)
|
||||
target_sources(${name} PRIVATE ${STM32F4_MSC_SRC})
|
||||
endif()
|
||||
endfunction()
|
||||
|
||||
function(target_stm32f411 name)
|
||||
target_stm32f4xx(${name})
|
||||
set(STM32F411_STDPERIPH_SRC ${STM32F4_STDPERIPH_SRC})
|
||||
exclude_basenames(STM32F411_STDPERIPH_SRC STM32F411_STDPERIPH_SRC_EXCLUDES)
|
||||
target_sources(${name} PRIVATE "${STM32_STARTUP_DIR}/startup_stm32f411xe.s" ${STM32F411_STDPERIPH_SRC})
|
||||
target_link_options(${name} PRIVATE "-T${STM32_LINKER_DIR}/stm32_flash_f411.ld")
|
||||
target_compile_definitions(${name} PRIVATE STM32F411xE ${STM32F411_COMPILE_DEFINITIONS})
|
||||
setup_firmware_target(${name})
|
||||
endfunction()
|
|
@ -97,7 +97,7 @@ This board use the STM32F405RGT6 microcontroller and have the following features
|
|||
| 3 | SWDIO | PAD |
|
||||
| 4 | 3V3 | PAD |
|
||||
|
||||
###Designers
|
||||
### Designers
|
||||
* ZhengNyway(nyway@vip.qq.com) FROM DALRC
|
||||
|
||||
|
||||
|
|
|
@ -102,7 +102,7 @@ This board use the STM32F722RET6 microcontroller and have the following features
|
|||
| 4 | 3V3 | PAD |
|
||||
|
||||
|
||||
###Designers
|
||||
### Designers
|
||||
* ZhengNyway(nyway@vip.qq.com) FROM DALRC
|
||||
|
||||
|
||||
|
|
33
docs/Board - FLYWOOF411.md
Executable file
33
docs/Board - FLYWOOF411.md
Executable file
|
@ -0,0 +1,33 @@
|
|||
# Board - FLYWOOF411
|
||||
|
||||

|
||||

|
||||

|
||||
|
||||
*Note:* This board used to be sold as a 'NOX F4' but is now an updated version similar to a Flywoo F411
|
||||
|
||||
## Banggood Specification:
|
||||
* Model: Upgrade Betaflight F4 Noxe V1
|
||||
* Version: Acro Version / Deluxe Version
|
||||
* Acro Version: Without Barometer and Blackbox
|
||||
* Deluxe Version: With Barometer and Blackbox
|
||||
* CPU: STM32F411C
|
||||
* MPU: MPU6000
|
||||
* Input Voltage: Support 2-6S Lipo Input
|
||||
* Built-In Betaflight OSD
|
||||
* Built-in 5V @ 2.5A BEC & 8V @ 3A BEC
|
||||
* 3.3V
|
||||
* 4.5V powered by USB
|
||||
* DShot, Proshot ESC
|
||||
* Support Spektrum 1024 /2048 , SBUS, IBUS, PPM
|
||||
* Built in flash for blackbox 16MB
|
||||
* Support WS2812 LED strip
|
||||
* Size: 27x27mm
|
||||
* Mounting Hole: 20x20mm , M2.5
|
||||
* Weight: 4.3g
|
||||
* DSM / IBUS/SBUS Receiver, choose UART RX2
|
||||
* PPM Receiver, don't need choose UART Port
|
||||
|
||||
|
||||
## Where to buy:
|
||||
* [Banggood](https://inavflight.com/shop/s/bg/1310419)
|
|
@ -1,6 +1,6 @@
|
|||
# Board - FOXEERF722DUAL
|
||||
# Board - FOXEERF722DUAL, Foxeer F722 V2 and Foxeer F722 Mini
|
||||
|
||||
The FOXEERF722DUAL described here:
|
||||
The Foxeer F722 DUAL, Foxeer F722 V2 and Foxeer F722 Mini described here:
|
||||
|
||||
This board use the STM32F722RET6 microcontroller and have the following features:
|
||||
* High-performance and DSP with FPU, ARM Cortex-M7 MCU with 512 Kbytes Flash
|
||||
|
@ -99,5 +99,5 @@ This board use the STM32F722RET6 microcontroller and have the following features
|
|||
| 4 | 3V3 | PAD |
|
||||
|
||||
|
||||
###Designers
|
||||
### Designers
|
||||
* NywayZheng(nyway@vip.qq.com)
|
|
@ -1,5 +1,7 @@
|
|||
# Board - OMNIBUS F3
|
||||
|
||||
> This board is not supported in recent INAV releases
|
||||
|
||||
## Hardware Features
|
||||
|
||||
Refer to the product web page:
|
||||
|
|
411
docs/Cli.md
411
docs/Cli.md
|
@ -123,403 +123,16 @@ A shorter form is also supported to enable and disable functions using `serial <
|
|||
|
||||
`serial` can also be used without any argument to print the current configuration of all the serial ports.
|
||||
|
||||
## CLI Variable Reference
|
||||
## Flash chip management
|
||||
|
||||
| Variable Name | Default Value | Description |
|
||||
| ------ | ------ | ------ |
|
||||
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
|
||||
| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) |
|
||||
| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
|
||||
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
|
||||
| min_check | 1100 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| rssi_channel | 0 | RX channel containing the RSSI signal |
|
||||
| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). |
|
||||
| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. |
|
||||
| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values |
|
||||
| input_filtering_mode | OFF | Filter out noise from OpenLRS Telemetry RX |
|
||||
| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. |
|
||||
| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. |
|
||||
| min_command | 1000 | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. |
|
||||
| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) |
|
||||
| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) |
|
||||
| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode |
|
||||
| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. |
|
||||
| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. |
|
||||
| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED |
|
||||
| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
|
||||
| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. |
|
||||
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
|
||||
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
|
||||
| reboot_character | 82 | Special character used to trigger reboot |
|
||||
| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). |
|
||||
| gps_sbas_mode | NONE | Which SBAS mode to be used |
|
||||
| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. |
|
||||
| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. |
|
||||
| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports |
|
||||
| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. |
|
||||
| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON].
|
||||
| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. |
|
||||
| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. |
|
||||
| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. |
|
||||
| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) |
|
||||
| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
|
||||
| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] |
|
||||
| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate |
|
||||
| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
|
||||
| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero |
|
||||
| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. |
|
||||
| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed |
|
||||
| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost |
|
||||
| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost |
|
||||
| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation |
|
||||
| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] |
|
||||
| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] |
|
||||
| name | Empty string | Craft name |
|
||||
| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing |
|
||||
| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude |
|
||||
| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used |
|
||||
| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. |
|
||||
| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) |
|
||||
| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius |
|
||||
| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. |
|
||||
| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] |
|
||||
| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] |
|
||||
| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] |
|
||||
| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] |
|
||||
| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] |
|
||||
| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] |
|
||||
| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] |
|
||||
| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] |
|
||||
| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. |
|
||||
| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. |
|
||||
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
|
||||
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
|
||||
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
|
||||
| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
|
||||
| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details |
|
||||
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
||||
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
|
||||
| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] |
|
||||
| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) |
|
||||
| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) |
|
||||
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
|
||||
| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. |
|
||||
| nav_mc_auto_disarm_delay | 2000 | |
|
||||
| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) |
|
||||
| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s |
|
||||
| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing |
|
||||
| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll |
|
||||
| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) |
|
||||
| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error |
|
||||
| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] |
|
||||
| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] |
|
||||
| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s |
|
||||
| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] |
|
||||
| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] |
|
||||
| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) |
|
||||
| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) |
|
||||
| nav_fw_launch_end_time | 3000 | Time for the transition of throttle and pitch angle, between the launch state and the subsequent flight mode [ms] |
|
||||
| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) |
|
||||
| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller |
|
||||
| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) |
|
||||
| nav_fw_launch_max_altitude | 0 | Altitude at which LAUNCH mode will be turned off and regular flight mode will take over. [cm] |
|
||||
| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. |
|
||||
| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. |
|
||||
| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees |
|
||||
| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps]|
|
||||
| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats |
|
||||
| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
|
||||
| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire |
|
||||
| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). |
|
||||
| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX |
|
||||
| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. |
|
||||
| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. |
|
||||
| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] |
|
||||
| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
|
||||
| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
|
||||
| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data |
|
||||
| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends precent). [PERCENT/MAH/MWH] |
|
||||
| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
|
||||
| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON |
|
||||
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
|
||||
| smartport_fuel_unit | MAH | S.Port and D-Series telemetry: Unit of the value sent with the `FUEL` ID. [PERCENT/MAH/MWH] |
|
||||
| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. |
|
||||
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
|
||||
| battery_capacity | 0 | Battery capacity in mAH. This value is used in conjunction with the current meter to determine remaining battery capacity. |
|
||||
| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. |
|
||||
| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` |
|
||||
| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation |
|
||||
| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V |
|
||||
| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V |
|
||||
| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) |
|
||||
| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) |
|
||||
| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. |
|
||||
| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. |
|
||||
| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. |
|
||||
| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. |
|
||||
| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. |
|
||||
| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). |
|
||||
| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit |
|
||||
| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit |
|
||||
| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation |
|
||||
| multiwii_current_meter_output | OFF | Default current output via MSP is in 0.01A steps. Setting this to 1 causes output in default multiwii scaling (1mA steps) |
|
||||
| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. |
|
||||
| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. |
|
||||
| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. |
|
||||
| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. |
|
||||
| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) |
|
||||
| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
|
||||
| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. |
|
||||
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
|
||||
| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements |
|
||||
| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements |
|
||||
| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements |
|
||||
| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes |
|
||||
| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) |
|
||||
| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo |
|
||||
| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] |
|
||||
| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. |
|
||||
| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. |
|
||||
| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) |
|
||||
| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] |
|
||||
| servo_center_pulse | 1500 | Servo midpoint |
|
||||
| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. |
|
||||
| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). |
|
||||
| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). |
|
||||
| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). |
|
||||
| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
|
||||
| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. |
|
||||
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
|
||||
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
|
||||
| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn |
|
||||
| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. |
|
||||
| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. |
|
||||
| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. |
|
||||
| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. |
|
||||
| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode |
|
||||
| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. |
|
||||
| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. |
|
||||
| rx_nosignal_throttle | HOLD | Defines behavior of throttle channel after signal loss is detected and until `failsafe_procedure` kicks in. Possible values - `HOLD` and `DROP`. |
|
||||
| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting |
|
||||
| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target |
|
||||
| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts |
|
||||
| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations |
|
||||
| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. |
|
||||
| blackbox_device | SPIFLASH | Selection of where to write blackbox data |
|
||||
| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. |
|
||||
| ledstrip_visual_beeper | OFF | |
|
||||
| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` |
|
||||
| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) |
|
||||
| osd_units | METRIC| IMPERIAL, METRIC, UK |
|
||||
| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) |
|
||||
| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. |
|
||||
| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink |
|
||||
| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) |
|
||||
| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) |
|
||||
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) |
|
||||
| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) |
|
||||
| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) |
|
||||
| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. |
|
||||
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
|
||||
| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe |
|
||||
| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` |
|
||||
| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD.|
|
||||
| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. |
|
||||
| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON |
|
||||
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) |
|
||||
| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) |
|
||||
| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) |
|
||||
| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) |
|
||||
| nav_mc_vel_z_p | 100 | P gain of velocity PID controller |
|
||||
| nav_mc_vel_z_i | 50 | I gain of velocity PID controller |
|
||||
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
|
||||
| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
|
||||
| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
|
||||
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
|
||||
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
|
||||
| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
|
||||
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course |
|
||||
| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) |
|
||||
| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) |
|
||||
| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
|
||||
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
|
||||
| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. |
|
||||
| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. |
|
||||
| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter |
|
||||
| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. |
|
||||
| mode_range_logic_operator | OR | Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. |
|
||||
| default_rate_profile | 0 | Default = profile number |
|
||||
| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. |
|
||||
| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. |
|
||||
| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. |
|
||||
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
|
||||
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
|
||||
| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH |
|
||||
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
|
||||
| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL |
|
||||
| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL |
|
||||
| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW |
|
||||
| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW |
|
||||
| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW |
|
||||
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
|
||||
| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff |
|
||||
| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point |
|
||||
| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH |
|
||||
| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH |
|
||||
| fw_ff_pitch| 50 | Fixed-wing rate stabilisation FF-gain for PITCH |
|
||||
| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL |
|
||||
| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL |
|
||||
| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL |
|
||||
| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW |
|
||||
| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW |
|
||||
| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW |
|
||||
| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain |
|
||||
| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff |
|
||||
| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point |
|
||||
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
|
||||
| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° |
|
||||
| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side |
|
||||
| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) |
|
||||
| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
|
||||
| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
|
||||
| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
|
||||
| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
|
||||
| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value |
|
||||
| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter |
|
||||
| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |
|
||||
| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter |
|
||||
| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers |
|
||||
| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches |
|
||||
| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` |
|
||||
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) |
|
||||
| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV |
|
||||
| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine |
|
||||
| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` |
|
||||
| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting |
|
||||
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| `pid_type` | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` |
|
||||
| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) |
|
||||
| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. |
|
||||
| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. |
|
||||
| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) |
|
||||
| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) |
|
||||
| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] |
|
||||
| manual rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] |
|
||||
| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. |
|
||||
| thr_expo | 0 | Throttle exposition value |
|
||||
| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% |
|
||||
| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% |
|
||||
| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% |
|
||||
| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. |
|
||||
| tpa_breakpoint | 1500 | See tpa_rate. |
|
||||
| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups |
|
||||
| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot |
|
||||
| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot |
|
||||
| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection |
|
||||
| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] |
|
||||
| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] |
|
||||
| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) |
|
||||
| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. |
|
||||
| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. |
|
||||
| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled |
|
||||
| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
|
||||
| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
|
||||
| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
|
||||
| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
|
||||
| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. |
|
||||
| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs |
|
||||
| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. |
|
||||
| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. |
|
||||
| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. |
|
||||
| vtx_freq | 5740 | Set the VTX frequency using raw MHz. This parameter is ignored unless `vtx_band` is 0. |
|
||||
| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. |
|
||||
| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. |
|
||||
| vtx_pit_mode_freq | Frequency to use (in MHz) when the VTX is in pit mode. |
|
||||
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
|
||||
| vtx_max_power_override | 0 | Some VTXes may report max power incorrectly (i.e. 200mW for a 600mW VTX). Use this to override max supported power. 0 to disable and use whatever VTX reports as it's capabilities |
|
||||
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
|
||||
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
|
||||
| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
|
||||
| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen |
|
||||
| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value |
|
||||
| nav_mc_braking_timeout | 2000 | timeout in ms for braking |
|
||||
| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase |
|
||||
| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen |
|
||||
| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value |
|
||||
| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value |
|
||||
| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode |
|
||||
| nav_mc_pos_deceleration_time | 120 | Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting |
|
||||
| nav_mc_pos_expo | 10 | Expo for PosHold control |
|
||||
| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon |
|
||||
| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. |
|
||||
| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. |
|
||||
| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used |
|
||||
| use_dterm_fir_filter | ON | Setting to **OFF** disabled extra filter on Dterm. **OFF** offers faster Dterm and better inflight performance with a cost of being more sensitive to gyro noise. Small and relatively clean multirotors (7 inches and below) are suggested to use **OFF** setting. If motors are getting too hot, switch back to **ON** |
|
||||
| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. |
|
||||
| sim_pin | Empty string | PIN code for the SIM module |
|
||||
| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 |
|
||||
| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low |
|
||||
| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. |
|
||||
| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. |
|
||||
| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. |
|
||||
| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`.|
|
||||
| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` |
|
||||
| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% |
|
||||
| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running |
|
||||
| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements |
|
||||
| antigravity_accelerator | 1 | |
|
||||
| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain |
|
||||
| sim_pin | | PIN for GSM card module |
|
||||
For targets that have a flash data chip, typically used for blackbox logs, the following additional comamnds are provided.
|
||||
|
||||
| Command | Effect |
|
||||
| ------- | ------ |
|
||||
| `flash_erase` | Erases the flash chip |
|
||||
| `flash_info` | Displays flash chip information (used, free etc.) |
|
||||
| `flash_read <length> <address>` | Reads `length` bytes from `address` |
|
||||
| `flash_write <address> <data>` | Writes `data` to `address` |
|
||||
|
||||
## CLI Variable Reference
|
||||
See [Settings.md](Settings.md).
|
||||
|
|
|
@ -1,78 +0,0 @@
|
|||
# Global Functions
|
||||
|
||||
_Global Functions_ (abbr. GF) are a mechanism allowing to override certain flight parameters (during flight). Global Functions are activated by [Logic Conditions](Logic%20Conditions.md)
|
||||
|
||||
## CLI
|
||||
|
||||
`gf <rule> <enabled> <logic condition> <action> <operand type> <operand value> <flags>`
|
||||
|
||||
* `<rule>` - GF ID, indexed from `0`
|
||||
* `<enabled>` - `0` evaluates as disabled, `1` evaluates as enabled. Only enabled GFs are executed
|
||||
* `<logic condition>` - the ID of _LogicCondition_ used to trigger GF On/Off. Then LC evaluates `true`, GlobalFunction will be come active
|
||||
* `<action>` - action to execute when GF is active
|
||||
* `<operand type>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md)
|
||||
* `<operand value>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands. Used only when `action` requires it. Should be kept at `0` in other case. See [Logic Conditions](Logic%20Conditions.md)
|
||||
* `<flags>` - allows to pass arguments into Global Function action. Syntax is the same as in case of Logic Conditions operands
|
||||
|
||||
## Actions
|
||||
|
||||
| Action ID | Name | Notes |
|
||||
|---- |---- |---- |
|
||||
| 0 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
|
||||
| 1 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
|
||||
| 2 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
|
||||
| 3 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
|
||||
| 4 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
|
||||
| 5 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
|
||||
| 6 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
|
||||
| 7 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 8 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
|
||||
| 8 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
|
||||
|
||||
## Flags
|
||||
|
||||
Current no flags are implemented
|
||||
|
||||
## Example
|
||||
|
||||
### Dynamic THROTTLE scale
|
||||
|
||||
`gf 0 1 0 1 0 50 0`
|
||||
|
||||
Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set VTX power level via Smart Audio
|
||||
|
||||
`gf 0 1 0 3 0 3 0`
|
||||
|
||||
Sets VTX power level to `3` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Invert ROLL and PITCH when rear facing camera FPV is used
|
||||
|
||||
Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439)
|
||||
|
||||
```
|
||||
gf 0 1 0 4 0 0 0
|
||||
gf 1 1 0 5 0 0 0
|
||||
```
|
||||
|
||||
Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera)
|
||||
|
||||
### Cut motors but keep other throttle bindings active
|
||||
|
||||
`gf 0 1 0 7 0 1000 0`
|
||||
|
||||
Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set throttle to 50% and keep other throttle bindings active
|
||||
|
||||
`gf 0 1 0 7 0 1500 0`
|
||||
|
||||
Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set throttle control to different RC channel
|
||||
|
||||
`gf 0 1 0 7 1 7 0`
|
||||
|
||||
If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel
|
||||
|
|
@ -536,7 +536,7 @@ LEDs 14-15 should be placed facing up, in the middle
|
|||
### Exmple 28 LED config
|
||||
|
||||
```
|
||||
#right rear cluster
|
||||
# right rear cluster
|
||||
led 0 9,9:S:FWT:0
|
||||
led 1 10,10:S:FWT:0
|
||||
led 2 11,11:S:IA:0
|
||||
|
|
|
@ -58,12 +58,14 @@ When deciding what altitude to maintain, RTH has 4 different modes of operation
|
|||
|
||||
Parameters:
|
||||
|
||||
* `<action>` - The action to be taken at the WP. The following are enumerations are available in inav 2.5 and later:
|
||||
* `<action>` - The action to be taken at the WP. The following are enumerations are available in inav 2.6 and later:
|
||||
* 0 - Unused / Unassigned
|
||||
* 1 - WAYPOINT
|
||||
* 3 - POSHOLD_TIME
|
||||
* 4 - RTH
|
||||
* 5 - SET_POI
|
||||
* 6 - JUMP
|
||||
* 7 - SET_HEAD
|
||||
* 8 - LAND
|
||||
|
||||
* `<lat>` - Latitude (WGS84), in degrees * 1E7 (for example 123456789 means 12.3456789).
|
||||
|
@ -72,7 +74,7 @@ Parameters:
|
|||
|
||||
* `<alt>` - Altitude in cm.
|
||||
|
||||
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number).
|
||||
* `<p1>` - For a RTH waypoint, p1 > 0 enables landing. For a normal waypoint it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For POSHOLD TIME waypoint it is time to loiter in seconds. For JUMP it is the target WP **index** (not number). For SET_HEAD, it is the desired heading (0-359) or -1 to cancel a previous SET_HEAD or SET_POI.
|
||||
|
||||
* `<p2>` - For a POSHOLD TIME it is the speed to this waypoint (cm/s), it is taken into account only for multicopters and when > 50 and < nav_auto_speed. For JUMP it is the number of iterations of the JUMP.
|
||||
|
||||
|
@ -90,7 +92,7 @@ Parameters:
|
|||
# wp load
|
||||
|
||||
# wp
|
||||
#wp 11 valid
|
||||
# wp 11 valid
|
||||
wp 0 1 543533193 -45179273 3500 0 0 0 0
|
||||
wp 1 1 543535723 -45193913 3500 0 0 0 0
|
||||
wp 2 1 543544541 -45196617 5000 0 0 0 0
|
||||
|
|
|
@ -1,15 +1,20 @@
|
|||
# Logic Conditions
|
||||
# INAV Programming Framework
|
||||
|
||||
Logic Conditions (abbr. LC) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in:
|
||||
INAV Programming Framework (abbr. IPF) is a mechanism that allows to evaluate cenrtain flight parameters (RC channels, switches, altitude, distance, timers, other logic conditions) and use the value of evaluated expression in different places of INAV. Currently, the result of LCs can be used in:
|
||||
|
||||
* [Servo mixer](Mixer.md) to activate/deactivate certain servo mix rulers
|
||||
* [Global functions](Global%20Functions.md) to activate/deactivate system overrides
|
||||
* To activate/deactivate system overrides
|
||||
|
||||
Logic conditions can be edited using INAV Configurator user interface, of via CLI
|
||||
INAV Programming Framework coinsists of:
|
||||
|
||||
* Logic Conditions - each Logic Condition can be understood as a single command, a single line of code
|
||||
* Global Variables - variables that can store values from and for LogiC Conditions and servo mixer
|
||||
|
||||
IPF can be edited using INAV Configurator user interface, of via CLI
|
||||
|
||||
## CLI
|
||||
|
||||
`logic <rule> <enabled> <operation> <operand A type> <operand A value> <operand B type> <operand B value> <flags>`
|
||||
`logic <rule> <enabled> <activatorId> <operation> <operand A type> <operand A value> <operand B type> <operand B value> <flags>`
|
||||
|
||||
* `<rule>` - ID of Logic Condition rule
|
||||
* `<enabled>` - `0` evaluates as disabled, `1` evaluates as enabled
|
||||
|
@ -39,6 +44,26 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL
|
|||
| 11 | NOR | |
|
||||
| 12 | NOT | |
|
||||
| 13 | STICKY | `Operand A` is activation operator, `Operand B` is deactivation operator. After activation, operator will return `true` until Operand B is evaluated as `true`|
|
||||
| 14 | ADD | Add `Operand A` to `Operand B` and returns the result |
|
||||
| 15 | SUB | Substract `Operand B` from `Operand A` and returns the result |
|
||||
| 16 | MUL | Multiply `Operand A` by `Operand B` and returns the result |
|
||||
| 17 | DIV | Divide `Operand A` by `Operand B` and returns the result |
|
||||
| 18 | GVAR SET | Store value from `Operand B` into the Global Variable addressed by `Operand B`. Bear in mind, that operand `Global Variable` means: Value stored in Global Variable of an index! To store in GVAR 1 use `Value 1` not `Global Variable 1` |
|
||||
| 19 | GVAR INC | Increase the GVAR indexed by `Operand A` with value from `Operand B` |
|
||||
| 20 | GVAR DEC | Decrease the GVAR indexed by `Operand A` with value from `Operand B` |
|
||||
| 21 | IO PORT SET | Set I2C IO Expander pin `Operand A` to value of `Operand B`. `Operand A` accepts values `0-7` and `Operand B` accepts `0` and `1` |
|
||||
| 22 | OVERRIDE_ARMING_SAFETY | Allows to arm on any angle even without GPS fix |
|
||||
| 23 | OVERRIDE_THROTTLE_SCALE | Override throttle scale to the value defined by operand. Operand type `0` and value `50` means throttle will be scaled by 50%. |
|
||||
| 24 | SWAP_ROLL_YAW | basically, when activated, yaw stick will control roll and roll stick will control yaw. Required for tail-sitters VTOL during vertical-horizonral transition when body frame changes |
|
||||
| 25 | SET_VTX_POWER_LEVEL | Sets VTX power level. Accepted values are `0-3` for SmartAudio and `0-4` for Tramp protocol |
|
||||
| 26 | INVERT_ROLL | Inverts ROLL axis input for PID/PIFF controller |
|
||||
| 27 | INVERT_PITCH | Inverts PITCH axis input for PID/PIFF controller |
|
||||
| 28 | INVERT_YAW | Inverts YAW axis input for PID/PIFF controller |
|
||||
| 29 | OVERRIDE_THROTTLE | Override throttle value that is fed to the motors by mixer. Operand is scaled in us. `1000` means throttle cut, `1500` means half throttle |
|
||||
| 30 | SET_VTX_BAND | Sets VTX band. Accepted values are `1-5` |
|
||||
| 31 | SET_VTX_CHANNEL | Sets VTX channel. Accepted values are `1-8` |
|
||||
| 32 | SET_OSD_LAYOUT | Sets OSD layout. Accepted values are `0-3` |
|
||||
|
||||
|
||||
### Operands
|
||||
|
||||
|
@ -49,6 +74,7 @@ Logic conditions can be edited using INAV Configurator user interface, of via CL
|
|||
| 2 | FLIGHT | `value` points to flight parameter table |
|
||||
| 3 | FLIGHT_MODE | `value` points to flight modes table |
|
||||
| 4 | LC | `value` points to other logic condition ID |
|
||||
| 5 | GVAR | Value stored in Global Variable indexed by `value`. `GVAR 1` means: value in GVAR 1 |
|
||||
|
||||
#### FLIGHT
|
||||
|
||||
|
@ -103,3 +129,47 @@ All flags are reseted on ARM and DISARM event.
|
|||
| bit | Decimal | Function |
|
||||
|---- |---- |---- |
|
||||
| 0 | 1 | Latch - after activation LC will stay active until LATCH flag is reseted |
|
||||
|
||||
## Examples
|
||||
|
||||
### Dynamic THROTTLE scale
|
||||
|
||||
`logic 0 1 0 23 0 50 0 0 0`
|
||||
|
||||
Limits the THROTTLE output to 50% when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set VTX power level via Smart Audio
|
||||
|
||||
`logic 0 1 0 25 0 3 0 0 0`
|
||||
|
||||
Sets VTX power level to `3` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Invert ROLL and PITCH when rear facing camera FPV is used
|
||||
|
||||
Solves the problem from [https://github.com/iNavFlight/inav/issues/4439](https://github.com/iNavFlight/inav/issues/4439)
|
||||
|
||||
```
|
||||
logic 0 1 0 26 0 0 0 0 0
|
||||
logic 1 1 0 27 0 0 0 0 0
|
||||
```
|
||||
|
||||
Inverts ROLL and PITCH input when Logic Condition `0` evaluates as `true`. Moving Pitch stick up will cause pitch down (up for rear facing camera). Moving Roll stick right will cause roll left of a quad (right in rear facing camera)
|
||||
|
||||
### Cut motors but keep other throttle bindings active
|
||||
|
||||
`logic 0 1 0 29 0 1000 0 0 0`
|
||||
|
||||
Sets Thhrottle output to `0%` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set throttle to 50% and keep other throttle bindings active
|
||||
|
||||
`logic 0 1 0 29 0 1500 0 0 0`
|
||||
|
||||
Sets Thhrottle output to about `50%` when Logic Condition `0` evaluates as `true`
|
||||
|
||||
### Set throttle control to different RC channel
|
||||
|
||||
`logic 0 1 0 29 1 7 0 0 0`
|
||||
|
||||
If Logic Condition `0` evaluates as `true`, motor throttle control is bound to RC channel 7 instead of throttle channel
|
||||
|
393
docs/Settings.md
Normal file
393
docs/Settings.md
Normal file
|
@ -0,0 +1,393 @@
|
|||
# CLI Variable Reference
|
||||
|
||||
| Variable Name | Default Value | Description |
|
||||
| ------------- | ------------- | ----------- |
|
||||
| 3d_deadband_high | 1514 | High value of throttle deadband for 3D mode (when stick is in the deadband range, the value in 3d_neutral is used instead) |
|
||||
| 3d_deadband_low | 1406 | Low value of throttle deadband for 3D mode (when stick is in the 3d_deadband_throttle range, the fixed values of 3d_deadband_low / _high are used instead) |
|
||||
| 3d_deadband_throttle | 50 | Throttle signal will be held to a fixed value when throttle is centered with an error margin defined in this parameter. |
|
||||
| 3d_neutral | 1460 | Neutral (stop) throttle value for 3D mode |
|
||||
| acc_event_threshold_high | 0 | Acceleration threshold [cm/s/s] for impact / high g event text messages sent by SIM module. Acceleration values greater than 4 g can occur in fixed wing flight without an impact, so a setting of 4000 or greater is suggested. 0 = detection off. |
|
||||
| acc_event_threshold_low | 0 | Acceleration threshold [cm/s/s] for low-g / freefall detection text messages sent by SIM module. A setting of less than 100 is suggested. Valid values: [0-900], 0 = detection off. |
|
||||
| acc_event_threshold_neg_x | 0 | Acceleration threshold [cm/s/s] for backwards acceleration / fixed wing landing detection text messages sent by SIM module. Suggested value for fixed wing: 1100. 0 = detection off. |
|
||||
| acc_hardware | AUTO | Selection of acc hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| acc_lpf_hz | 15 | Software-based filter to remove mechanical vibrations from the accelerometer measurements. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
|
||||
| acc_lpf_type | BIQUAD | Specifies the type of the software LPF of the acc signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
|
||||
| accgain_x | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| accgain_y | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| accgain_z | 4096 | Calculated value after '6 position avanced calibration'. Uncalibrated value is 4096. See Wiki page. |
|
||||
| acczero_x | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_y | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| acczero_z | 0 | Calculated value after '6 position avanced calibration'. See Wiki page. |
|
||||
| airspeed_adc_channel | 0 | ADC channel to use for analog pitot tube (airspeed) sensor. If board doesn't have a dedicated connector for analog airspeed sensor will default to 0 |
|
||||
| align_acc | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_board_pitch | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_board_roll | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_board_yaw | 0 | Arbitrary board rotation in deci-degrees (0.1 degree), to allow mounting it sideways / upside down / rotated etc |
|
||||
| align_gyro | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_mag | DEFAULT | When running on non-default hardware or adding support for new sensors/sensor boards, these values are used for sensor orientation. When carefully understood, these values can also be used to rotate (in 90deg steps) or flip the board. Possible values are: DEFAULT, CW0_DEG, CW90_DEG, CW180_DEG, CW270_DEG, CW0_DEG_FLIP, CW90_DEG_FLIP, CW180_DEG_FLIP, CW270_DEG_FLIP. |
|
||||
| align_mag_pitch | 0 | Same as align_mag_roll, but for the pitch axis. |
|
||||
| align_mag_roll | 0 | Set the external mag alignment on the roll axis (in 0.1 degree steps). If this value is non-zero, the compass is assumed to be externally mounted and both the board and on-board compass alignent (align_mag) are ignored. See also align_mag_pitch and align_mag_yaw. |
|
||||
| align_mag_yaw | 0 | Same as align_mag_roll, but for the yaw axis. |
|
||||
| align_opflow | 5 | Optical flow module alignment (default CW0_DEG_FLIP) |
|
||||
| alt_hold_deadband | 50 | Defines the deadband of throttle during alt_hold [r/c points] |
|
||||
| antigravity_accelerator | 1 | |
|
||||
| antigravity_cutoff_lpf_hz | 15 | Antigravity cutoff frequenct for Throtte filter. Antigravity is based on the difference between actual and filtered throttle input. The bigger is the difference, the bigger Antigravity gain |
|
||||
| antigravity_gain | 1 | Max Antigravity gain. `1` means Antigravity is disabled, `2` means Iterm is allowed to double during rapid throttle movements |
|
||||
| baro_cal_tolerance | 150 | Baro calibration tolerance in cm. The default should allow the noisiest baro to complete calibration [cm]. |
|
||||
| baro_hardware | AUTO | Selection of baro hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| baro_median_filter | ON | 3-point median filtering for barometer readouts. No reason to change this setting |
|
||||
| bat_cells | 0 | Number of cells of the battery (0 = autodetect), see battery documentation |
|
||||
| bat_voltage_src | RAW | Chose between raw and sag compensated battery voltage to use for battery alarms and telemetry. Possible values are `RAW` and `SAG_COMP` |
|
||||
| battery_capacity | 0 | Set the battery capacity in mAh or mWh (see `battery_capacity_unit`). Used to calculate the remaining battery capacity. |
|
||||
| battery_capacity_critical | 0 | If the remaining battery capacity goes below this threshold the battery is considered empty and the beeper will emit long beeps. |
|
||||
| battery_capacity_unit | MAH | Unit used for `battery_capacity`, `battery_capacity_warning` and `battery_capacity_critical` [MAH/MWH] (milliAmpere hour / milliWatt hour). |
|
||||
| battery_capacity_warning | 0 | If the remaining battery capacity goes below this threshold the beeper will emit short beeps and the relevant OSD items will blink. |
|
||||
| blackbox_device | SPIFLASH | Selection of where to write blackbox data |
|
||||
| blackbox_rate_denom | 1 | Blackbox logging rate denominator. See blackbox_rate_num. |
|
||||
| blackbox_rate_num | 1 | Blackbox logging rate numerator. Use num/denom settings to decide if a frame should be logged, allowing control of the portion of logged loop iterations |
|
||||
| cpu_underclock | OFF | This option is only available on certain architectures (F3 CPUs at the moment). It makes CPU clock lower to reduce interference to long-range RC systems working at 433MHz |
|
||||
| cruise_power | 0 | Power draw at cruise throttle used for remaining flight time/distance estimation in 0.01W unit |
|
||||
| current_adc_channel | - | ADC channel to use for analog current sensor input. Defaults to board CURRENT sensor input (if available). 0 = disabled |
|
||||
| current_meter_offset | 0 | This sets the output offset voltage of the current sensor in millivolts. |
|
||||
| current_meter_scale | 400 | This sets the output voltage to current scaling for the current sensor in 0.1 mV/A steps. 400 is 40mV/A such as the ACS756 sensor outputs. 183 is the setting for the uberdistro with a 0.25mOhm shunt. |
|
||||
| current_meter_type | ADC | ADC , VIRTUAL, NONE. The virtual current sensor, once calibrated, estimates the current value from throttle position. |
|
||||
| deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| disarm_kill_switch | ON | Disarms the motors independently of throttle value. Setting to OFF reverts to the old behaviour of disarming only when the throttle is low. Only applies when arming and disarming with an AUX channel. |
|
||||
| display_force_sw_blink | OFF | OFF = OSD hardware blink / ON = OSD software blink. If OSD warning text/values are invisible, try setting this to ON |
|
||||
| dterm_lpf2_hz | 0 | Cutoff frequency for stage 2 D-term low pass filter |
|
||||
| dterm_lpf2_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| dterm_lpf_hz | 40 | Dterm low pass filter cutoff frequency. Default setting is very conservative and small multirotors should use higher value between 80 and 100Hz. 80 seems like a gold spot for 7-inch builds while 100 should work best with 5-inch machines. If motors are getting too hot, lower the value |
|
||||
| dterm_lpf_type | `BIQUAD` | Defines the type of stage 1 D-term LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| dynamic_gyro_notch_enabled | `OFF` | Enable/disable dynamic gyro notch also known as Matrix Filter |
|
||||
| dynamic_gyro_notch_min_hz | 150 | Minimum frequency for dynamic notches. Default value of `150` works best with 5" multirors. Should be lowered with increased size of propellers. Values around `100` work fine on 7" drones. 10" can go down to `60` - `70` |
|
||||
| dynamic_gyro_notch_q | 120 | Q factor for dynamic notches |
|
||||
| dynamic_gyro_notch_range | `MEDIUM` | Range for dynamic gyro notches. `MEDIUM` for 5", `HIGH` for 3" and `MEDIUM`/`LOW` for 7" and bigger propellers |
|
||||
| failsafe_delay | 5 | Time in deciseconds to wait before activating failsafe when signal is lost. See [Failsafe documentation](Failsafe.md#failsafe_delay). |
|
||||
| failsafe_fw_pitch_angle | 100 | Amount of dive/climb when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = climb |
|
||||
| failsafe_fw_roll_angle | -200 | Amount of banking when `SET-THR` failsafe is active on a fixed-wing machine. In 1/10 deg (deci-degrees). Negative values = left roll |
|
||||
| failsafe_fw_yaw_rate | -45 | Requested yaw rate to execute when `SET-THR` failsafe is active on a fixed-wing machine. In deg/s. Negative values = left turn |
|
||||
| failsafe_lights | ON | Enable or disable the lights when the `FAILSAFE` flight mode is enabled. The target needs to be compiled with `USE_LIGHTS` [ON/OFF]. |
|
||||
| failsafe_lights_flash_on_time | 100 | Flash lights ON time in milliseconds when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled. [20-65535]. |
|
||||
| failsafe_lights_flash_period | 1000 | Time in milliseconds between two flashes when `failsafe_lights` is ON and `FAILSAFE` flight mode is enabled [40-65535]. |
|
||||
| failsafe_min_distance | 0 | If failsafe happens when craft is closer than this distance in centimeters from home, failsafe will not execute regular failsafe_procedure, but will execute procedure specified in failsafe_min_distance_procedure instead. 0 = Normal failsafe_procedure always taken. |
|
||||
| failsafe_min_distance_procedure | DROP | What failsafe procedure to initiate in Stage 2 when craft is closer to home than failsafe_min_distance. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_mission | ON | If set to `OFF` the failsafe procedure won't be triggered and the mission will continue if the FC is in WP (automatic mission) mode |
|
||||
| failsafe_off_delay | 200 | Time in deciseconds to wait before turning off motors when failsafe is activated. 0 = No timeout. See [Failsafe documentation](Failsafe.md#failsafe_off_delay). |
|
||||
| failsafe_procedure | SET-THR | What failsafe procedure to initiate in Stage 2. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_recovery_delay | 5 | Time in deciseconds to wait before aborting failsafe when signal is recovered. See [Failsafe documentation](Failsafe.md#failsafe_recovery_delay). |
|
||||
| failsafe_stick_threshold | 50 | Threshold for stick motion to consider failsafe condition resolved. If non-zero failsafe won't clear even if RC link is restored - you have to move sticks to exit failsafe. |
|
||||
| failsafe_throttle | 1000 | Throttle level used for landing when failsafe is enabled. See [Failsafe documentation](Failsafe.md#failsafe_throttle). |
|
||||
| failsafe_throttle_low_delay | 100 | If failsafe activated when throttle is low for this much time - bypass failsafe and disarm, in 10th of seconds. 0 = No timeout |
|
||||
| fixed_wing_auto_arm | OFF | Auto-arm fixed wing aircraft on throttle above min_check, and disarming with stick commands are disabled, so power cycle is required to disarm. Requires enabled motorstop and no arm switch configured. |
|
||||
| flaperon_throw_offset | 200 | Defines throw range in us for both ailerons that will be passed to servo mixer via input source 14 (`FEATURE FLAPS`) when FLAPERON mode is activated. |
|
||||
| frsky_coordinates_format | 0 | D-Series telemetry only: FRSKY_FORMAT_DMS (default), FRSKY_FORMAT_NMEA |
|
||||
| frsky_default_latitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_default_longitude | 0.000 | D-Series telemetry only: OpenTX needs a valid set of coordinates to show compass value. A fake value defined in this setting is sent while no fix is acquired. |
|
||||
| frsky_pitch_roll | OFF | S.Port and D-Series telemetry: Send pitch and roll degrees*10 instead of raw accelerometer data |
|
||||
| frsky_unit | METRIC | Not used? [METRIC/IMPERIAL] |
|
||||
| frsky_vfas_precision | 0 | D-Series telemetry only: Set to 1 to send raw VBat value in 0.1V resolution for receivers that can handle it, or 0 (default) to use the standard method |
|
||||
| fw_autotune_ff_to_i_tc | 600 | FF to I time (defines time for I to reach the same level of response as FF) [ms] |
|
||||
| fw_autotune_ff_to_p_gain | 10 | FF to P gain (strength relationship) [%] |
|
||||
| fw_autotune_overshoot_time | 100 | Time [ms] to detect sustained overshoot |
|
||||
| fw_autotune_threshold | 50 | Threshold [%] of max rate to consider overshoot/undershoot detection |
|
||||
| fw_autotune_undershoot_time | 200 | Time [ms] to detect sustained undershoot |
|
||||
| fw_d_level | 75 | Fixed-wing attitude stabilisation HORIZON transition point |
|
||||
| fw_ff_pitch | 50 | Fixed-wing rate stabilisation FF-gain for PITCH |
|
||||
| fw_ff_roll | 50 | Fixed-wing rate stabilisation FF-gain for ROLL |
|
||||
| fw_ff_yaw | 60 | Fixed-wing rate stabilisation FF-gain for YAW |
|
||||
| fw_i_level | 5 | Fixed-wing attitude stabilisation low-pass filter cutoff |
|
||||
| fw_i_pitch | 7 | Fixed-wing rate stabilisation I-gain for PITCH |
|
||||
| fw_i_roll | 7 | Fixed-wing rate stabilisation I-gain for ROLL |
|
||||
| fw_i_yaw | 10 | Fixed-wing rate stabilisation I-gain for YAW |
|
||||
| fw_iterm_limit_stick_position | 0.5 | Iterm is not allowed to grow when stick position is above threshold. This solves the problem of bounceback or followthrough when full stick deflection is applied on poorely tuned fixed wings. In other words, stabilization is partialy disabled when pilot is actively controlling the aircraft and active when sticks are not touched. `0` mean stick is in center position, `1` means it is fully deflected to either side |
|
||||
| fw_iterm_throw_limit | 165 | Limits max/min I-term value in stabilization PID controller in case of Fixed Wing. It solves the problem of servo saturation before take-off/throwing the airplane into the air. By default, error accumulated in I-term can not exceed 1/3 of servo throw (around 165us). Set 0 to disable completely. |
|
||||
| fw_loiter_direction | RIGHT | Direction of loitering: center point on right wing (clockwise - default), or center point on left wing (counterclockwise). If equal YAW then can be changed in flight using a yaw stick. |
|
||||
| fw_min_throttle_down_pitch | 0 | Automatic pitch down angle when throttle is at 0 in angle mode. Progressively applied between cruise throttle and zero throttle (decidegrees) |
|
||||
| fw_p_level | 20 | Fixed-wing attitude stabilisation P-gain |
|
||||
| fw_p_pitch | 5 | Fixed-wing rate stabilisation P-gain for PITCH |
|
||||
| fw_p_roll | 5 | Fixed-wing rate stabilisation P-gain for ROLL |
|
||||
| fw_p_yaw | 6 | Fixed-wing rate stabilisation P-gain for YAW |
|
||||
| fw_reference_airspeed | 1000 | Reference airspeed. Set this to airspeed at which PIDs were tuned. Usually should be set to cruise airspeed. Also used for coordinated turn calculation if airspeed sensor is not present. |
|
||||
| fw_tpa_time_constant | 0 | TPA smoothing and delay time constant to reflect non-instant speed/throttle response of the plane. Planes with low thrust/weight ratio generally need higher time constant. Default is zero for compatibility with old setups |
|
||||
| fw_turn_assist_yaw_gain | 1 | Gain required to keep the yaw rate consistent with the turn rate for a coordinated turn (in TURN_ASSIST mode). Value significantly different from 1.0 indicates a problem with the airspeed calibration (if present) or value of `fw_reference_airspeed` parameter |
|
||||
| gps_auto_baud | ON | Automatic configuration of GPS baudrate(The specified baudrate in configured in ports will be used) when used with UBLOX GPS. When used with NAZA/DJI it will automatic detect GPS baudrate and change to it, ignoring the selected baudrate set in ports |
|
||||
| gps_auto_config | ON | Enable automatic configuration of UBlox GPS receivers. |
|
||||
| gps_dyn_model | AIR_1G | GPS navigation model: Pedestrian, Air_1g, Air_4g. Default is AIR_1G. Use pedestrian with caution, can cause flyaways with fast flying. |
|
||||
| gps_min_sats | 6 | Minimum number of GPS satellites in view to acquire GPS_FIX and consider GPS position valid. Some GPS receivers appeared to be very inaccurate with low satellite count. |
|
||||
| gps_provider | UBLOX | Which GPS protocol to be used, note that UBLOX is 5Hz and UBLOX7 is 10Hz (M8N). |
|
||||
| gps_sbas_mode | NONE | Which SBAS mode to be used |
|
||||
| gps_ublox_use_galileo | OFF | Enable use of Galileo satellites. This is at the expense of other regional constellations, so benefit may also be regional. Requires M8N and Ublox firmware 3.x (or later) [OFF/ON]. |
|
||||
| gyro_hardware_lpf | 42HZ | Hardware lowpass filter for gyro. Allowed values depend on the driver - For example MPU6050 allows 10HZ,20HZ,42HZ,98HZ,188HZ,256Hz (8khz mode). If you have to set gyro lpf below 42Hz generally means the frame is vibrating too much, and that should be fixed first. |
|
||||
| gyro_lpf_hz | 60 | Software-based filter to remove mechanical vibrations from the gyro signal. Value is cutoff frequency (Hz). For larger frames with bigger props set to lower value. |
|
||||
| gyro_lpf_type | BIQUAD | Specifies the type of the software LPF of the gyro signals. BIQUAD gives better filtering and more delay, PT1 less filtering and less delay, so use only on clean builds. |
|
||||
| gyro_stage2_lowpass_hz | 0 | Software based second stage lowpass filter for gyro. Value is cutoff frequency (Hz) |
|
||||
| gyro_stage2_lowpass_type | `BIQUAD` | Defines the type of stage 2 gyro LPF filter. Possible values: `PT1`, `BIQUAD`. `PT1` offers faster filter response while `BIQUAD` better attenuation. |
|
||||
| gyro_sync | OFF | This option enables gyro_sync feature. In this case the loop will be synced to gyro refresh rate. Loop will always wait for the newest gyro measurement. Maximum gyro refresh rate is determined by gyro_hardware_lpf |
|
||||
| has_flaps | OFF | Defines is UAV is capable of having flaps. If ON and AIRPLANE `platform_type` is used, **FLAPERON** flight mode will be available for the pilot |
|
||||
| heading_hold_rate_limit | 90 | This setting limits yaw rotation rate that HEADING_HOLD controller can request from PID inner loop controller. It is independent from manual yaw rate and used only when HEADING_HOLD flight mode is enabled by pilot, RTH or WAYPOINT modes. |
|
||||
| hott_alarm_sound_interval | 5 | Battery alarm delay in seconds for Hott telemetry |
|
||||
| i2c_speed | 400KHZ | This setting controls the clock speed of I2C bus. 400KHZ is the default that most setups are able to use. Some noise-free setups may be overclocked to 800KHZ. Some sensor chips or setups with long wires may work unreliably at 400KHZ - user can try lowering the clock speed to 200KHZ or even 100KHZ. User need to bear in mind that lower clock speeds might require higher looptimes (lower looptime rate) |
|
||||
| ibus_telemetry_type | 0 | Type compatibility ibus telemetry for transmitters. See Telemetry.md label IBUS for details. |
|
||||
| idle_power | 0 | Power draw at zero throttle used for remaining flight time/distance estimation in 0.01W unit |
|
||||
| imu_acc_ignore_rate | 0 | Total gyro rotation rate threshold [deg/s] to consider accelerometer trustworthy on airplanes |
|
||||
| imu_acc_ignore_slope | 0 | Half-width of the interval to gradually reduce accelerometer weight. Centered at `imu_acc_ignore_rate` (exactly 50% weight) |
|
||||
| imu_dcm_ki | 50 | Inertial Measurement Unit KI Gain for accelerometer measurements |
|
||||
| imu_dcm_ki_mag | 0 | Inertial Measurement Unit KI Gain for compass measurements |
|
||||
| imu_dcm_kp | 2500 | Inertial Measurement Unit KP Gain for accelerometer measurements |
|
||||
| imu_dcm_kp_mag | 10000 | Inertial Measurement Unit KP Gain for compass measurements |
|
||||
| inav_auto_mag_decl | ON | Automatic setting of magnetic declination based on GPS position. When used manual magnetic declination is ignored. |
|
||||
| inav_baro_epv | 100.000 | Uncertainty value for barometric sensor [cm] |
|
||||
| inav_gravity_cal_tolerance | 5 | Unarmed gravity calibration tolerance level. Won't finish the calibration until estimated gravity error falls below this value. |
|
||||
| inav_max_eph_epv | 1000.000 | Maximum uncertainty value until estimated position is considered valid and is used for navigation [cm] |
|
||||
| inav_max_surface_altitude | 200 | Max allowed altitude for surface following mode. [cm] |
|
||||
| inav_reset_altitude | FIRST_ARM | Defines when relative estimated altitude is reset to zero. Variants - `NEVER` (once reference is acquired it's used regardless); `FIRST_ARM` (keep altitude at zero until firstly armed), `EACH_ARM` (altitude is reset to zero on each arming) |
|
||||
| inav_reset_home | FIRST_ARM | Allows to chose when the home position is reset. Can help prevent resetting home position after accidental mid-air disarm. Possible values are: NEVER, FIRST_ARM and EACH_ARM |
|
||||
| inav_use_gps_velned | ON | Defined if iNav should use velocity data provided by GPS module for doing position and speed estimation. If set to OFF iNav will fallback to calculating velocity from GPS coordinates. Using native velocity data may improve performance on some GPS modules. Some GPS modules introduce significant delay and using native velocity may actually result in much worse performance. |
|
||||
| inav_w_acc_bias | 0.010 | Weight for accelerometer drift estimation |
|
||||
| inav_w_xy_gps_p | 1.000 | Weight of GPS coordinates in estimated UAV position and speed. |
|
||||
| inav_w_xy_gps_v | 2.000 | Weight of GPS velocity data in estimated UAV speed |
|
||||
| inav_w_xy_res_v | 0.500 | Decay coefficient for estimated velocity when GPS reference for position is lost |
|
||||
| inav_w_z_baro_p | 0.350 | Weight of barometer measurements in estimated altitude and climb rate |
|
||||
| inav_w_z_gps_p | 0.200 | Weight of GPS altitude measurements in estimated altitude. Setting is used only of airplanes |
|
||||
| inav_w_z_gps_v | 0.500 | Weight of GPS climb rate measurements in estimated climb rate. Setting is used on both airplanes and multirotors. If GPS doesn't support native climb rate reporting (i.e. NMEA GPS) you may consider setting this to zero |
|
||||
| inav_w_z_res_v | 0.500 | Decay coefficient for estimated climb rate when baro/GPS reference for altitude is lost |
|
||||
| iterm_windup | 50 | Used to prevent Iterm accumulation on during maneuvers. Iterm will be dampened when motors are reaching it's limit (when requested motor correction range is above percentage specified by this parameter) |
|
||||
| ledstrip_visual_beeper | OFF | |
|
||||
| looptime | 1000 | This is the main loop time (in us). Changing this affects PID effect with some PID controllers (see PID section for details). A very conservative value of 3500us/285Hz should work for everyone. Setting it to zero does not limit loop time, so it will go as fast as possible. |
|
||||
| ltm_update_rate | NORMAL | Defines the LTM update rate (use of bandwidth [NORMAL/MEDIUM/SLOW]). See Telemetry.md, LTM section for details. |
|
||||
| mag_calibration_time | 30 | Adjust how long time the Calibration of mag will last. |
|
||||
| mag_declination | 0 | Current location magnetic declination in format. For example, -6deg 37min = -637 for Japan. Leading zero in ddd not required. Get your local magnetic declination here: http://magnetic-declination.com/ . Not in use if inav_auto_mag_decl is turned on and you acquire valid GPS fix. |
|
||||
| mag_hardware | AUTO | Selection of mag hardware. See Wiki Sensor auto detect and hardware failure detection for more info |
|
||||
| mag_to_use | | Allow to chose between built-in and external compass sensor if they are connected to separate buses. Currently only for REVO target |
|
||||
| magzero_x | 0 | Magnetometer calibration X offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_y | 0 | Magnetometer calibration Y offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| magzero_z | 0 | Magnetometer calibration Z offset. If its 0 none offset has been applied and calibration is failed. |
|
||||
| manual_pitch_rate | 100 | Servo travel multiplier for the PITCH axis in `MANUAL` flight mode [0-100]% |
|
||||
| manual_rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by the `MANUAL` flight mode [0-100] |
|
||||
| manual_rc_yaw_expo | 20 | Exposition value used for the YAW axis by the `MANUAL` flight mode [0-100] |
|
||||
| manual_roll_rate | 100 | Servo travel multiplier for the ROLL axis in `MANUAL` flight mode [0-100]% |
|
||||
| manual_yaw_rate | 100 | Servo travel multiplier for the YAW axis in `MANUAL` flight mode [0-100]% |
|
||||
| max_angle_inclination_pit | 300 | Maximum inclination in level (angle) mode (PITCH axis). 100=10° |
|
||||
| max_angle_inclination_rll | 300 | Maximum inclination in level (angle) mode (ROLL axis). 100=10° |
|
||||
| max_check | 1900 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| max_throttle | 1850 | This is the maximum value (in us) sent to esc when armed. Default of 1850 are OK for everyone (legacy). For modern ESCs, higher values (c. 2000) may be more appropriate. If you have brushed motors, the value should be set to 2000. |
|
||||
| mc_airmode_threshold | 1300 | Defines airmode THROTTLE activation threshold when `mc_airmode_type` **THROTTLE_THRESHOLD** is used |
|
||||
| mc_airmode_type | STICK_CENTER | Defines the Airmode state handling type for Multirotors. Default **STICK_CENTER** is the classical approach in which Airmode is always active if enabled, but when the throttle is low and ROLL/PITCH/YAW sticks are centered, Iterms is not allowed to grow (ANTI_WINDUP). **THROTTLE_THRESHOLD** is the Airmode behavior known from Betaflight. In this mode, Airmode is active as soon THROTTLE position is above `mc_airmode_threshold` and stays active until disarm. ANTI_WINDUP is never triggered. For small Multirotors (up to 7-inch propellers) it is suggested to switch to **THROTTLE_THRESHOLD** since it keeps full stabilization no matter what pilot does with the sticks. Fixed Wings always use **STICK_CENTER** mode. |
|
||||
| mc_cd_lpf_hz | 30 | Cutoff frequency for Control Derivative. Lower value smoother reaction on fast stick movements. With higher values, response will be more aggressive, jerky |
|
||||
| mc_cd_pitch | 60 | Multicopter Control Derivative gain for PITCH |
|
||||
| mc_cd_roll | 60 | Multicopter Control Derivative gain for ROLL |
|
||||
| mc_cd_yaw | 60 | Multicopter Control Derivative gain for YAW |
|
||||
| mc_d_level | 75 | Multicopter attitude stabilisation HORIZON transition point |
|
||||
| mc_d_pitch | 23 | Multicopter rate stabilisation D-gain for PITCH |
|
||||
| mc_d_roll | 23 | Multicopter rate stabilisation D-gain for ROLL |
|
||||
| mc_d_yaw | 0 | Multicopter rate stabilisation D-gain for YAW |
|
||||
| mc_i_level | 15 | Multicopter attitude stabilisation low-pass filter cutoff |
|
||||
| mc_i_pitch | 30 | Multicopter rate stabilisation I-gain for PITCH |
|
||||
| mc_i_roll | 30 | Multicopter rate stabilisation I-gain for ROLL |
|
||||
| mc_i_yaw | 45 | Multicopter rate stabilisation I-gain for YAW |
|
||||
| mc_p_level | 20 | Multicopter attitude stabilisation P-gain |
|
||||
| mc_p_pitch | 40 | Multicopter rate stabilisation P-gain for PITCH |
|
||||
| mc_p_roll | 40 | Multicopter rate stabilisation P-gain for ROLL |
|
||||
| mc_p_yaw | 85 | Multicopter rate stabilisation P-gain for YAW |
|
||||
| min_check | 1100 | These are min/max values (in us) which, when a channel is smaller (min) or larger (max) than the value will activate various RC commands, such as arming, or stick configuration. Normally, every RC channel should be set so that min = 1000us, max = 2000us. On most transmitters this usually means 125% endpoints. Default check values are 100us above/below this value. |
|
||||
| min_command | 1000 | This is the PWM value sent to ESCs when they are not armed. If ESCs beep slowly when powered up, try decreasing this value. It can also be used for calibrating all ESCs at once. |
|
||||
| mode_range_logic_operator | OR | Control how Mode selection works in flight modes. If you example have Angle mode configured on two different Aux channels, this controls if you need both activated ( AND ) or if you only need one activated ( OR ) to active angle mode. |
|
||||
| model_preview_type | -1 | ID of mixer preset applied in a Configurator. **Do not modify manually**. Used only for backup/restore reasons. |
|
||||
| moron_threshold | 32 | When powering up, gyro bias is calculated. If the model is shaking/moving during this initial calibration, offsets are calculated incorrectly, and could lead to poor flying performance. This threshold means how much average gyro reading could differ before re-calibration is triggered. |
|
||||
| motor_accel_time | 0 | Minimum time for the motor(s) to accelerate from 0 to 100% throttle (ms) [0-1000] |
|
||||
| motor_decel_time | 0 | Minimum time for the motor(s) to deccelerate from 100 to 0% throttle (ms) [0-1000] |
|
||||
| motor_direction_inverted | OFF | Use if you need to inverse yaw motor direction. |
|
||||
| motor_pwm_protocol | STANDARD | Protocol that is used to send motor updates to ESCs. Possible values - STANDARD, ONESHOT125, ONESHOT42, MULTISHOT, DSHOT150, DSHOT300, DSHOT600, DSHOT1200, BRUSHED |
|
||||
| motor_pwm_rate | 400 | Output frequency (in Hz) for motor pins. Default is 400Hz for motor with motor_pwm_protocol set to STANDARD. For *SHOT (e.g. ONESHOT125) values of 1000 and 2000 have been tested by the development team and are supported. It may be possible to use higher values. For BRUSHED values of 8000 and above should be used. Setting to 8000 will use brushed mode at 8kHz switching frequency. Up to 32kHz is supported for brushed. Default is 16000 for boards with brushed motors. Note, that in brushed mode, minthrottle is offset to zero. For brushed mode, set max_throttle to 2000. |
|
||||
| name | Empty string | Craft name |
|
||||
| nav_auto_climb_rate | 500 | Maximum climb/descent rate that UAV is allowed to reach during navigation modes. [cm/s] |
|
||||
| nav_auto_speed | 300 | Maximum velocity firmware is allowed in full auto modes (RTH, WP) [cm/s] [Multirotor only] |
|
||||
| nav_disarm_on_landing | OFF | If set to ON, iNav disarms the FC after landing |
|
||||
| nav_emerg_landing_speed | 500 | Rate of descent UAV will try to maintain when doing emergency descent sequence [cm/s] |
|
||||
| nav_extra_arming_safety | ON | If set to ON drone won't arm if no GPS fix and any navigation mode like RTH or POSHOLD is configured. ALLOW_BYPASS allows the user to momentarily disable this check by holding yaw high (left stick held at the bottom right in mode 2) when switch arming is used |
|
||||
| nav_fw_allow_manual_thr_increase | OFF | Enable the possibility to manually increase the throttle in auto throttle controlled modes for fixed wing |
|
||||
| nav_fw_bank_angle | 20 | Max roll angle when rolling / turning in GPS assisted modes, is also restrained by global max_angle_inclination_rll |
|
||||
| nav_fw_climb_angle | 20 | Max pitch angle when climbing in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_control_smoothness | 0 | How smoothly the autopilot controls the airplane to correct the navigation error |
|
||||
| nav_fw_cruise_speed | 0 | Speed for the plane/wing at cruise throttle used for remaining flight time/distance estimation in cm/s |
|
||||
| nav_fw_cruise_thr | 1400 | Cruise throttle in GPS assisted modes, this includes RTH. Should be set high enough to avoid stalling. This values gives INAV a base for throttle when flying straight, and it will increase or decrease throttle based on pitch of airplane and the parameters below. In addition it will increase throttle if GPS speed gets below 7m/s ( hardcoded ) |
|
||||
| nav_fw_cruise_yaw_rate | 20 | Max YAW rate when NAV CRUISE mode is enabled (0=disable control via yaw stick) [dps] |
|
||||
| nav_fw_dive_angle | 15 | Max negative pitch angle when diving in GPS assisted modes, is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_heading_p | 60 | P gain of Heading Hold controller (Fixedwing) |
|
||||
| nav_fw_land_dive_angle | 2 | Dive angle that airplane will use during final landing phase. During dive phase, motor is stopped or IDLE and roll control is locked to 0 degrees |
|
||||
| nav_fw_launch_accel | 1863 | Forward acceleration threshold for bungee launch of throw launch [cm/s/s], 1G = 981 cm/s/s |
|
||||
| nav_fw_launch_climb_angle | 18 | Climb angle for launch sequence (degrees), is also restrained by global max_angle_inclination_pit |
|
||||
| nav_fw_launch_detect_time | 40 | Time for which thresholds have to breached to consider launch happened [ms] |
|
||||
| nav_fw_launch_idle_thr | 1000 | Launch idle throttle - throttle to be set before launch sequence is initiated. If set below minimum throttle it will force motor stop or at idle throttle (depending if the MOTOR_STOP is enabled). If set above minimum throttle it will force throttle to this value (if MOTOR_STOP is enabled it will be handled according to throttle stick position) |
|
||||
| nav_fw_launch_max_altitude | 0 | Altitude (centimeters) at which LAUNCH mode will be turned off and regular flight mode will take over [0-60000]. |
|
||||
| nav_fw_launch_max_angle | 45 | Max tilt angle (pitch/roll combined) to consider launch successful. Set to 180 to disable completely [deg] |
|
||||
| nav_fw_launch_min_time | 0 | Allow launch mode to execute at least this time (ms) and ignore stick movements [0-60000]. |
|
||||
| nav_fw_launch_motor_delay | 500 | Delay between detected launch and launch sequence start and throttling up (ms) |
|
||||
| nav_fw_launch_spinup_time | 100 | Time to bring power from minimum throttle to nav_fw_launch_thr - to avoid big stress on ESC and large torque from propeller |
|
||||
| nav_fw_launch_thr | 1700 | Launch throttle - throttle to be set during launch sequence (pwm units) |
|
||||
| nav_fw_launch_timeout | 5000 | Maximum time for launch sequence to be executed. After this time LAUNCH mode will be turned off and regular flight mode will take over (ms) |
|
||||
| nav_fw_launch_velocity | 300 | Forward velocity threshold for swing-launch detection [cm/s] |
|
||||
| nav_fw_loiter_radius | 5000 | PosHold radius. 3000 to 7500 is a good value (30-75m) [cm] |
|
||||
| nav_fw_max_thr | 1700 | Maximum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_min_thr | 1200 | Minimum throttle for flying wing in GPS assisted modes |
|
||||
| nav_fw_pitch2thr | 10 | Amount of throttle applied related to pitch attitude in GPS assisted modes. Throttle = nav_fw_cruise_throttle - (nav_fw_pitch2thr * pitch_angle). (notice that pitch_angle is in degrees and is negative when climbing and positive when diving, and throttle value is constrained between nav_fw_min_thr and nav_fw_max_thr) |
|
||||
| nav_fw_pos_hdg_d | 0 | D gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_i | 0 | I gain of heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_p | 60 | P gain of heading PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_hdg_pidsum_limit | 350 | Output limit for heading trajectory PID controller. (Fixedwing, rovers, boats) |
|
||||
| nav_fw_pos_xy_d | 8 | D gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_fw_pos_xy_i | 5 | I gain of 2D trajectory PID controller. Too high and there will be overshoot in trajectory. Better start tuning with zero |
|
||||
| nav_fw_pos_xy_p | 75 | P gain of 2D trajectory PID controller. Play with this to get a straight line between waypoints or a straight RTH |
|
||||
| nav_fw_pos_z_d | 0 | D gain of altitude PID controller (Fixedwing) |
|
||||
| nav_fw_pos_z_i | 0 | I gain of altitude PID controller (Fixedwing) |
|
||||
| nav_fw_pos_z_p | 50 | P gain of altitude PID controller (Fixedwing) |
|
||||
| nav_fw_yaw_deadband | 0 | Deadband for heading trajectory PID controller. When heading error is below the deadband, controller assumes that vehicle is on course |
|
||||
| nav_land_slowdown_maxalt | 2000 | Defines at what altitude the descent velocity should start to ramp down from 100% nav_landing_speed to 25% nav_landing_speed. [cm] |
|
||||
| nav_land_slowdown_minalt | 500 | Defines at what altitude the descent velocity should start to be 25% of nav_landing_speed [cm] |
|
||||
| nav_landing_speed | 200 | Vertical descent velocity during the RTH landing phase. [cm/s] |
|
||||
| nav_manual_climb_rate | 200 | Maximum climb/descent rate firmware is allowed when processing pilot input for ALTHOLD control mode [cm/s] |
|
||||
| nav_manual_speed | 500 | Maximum velocity firmware is allowed when processing pilot input for POSHOLD/CRUISE control mode [cm/s] [Multirotor only] |
|
||||
| nav_mc_auto_disarm_delay | 2000 | |
|
||||
| nav_mc_bank_angle | 30 | Maximum banking angle (deg) that multicopter navigation is allowed to set. Machine must be able to satisfy this angle without loosing altitude |
|
||||
| nav_mc_braking_bank_angle | 40 | max angle that MR is allowed to bank in BOOST mode |
|
||||
| nav_mc_braking_boost_disengage_speed | 100 | BOOST will be disabled when speed goes below this value |
|
||||
| nav_mc_braking_boost_factor | 100 | acceleration factor for BOOST phase |
|
||||
| nav_mc_braking_boost_speed_threshold | 150 | BOOST can be enabled when speed is above this value |
|
||||
| nav_mc_braking_boost_timeout | 750 | how long in ms BOOST phase can happen |
|
||||
| nav_mc_braking_disengage_speed | 75 | braking is disabled when speed goes below this value |
|
||||
| nav_mc_braking_speed_threshold | 100 | min speed in cm/s above which braking can happen |
|
||||
| nav_mc_braking_timeout | 2000 | timeout in ms for braking |
|
||||
| nav_mc_heading_p | 60 | P gain of Heading Hold controller (Multirotor) |
|
||||
| nav_mc_hover_thr | 1500 | Multicopter hover throttle hint for altitude controller. Should be set to approximate throttle value when drone is hovering. |
|
||||
| nav_mc_pos_deceleration_time | 120 | Used for stoping distance calculation. Stop position is computed as _speed_ * _nav_mc_pos_deceleration_time_ from the place where sticks are released. Braking mode overrides this setting |
|
||||
| nav_mc_pos_expo | 10 | Expo for PosHold control |
|
||||
| nav_mc_pos_xy_p | 65 | Controls how fast the drone will fly towards the target position. This is a multiplier to convert displacement to target velocity |
|
||||
| nav_mc_pos_z_p | 50 | P gain of altitude PID controller (Multirotor) |
|
||||
| nav_mc_vel_xy_d | 100 | D gain of Position-Rate (Velocity to Acceleration) PID controller. It can damp P and I. Increasing D might help when drone overshoots target. |
|
||||
| nav_mc_vel_xy_i | 15 | I gain of Position-Rate (Velocity to Acceleration) PID controller. Used for drift compensation (caused by wind for example). Higher I means stronger response to drift. Too much I gain might cause target overshot |
|
||||
| nav_mc_vel_xy_p | 40 | P gain of Position-Rate (Velocity to Acceleration) PID controller. Higher P means stronger response when position error occurs. Too much P might cause "nervous" behavior and oscillations |
|
||||
| nav_mc_vel_z_d | 10 | D gain of velocity PID controller |
|
||||
| nav_mc_vel_z_i | 50 | I gain of velocity PID controller |
|
||||
| nav_mc_vel_z_p | 100 | P gain of velocity PID controller |
|
||||
| nav_min_rth_distance | 500 | Minimum distance from homepoint when RTH full procedure will be activated [cm]. Below this distance, the mode will activate at the current location and the final phase is executed (loiter / land). Above this distance, the full procedure is activated, which may include initial climb and flying directly to the homepoint before entering the loiter / land phase. |
|
||||
| nav_overrides_motor_stop | ON | Setting to OFF combined with MOTOR_STOP feature will allow user to stop motor when in autonomous modes. On most places this setting is likely to cause a stall. |
|
||||
| nav_position_timeout | 5 | If GPS fails wait for this much seconds before switching to emergency landing mode (0 - disable) |
|
||||
| nav_rth_abort_threshold | 50000 | RTH sanity checking feature will notice if distance to home is increasing during RTH and once amount of increase exceeds the threshold defined by this parameter, instead of continuing RTH machine will enter emergency landing, self-level and go down safely. Default is 500m which is safe enough for both multirotor machines and airplanes. [cm] |
|
||||
| nav_rth_allow_landing | ALWAYS | If set to ON drone will land as a last phase of RTH. |
|
||||
| nav_rth_alt_mode | AT_LEAST | Configure how the aircraft will manage altitude on the way home, see Navigation modes on wiki for more details |
|
||||
| nav_rth_altitude | 1000 | Used in EXTRA, FIXED and AT_LEAST rth alt modes [cm] (Default 1000 means 10 meters) |
|
||||
| nav_rth_climb_first | ON | If set to ON drone will climb to nav_rth_altitude first and head home afterwards. If set to OFF drone will head home instantly and climb on the way. |
|
||||
| nav_rth_climb_ignore_emerg | OFF | If set to ON, aircraft will execute initial climb regardless of position sensor (GPS) status. |
|
||||
| nav_rth_home_altitude | 0 | Aircraft will climb/descend to this altitude after reaching home if landing is not enabled. Set to 0 to stay at `nav_rth_altitude` (default) [cm] |
|
||||
| nav_rth_home_offset_direction | 0 | Direction offset from GPS established home to "safe" position used for RTH (degrees, 0=N, 90=E, 180=S, 270=W, requires non-zero offset distance) |
|
||||
| nav_rth_home_offset_distance | 0 | Distance offset from GPS established home to "safe" position used for RTH (cm, 0 disables) |
|
||||
| nav_rth_tail_first | OFF | If set to ON drone will return tail-first. Obviously meaningless for airplanes. |
|
||||
| nav_use_fw_yaw_control | OFF | Enables or Disables the use of the heading PID controller on fixed wing. Heading PID controller is always enabled for rovers and boats |
|
||||
| nav_use_midthr_for_althold | OFF | If set to OFF, the FC remembers your throttle stick position when enabling ALTHOLD and treats it as a neutral midpoint for holding altitude |
|
||||
| nav_user_control_mode | ATTI | Defines how Pitch/Roll input from RC receiver affects flight in POSHOLD mode: ATTI - pitch/roll controls attitude like in ANGLE mode; CRUISE - pitch/roll controls velocity in forward and right direction. |
|
||||
| nav_wp_radius | 100 | Waypoint radius [cm]. Waypoint would be considered reached if machine is within this radius |
|
||||
| nav_wp_safe_distance | 10000 | First waypoint in the mission should be closer than this value [cm]. A value of 0 disables this check. |
|
||||
| osd_ahi_style | DEFAULT | Sets OSD Artificial Horizon style "DEFAULT" or "LINE" for the FrSky Graphical OSD. |
|
||||
| osd_alt_alarm | 100 | Value above which to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_artificial_horizon_max_pitch | 20 | Max pitch, in degrees, for OSD artificial horizon |
|
||||
| osd_baro_temp_alarm_max | 600 | Temperature above which the baro temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_baro_temp_alarm_min | -200 | Temperature under which the baro temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_current_alarm | 0 | Value above which the OSD current consumption element will start blinking. Measured in full Amperes. |
|
||||
| osd_dist_alarm | 1000 | Value above which to make the OSD distance from home indicator blink (meters) |
|
||||
| osd_esc_temp_alarm_max | 900 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_esc_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_estimations_wind_compensation | ON | Use wind estimation for remaining flight time/distance estimation |
|
||||
| osd_failsafe_switch_layout | OFF | If enabled the OSD automatically switches to the first layout during failsafe |
|
||||
| osd_gforce_alarm | 5 | Value above which the OSD g force indicator will blink (g) |
|
||||
| osd_gforce_axis_alarm_max | 5 | Value above which the OSD axis g force indicators will blink (g) |
|
||||
| osd_gforce_axis_alarm_min | -5 | Value under which the OSD axis g force indicators will blink (g) |
|
||||
| osd_hud_wp_disp | OFF | Controls display of the next waypoints in the HUD. |
|
||||
| osd_imu_temp_alarm_max | 600 | Temperature above which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_imu_temp_alarm_min | -200 | Temperature under which the IMU temperature OSD element will start blinking (decidegrees centigrade) |
|
||||
| osd_main_voltage_decimals | 1 | Number of decimals for the battery voltages displayed in the OSD [1-2]. |
|
||||
| osd_neg_alt_alarm | 5 | Value bellow which (negative altitude) to make the OSD relative altitude indicator blink (meters) |
|
||||
| osd_row_shiftdown | 0 | Number of rows to shift the OSD display (increase if top rows are cut off) |
|
||||
| osd_rssi_alarm | 20 | Value bellow which to make the OSD RSSI indicator blink |
|
||||
| osd_stats_energy_unit | MAH | Unit used for the drawn energy in the OSD stats [MAH/WH] (milliAmpere hour/ Watt hour) |
|
||||
| osd_temp_label_align | LEFT | Allows to chose between left and right alignment for the OSD temperature sensor labels. Valid values are `LEFT` and `RIGHT` |
|
||||
| osd_time_alarm | 10 | Value above which to make the OSD flight time indicator blink (minutes) |
|
||||
| osd_units | METRIC | IMPERIAL, METRIC, UK |
|
||||
| osd_video_system | AUTO | Video system used. Possible values are `AUTO`, `PAL` and `NTSC` |
|
||||
| pid_type | | Allows to set type of PID controller used in control loop. Possible values: `NONE`, `PID`, `PIFF`, `AUTO`. Change only in case of experimental platforms like VTOL, tailsitters, rovers, boats, etc. Airplanes should always use `PIFF` and multirotors `PID` |
|
||||
| pidsum_limit | 500 | A limitation to overall amount of correction Flight PID can request on each axis (Roll/Pitch). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| pidsum_limit_yaw | 400 | A limitation to overall amount of correction Flight PID can request on each axis (Yaw). If when doing a hard maneuver on one axis machine looses orientation on other axis - reducing this parameter may help |
|
||||
| pitch_rate | 20 | Defines rotation rate on PITCH axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| platform_type | "MULTIROTOR" | Defines UAV platform type. Allowed values: "MULTIROTOR", "AIRPLANE", "HELICOPTER", "TRICOPTER", "ROVER", "BOAT". Currently only MULTIROTOR, AIRPLANE and TRICOPTER types are implemented |
|
||||
| pos_hold_deadband | 20 | Stick deadband in [r/c points], applied after r/c deadband and expo |
|
||||
| rangefinder_median_filter | OFF | 3-point median filtering for rangefinder readouts |
|
||||
| rate_accel_limit_roll_pitch | 0 | Limits acceleration of ROLL/PITCH rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 5000 dps^2 and even > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 360 dps^2). When set correctly, it greatly improves stopping performance. Value of 0 disables limiting. |
|
||||
| rate_accel_limit_yaw | 10000 | Limits acceleration of YAW rotation speed that can be requested by stick input. In degrees-per-second-squared. Small and powerful UAV flies great with high acceleration limit ( > 10000 dps^2). Big and heavy multirotors will benefit from low acceleration limit (~ 180 dps^2). When set correctly, it greatly improves stopping performance and general stability during yaw turns. Value of 0 disables limiting. |
|
||||
| rc_expo | 70 | Exposition value used for the PITCH/ROLL axes by all the stabilized flights modes (all but `MANUAL`) |
|
||||
| rc_filter_frequency | 50 | RC data biquad filter cutoff frequency. Lower cutoff frequencies result in smoother response at expense of command control delay. Practical values are 20-50. Set to zero to disable entirely and use unsmoothed RC stick values |
|
||||
| rc_yaw_expo | 20 | Exposition value used for the YAW axis by all the stabilized flights modes (all but `MANUAL`) |
|
||||
| reboot_character | 82 | Special character used to trigger reboot |
|
||||
| report_cell_voltage | OFF | S.Port, D-Series, and IBUS telemetry: Send the average cell voltage if set to ON |
|
||||
| roll_rate | 20 | Defines rotation rate on ROLL axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
| rpm_gyro_filter_enabled | `OFF` | Enables gyro RPM filtere. Set to `ON` only when ESC telemetry is working and rotation speed of the motors is correctly reported to INAV |
|
||||
| rpm_gyro_harmonics | 1 | Number of harmonic frequences to be covered by gyro RPM filter. Default value of `1` usually works just fine |
|
||||
| rpm_gyro_min_hz | 150 | The lowest frequency for gyro RPM filtere. Default `150` is fine for 5" mini-quads. On 7-inch drones you can lower even down to `60`-`70` |
|
||||
| rpm_gyro_q | 500 | Q factor for gyro RPM filter. Lower values give softer, wider attenuation. Usually there is no need to change this setting |
|
||||
| rssi_adc_channel | - | ADC channel to use for analog RSSI input. Defaults to board RSSI input (if available). 0 = disabled |
|
||||
| rssi_channel | 0 | RX channel containing the RSSI signal |
|
||||
| rssi_max | 100 | The maximum RSSI value sent by the receiver, in %. For example, if your receiver's maximum RSSI value shows as 83% in the configurator/OSD set this parameter to 83. See also rssi_min. |
|
||||
| rssi_min | 0 | The minimum RSSI value sent by the receiver, in %. For example, if your receiver's minimum RSSI value shows as 42% in the configurator/OSD set this parameter to 42. See also rssi_max. Note that rssi_min can be set to a value bigger than rssi_max to invert the RSSI calculation (i.e. bigger values mean lower RSSI). |
|
||||
| rssi_source | `AUTO` | Source of RSSI input. Possible values: `NONE`, `AUTO`, `ADC`, `CHANNEL`, `PROTOCOL`, `MSP` |
|
||||
| rth_energy_margin | 5 | Energy margin wanted after getting home (percent of battery energy capacity). Use for the remaining flight time/distance calculation |
|
||||
| rx_max_usec | 2115 | Defines the longest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value higher than this value then the channel will be marked as bad and will default to the value of mid_rc. |
|
||||
| rx_min_usec | 885 | Defines the shortest pulse width value used when ensuring the channel value is valid. If the receiver gives a pulse value lower than this value then the channel will be marked as bad and will default to the value of mid_rc. |
|
||||
| sdcard_detect_inverted | `TARGET dependent` | This setting drives the way SD card is detected in card slot. On some targets (AnyFC F7 clone) different card slot was used and depending of hardware revision ON or OFF setting might be required. If card is not detected, change this value. |
|
||||
| serialrx_halfduplex | OFF | Allow serial receiver to operate on UART TX pin. With some receivers will allow control and telemetry over a single wire |
|
||||
| serialrx_inverted | OFF | Reverse the serial inversion of the serial RX protocol. When this value is OFF, each protocol will use its default signal (e.g. SBUS will use an inverted signal). Some OpenLRS receivers produce a non-inverted SBUS signal. This setting supports this type of receivers (including modified FrSKY). |
|
||||
| serialrx_provider | SPEK1024 | When feature SERIALRX is enabled, this allows connection to several receivers which output data via digital interface resembling serial. See RX section. |
|
||||
| servo_center_pulse | 1500 | Servo midpoint |
|
||||
| servo_lpf_hz | 20 | Selects the servo PWM output cutoff frequency. Value is in [Hz] |
|
||||
| servo_protocol | PWM | An option to chose the protocol/option that would be used to output servo data. Possible options `PWM` (FC servo outputs), `SERVO_DRIVER` (I2C PCA9685 peripheral), `SBUS` (S.Bus protocol output via a configured serial port) |
|
||||
| servo_pwm_rate | 50 | Output frequency (in Hz) servo pins. When using tricopters or gimbal with digital servo, this rate can be increased. Max of 498Hz (for 500Hz pwm period), and min of 50Hz. Most digital servos will support for example 330Hz. |
|
||||
| sim_ground_station_number | Empty string | Number of phone that is used to communicate with SIM module. Messages / calls from other numbers are ignored. If undefined, can be set by calling or sending a message to the module. |
|
||||
| sim_low_altitude | 0 | Threshold for low altitude warning messages sent by SIM module when the 'L' transmit flag is set in `sim_transmit_flags`. |
|
||||
| sim_pin | Empty string | PIN code for the SIM module |
|
||||
| sim_transmit_flags | F | String specifying text message transmit condition flags for the SIM module. Flags can be given in any order. Empty string means the module only sends response messages. `A`: acceleration events, `T`: continuous transmission, `F`: continuous transmission in failsafe mode, `L`: continuous transmission when altitude is below `sim_low_altitude`, `G`: continuous transmission when GPS signal quality is low |
|
||||
| sim_transmit_interval | 60 | Text message transmission interval in seconds for SIM module. Minimum value: 10 |
|
||||
| small_angle | 25 | If the aircraft tilt angle exceed this value the copter will refuse to arm. |
|
||||
| smartport_fuel_unit | MAH | S.Port telemetry only: Unit of the value sent with the `FUEL` ID (FrSky D-Series always sends percent). [PERCENT/MAH/MWH] |
|
||||
| spektrum_sat_bind | 0 | 0 = disabled. Used to bind the spektrum satellite to RX |
|
||||
| stats | OFF | General switch of the statistics recording feature (a.k.a. odometer) |
|
||||
| stats_total_dist | 0 | Total flight distance [in meters]. The value is updated on every disarm when "stats" are enabled. |
|
||||
| stats_total_time | 0 | Total flight time [in seconds]. The value is updated on every disarm when "stats" are enabled. |
|
||||
| switch_disarm_delay | 250 | Delay before disarming when requested by switch (ms) [0-1000] |
|
||||
| telemetry_halfduplex | OFF | S.Port telemetry only: Turn UART into UNIDIR for usage on F1 and F4 target. See Telemetry.md for details |
|
||||
| telemetry_inverted | OFF | Determines if the telemetry protocol default signal inversion is reversed. This should be OFF in most cases unless a custom or hacked RX is used. |
|
||||
| telemetry_switch | OFF | Which aux channel to use to change serial output & baud rate (MSP / Telemetry). It disables automatic switching to Telemetry when armed. |
|
||||
| thr_comp_weight | 0.692 | Weight used for the throttle compensation based on battery voltage. See the [battery documentation](Battery.md#automatic-throttle-compensation-based-on-battery-voltage) |
|
||||
| thr_expo | 0 | Throttle exposition value |
|
||||
| thr_mid | 50 | Throttle value when the stick is set to mid-position. Used in the throttle curve calculation. |
|
||||
| throttle_idle | 15 | The percentage of the throttle range (`max_throttle` - `min_command`) above `min_command` used for minimum / idle throttle. |
|
||||
| throttle_scale | 1.000 | Throttle scaling factor. `1` means no throttle scaling. `0.5` means throttle scaled down by 50% |
|
||||
| throttle_tilt_comp_str | 0 | Can be used in ANGLE and HORIZON mode and will automatically boost throttle when banking. Setting is in percentage, 0=disabled. |
|
||||
| tpa_breakpoint | 1500 | See tpa_rate. |
|
||||
| tpa_rate | 0 | Throttle PID attenuation reduces influence of P on ROLL and PITCH as throttle increases. For every 1% throttle after the TPA breakpoint, P is reduced by the TPA rate. |
|
||||
| tri_unarmed_servo | ON | On tricopter mix only, if this is set to ON, servo will always be correcting regardless of armed state. to disable this, set it to OFF. |
|
||||
| tz_automatic_dst | OFF | Automatically add Daylight Saving Time to the GPS time when needed or simply ignore it. Includes presets for EU and the USA - if you live outside these areas it is suggested to manage DST manually via `tz_offset`. |
|
||||
| tz_offset | 0 | Time zone offset from UTC, in minutes. This is applied to the GPS time for logging and time-stamping of Blackbox logs |
|
||||
| vbat_adc_channel | - | ADC channel to use for battery voltage sensor. Defaults to board VBAT input (if available). 0 = disabled |
|
||||
| vbat_cell_detect_voltage | 430 | Maximum voltage per cell, used for auto-detecting the number of cells of the battery in 0.01V units, default is 4.30V |
|
||||
| vbat_max_cell_voltage | 420 | Maximum voltage per cell in 0.01V units, default is 4.20V |
|
||||
| vbat_meter_type | `ADC` | Vbat voltage source. Possible values: `NONE`, `ADC`, `ESC`. `ESC` required ESC telemetry enebled and running |
|
||||
| vbat_min_cell_voltage | 330 | Minimum voltage per cell, this triggers battery out alarms, in 0.01V units, default is 330 (3.3V) |
|
||||
| vbat_scale | 1100 | Battery voltage calibration value. 1100 = 11:1 voltage divider (10k:1k) x 100. Adjust this slightly if reported pack voltage is different from multimeter reading. You can get current voltage by typing "status" in cli. |
|
||||
| vbat_warning_cell_voltage | 350 | Warning voltage per cell, this triggers battery-warning alarms, in 0.01V units, default is 350 (3.5V) |
|
||||
| vtx_band | 4 | Configure the VTX band. Set to zero to use `vtx_freq`. Bands: 1: A, 2: B, 3: E, 4: F, 5: Race. |
|
||||
| vtx_channel | 1 | Channel to use within the configured `vtx_band`. Valid values are [1, 8]. |
|
||||
| vtx_halfduplex | ON | Use half duplex UART to communicate with the VTX, using only a TX pin in the FC. |
|
||||
| vtx_low_power_disarm | OFF | When the craft is disarmed, set the VTX to its lowest power. `ON` will set the power to its minimum value on startup, increase it to `vtx_power` when arming and change it back to its lowest setting after disarming. `UNTIL_FIRST_ARM` will start with minimum power, but once the craft is armed it will increase to `vtx_power` and it will never decrease until the craft is power cycled. |
|
||||
| vtx_power | 1 | VTX RF power level to use. The exact number of mw depends on the VTX hardware. |
|
||||
| yaw_deadband | 5 | These are values (in us) by how much RC input can be different before it's considered valid. For transmitters with jitter on outputs, this value can be increased. Defaults are zero, but can be increased up to 10 or so if rc inputs twitch while idle. |
|
||||
| yaw_lpf_hz | 30 | Yaw low pass filter cutoff frequency. Should be disabled (set to `0`) on small multirotors (7 inches and below) |
|
||||
| yaw_rate | 20 | Defines rotation rate on YAW axis that UAV will try to archive on max. stick deflection. Rates are defined in tens of degrees (deca-degrees) per second [rate = dps/10]. That means, rate 20 represents 200dps rotation speed. Default 20 (200dps) is more less equivalent of old Cleanflight/Baseflight rate 0. Max. 180 (1800dps) is what gyro can measure. |
|
||||
|
||||
> Note: this table is autogenerated. Do not edit it manually.
|
|
@ -1,15 +1,15 @@
|
|||
#Building Manual.
|
||||
# Building Manual.
|
||||
|
||||
The manual PDF file is generated by concatenating relevant markdown files and by transforming the result using Gimli to obtain the final PDF file. This steps are handled automatically by the ```build_docs.sh``` script located in the root of the repository next to the Makefile.
|
||||
|
||||
##Requirements & Installation
|
||||
## Requirements & Installation
|
||||
The PDF manual generation uses the Gimli for the conversion. It can be installed via ruby gems. On Debian based systems the installation steps are:
|
||||
```bash
|
||||
sudo apt-get install ruby1.9.1 ruby1.9.1-dev rubygems zlib1g-dev wkhtmltopdf libxml2-dev libxslt-dev
|
||||
sudo gem1.9.1 install gimli
|
||||
```
|
||||
|
||||
##Configuration
|
||||
## Configuration
|
||||
All markdown files need to be registered in the ```build_manual.sh``` file individually by modifying the ```doc_files``` variable / array:
|
||||
```bash
|
||||
doc_files=( 'Configuration.md'
|
||||
|
|
|
@ -2,17 +2,53 @@
|
|||
|
||||
Linux subsystem for Windows 10 is probably the simplest way of building INAV under Windows 10.
|
||||
|
||||
1. Enable WSL (_Windows Subsystem for Linux) using any guide from internet. [This](https://winaero.com/blog/enable-wsl-windows-10-fall-creators-update/) is up to date step by step (January 2018)
|
||||
1. From _Windows Store_ install `Ubuntu`
|
||||
1. Start `Ubuntu` and run:
|
||||
1. `sudo add-apt-repository ppa:team-gcc-arm-embedded/ppa`
|
||||
1. `sudo apt-get update`
|
||||
1. `sudo apt-get install gcc-arm-embedded make ruby`
|
||||
## Setting up the environment
|
||||
|
||||
At the moment (January 2018) it will install `gcc-arm-none-eabi` in version _7 q4_
|
||||
Enable WSL:
|
||||
run `windows features`
|
||||
enable `windows subsytem for linux`
|
||||
reboot
|
||||
|
||||
From this moment INAV can be build using the following command
|
||||
|
||||
`make TARGET={TARGET_NAME}`
|
||||
Install Ubuntu:
|
||||
1. Go to Microsoft store https://www.microsoft.com/en-gb/store/b/home
|
||||
1. Search and install most recent Ubuntu LTS version
|
||||
1. When download completed, select `Launch Ubuntu`
|
||||
1. When prompted enter a user name and password which you will need to remember
|
||||
1. When complete, the linux command prompt will be displayed
|
||||
|
||||
Of course, replace `{TARGET_NAME}` with a target you want to compile
|
||||
NOTE: from this point all commands are entered into the Ubunto shell command window
|
||||
|
||||
Update the repo packages:
|
||||
1. `sudo apt update`
|
||||
|
||||
Install Git, Make, gcc and Ruby
|
||||
1. `sudo apt-get install git`
|
||||
1. `sudo apt-get install make`
|
||||
1. `sudo apt-get install gcc-arm-none-eabi`
|
||||
1. `sudo apt-get install ruby`
|
||||
|
||||
## Downloading the iNav repository (example):
|
||||
|
||||
Mount MS windows C drive and clone iNav
|
||||
1. `cd /mnt/c`
|
||||
1. `git clone https://github.com/iNavFlight/inav.git`
|
||||
|
||||
You are ready!
|
||||
You now have a folder called inav in the root of C drive that you can edit in windows
|
||||
|
||||
|
||||
## Building (example):
|
||||
|
||||
Launch Ubuntu:
|
||||
Click Windows Start button then scroll and lauch "Ubuntu"
|
||||
|
||||
Building from Ubunto command line
|
||||
`cd /mnt/c/inav`
|
||||
`make clean TARGET=OMNIBUSF4PRO` (as an example)
|
||||
`make TARGET=MATEKF405` (as an example)
|
||||
|
||||
|
||||
## Flashing:
|
||||
Launch windows configurator GUI and from within the firmware flasher select `Load firmware[Local]`
|
||||
Hex files can be found in the folder `c:\inav\obj`
|
||||
|
|
|
@ -1,7 +1,7 @@
|
|||
# Building in windows light
|
||||
no cygwin and no path changes
|
||||
|
||||
##Install Git for windows
|
||||
## Install Git for windows
|
||||
download https://github.com/git-for-windows/git/releases/download/v2.10.1.windows.1/Git-2.10.1-32-bit.exe
|
||||
|
||||
Recommended install location is C:\Git (no spaces or special characters in path)
|
||||
|
@ -28,21 +28,21 @@ Follow images as not all are at default settings.
|
|||
|
||||

|
||||
|
||||
##Install toolset scripts
|
||||
## Install toolset scripts
|
||||
download https://www.dropbox.com/s/hhlr16h657y4l5u/devtools.zip?dl=0
|
||||
|
||||
extract it into C:\ it creates devtools folder
|
||||
|
||||
##Install latest arm toolchain
|
||||
## Install latest arm toolchain
|
||||
download https://gcc.gnu.org/mirrors.html
|
||||
|
||||
extract it into C:\devtools\gcc-arm-none-eabi-... (folder already there)
|
||||
|
||||
##Install Ruby
|
||||
## Install Ruby
|
||||
|
||||
Install the latest Ruby version using [Ruby Installer](https://rubyinstaller.org).
|
||||
|
||||
##Test
|
||||
## Test
|
||||
Run C:\devtools\shF4.cmd
|
||||
|
||||
If everything went according the manual you should be in mingw console window. (if not we need to update this manual)
|
||||
|
|
|
@ -77,24 +77,34 @@ The main flow for a contributing is as follows:
|
|||
1. Login to github, go to the INAV repository and press `fork`.
|
||||
2. Then using the command line/terminal on your computer: `git clone <url to YOUR fork>`
|
||||
3. `cd inav`
|
||||
4. `git checkout development`
|
||||
4. `git checkout master`
|
||||
5. `git checkout -b my-new-code`
|
||||
6. Make changes
|
||||
7. `git add <files that have changed>`
|
||||
8. `git commit`
|
||||
9. `git push origin my-new-code`
|
||||
10. Create pull request using github UI to merge your changes from your new branch into `inav/development`
|
||||
10. Create pull request using github UI to merge your changes from your new branch into `inav/master`
|
||||
11. Repeat from step 4 for new other changes.
|
||||
|
||||
The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `development` branch.
|
||||
The primary thing to remember is that separate pull requests should be created for separate branches. Never create a pull request from your `master` branch.
|
||||
|
||||
Later, you can get the changes from the INAV repo into your `development` branch by adding INAV as a git remote and merging from it as follows:
|
||||
Later, you can get the changes from the INAV repo into your `master` branch by adding INAV as a git remote and merging from it as follows:
|
||||
|
||||
1. `git remote add upstream https://github.com/iNavFlight/inav.git`
|
||||
2. `git checkout development`
|
||||
2. `git checkout master`
|
||||
3. `git fetch upstream`
|
||||
4. `git merge upstream/development`
|
||||
5. `git push origin development` is an optional step that will update your fork on github
|
||||
4. `git merge upstream/master`
|
||||
5. `git push origin master` is an optional step that will update your fork on github
|
||||
|
||||
|
||||
You can also perform the git commands using the git client inside Eclipse. Refer to the Eclipse git manual.
|
||||
|
||||
## Branching and release workflow
|
||||
|
||||
Normally, all development occurs on the `master` branch. Every release will have it's own branch named `release_x.y.z`.
|
||||
|
||||
During release candidate cycle we will follow the process outlined below:
|
||||
|
||||
1. Create a release branch `release_x.y.z`
|
||||
2. All bug fixes found in the release candidates will be merged into `release_x.y.z` branch and not into the `master`.
|
||||
3. After final release is made, the branch `release_x.y.z` is locked, and merged into `master` bringing all of the bug fixes into the development branch. Merge conflicts that may arise at this stage are resolved manually.
|
||||
|
|
|
@ -24,16 +24,22 @@ In addition to a cross-compiler, it is necessary to install some other tools:
|
|||
|
||||
### Ubuntu / Debian
|
||||
```
|
||||
$ # make sure the system is updated first
|
||||
$ sudo apt update && sudo apt upgrade
|
||||
$ sudo apt install gcc git make ruby curl
|
||||
```
|
||||
|
||||
### Fedora
|
||||
```
|
||||
$ # make sure the system is updated first
|
||||
$ sudo dnf -y update
|
||||
$ sudo dnf install gcc git make ruby curl
|
||||
```
|
||||
|
||||
### Arch
|
||||
```
|
||||
$ # make sure the system is updated first
|
||||
$ sudo pacman -Syu
|
||||
$ sudo pacman -S gcc git make ruby curl
|
||||
```
|
||||
|
||||
|
|
|
@ -1,4 +1,4 @@
|
|||
#Travis
|
||||
# Travis
|
||||
|
||||
INAV provides Travis build and config files in the repository root.
|
||||
|
||||
|
|
File diff suppressed because it is too large
Load diff
File diff suppressed because it is too large
Load diff
|
@ -1,38 +0,0 @@
|
|||
// Copyright 2006, Google Inc.
|
||||
// All rights reserved.
|
||||
//
|
||||
// Redistribution and use in source and binary forms, with or without
|
||||
// modification, are permitted provided that the following conditions are
|
||||
// met:
|
||||
//
|
||||
// * Redistributions of source code must retain the above copyright
|
||||
// notice, this list of conditions and the following disclaimer.
|
||||
// * Redistributions in binary form must reproduce the above
|
||||
// copyright notice, this list of conditions and the following disclaimer
|
||||
// in the documentation and/or other materials provided with the
|
||||
// distribution.
|
||||
// * Neither the name of Google Inc. nor the names of its
|
||||
// contributors may be used to endorse or promote products derived from
|
||||
// this software without specific prior written permission.
|
||||
//
|
||||
// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
// "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
// LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR
|
||||
// A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
|
||||
// OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
|
||||
// SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
|
||||
// LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE,
|
||||
// DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY
|
||||
// THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
|
||||
// (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
|
||||
// OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
|
||||
|
||||
#include <stdio.h>
|
||||
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
GTEST_API_ int main(int argc, char **argv) {
|
||||
printf("Running main() from gtest_main.cc\n");
|
||||
testing::InitGoogleTest(&argc, argv);
|
||||
return RUN_ALL_TESTS();
|
||||
}
|
|
@ -12,3 +12,6 @@ endif
|
|||
|
||||
gdb-openocd: $(TARGET_ELF)
|
||||
$(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS)
|
||||
|
||||
gdb-openocd-bl: $(TARGET_BL_ELF)
|
||||
$(GDB) $< -ex "target remote $(GDB_REMOTE)" $(GDB_OPENOCD_INIT_CMDS)
|
||||
|
|
|
@ -3,7 +3,7 @@
|
|||
#
|
||||
|
||||
ifeq ($(OPBL),yes)
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k_opbl.ld
|
||||
endif
|
||||
|
||||
TARGET_FLASH := 256
|
||||
|
@ -47,7 +47,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
VPATH := $(VPATH):$(FATFS_DIR)
|
||||
endif
|
||||
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F303_$(FLASH_SIZE)k.ld
|
||||
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
||||
|
@ -74,7 +74,9 @@ MCU_COMMON_SRC = \
|
|||
drivers/serial_uart_stm32f30x.c \
|
||||
drivers/system_stm32f30x.c \
|
||||
drivers/timer_impl_stdperiph.c \
|
||||
drivers/timer_stm32f30x.c
|
||||
drivers/timer_stm32f30x.c \
|
||||
src/main/drivers/bus_spi.c
|
||||
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4
|
||||
|
|
|
@ -141,23 +141,23 @@ endif
|
|||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F411xE
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
|
||||
STARTUP_SRC = startup_stm32f411xe.s
|
||||
DEVICE_FLAGS := -DSTM32F411xE
|
||||
LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F411.ld
|
||||
STARTUP_SRC := startup_stm32f411xe.s
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F40_41xxx -DSTM32F405xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
|
||||
STARTUP_SRC = startup_stm32f40xx.s
|
||||
DEVICE_FLAGS := -DSTM32F40_41xxx -DSTM32F405xx
|
||||
LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F405.ld
|
||||
STARTUP_SRC := startup_stm32f40xx.s
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F446_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F446xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f446.ld
|
||||
STARTUP_SRC = startup_stm32f446xx.s
|
||||
DEVICE_FLAGS := -DSTM32F446xx
|
||||
LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F446.ld
|
||||
STARTUP_SRC := startup_stm32f446xx.s
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F427_TARGETS)))
|
||||
DEVICE_FLAGS = -DSTM32F427_437xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f427.ld
|
||||
STARTUP_SRC = startup_stm32f427xx.s
|
||||
DEVICE_FLAGS := -DSTM32F427_437xx
|
||||
LD_SCRIPT := $(LINKER_DIR)/stm32_flash_F427.ld
|
||||
STARTUP_SRC := startup_stm32f427xx.s
|
||||
else
|
||||
$(error Unknown MCU for F4 target)
|
||||
$(error Unknown MCU for F4 target)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE)
|
||||
|
@ -169,6 +169,7 @@ MCU_COMMON_SRC = \
|
|||
drivers/adc_stm32f4xx.c \
|
||||
drivers/adc_stm32f4xx.c \
|
||||
drivers/bus_i2c_stm32f40x.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_stm32f4xx.c \
|
||||
drivers/system_stm32f4xx.c \
|
||||
|
|
|
@ -121,25 +121,30 @@ endif
|
|||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XI_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F765xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F765XI_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xI
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F765xI.ld
|
||||
STARTUP_SRC = startup_stm32f765xx.s
|
||||
TARGET_FLASH := 2048
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F745xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F765XG_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F765xx -DSTM32F765xG
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld
|
||||
STARTUP_SRC = startup_stm32f765xx.s
|
||||
TARGET_FLASH := 1024
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F745XG_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F745xx -DSTM32F745xG
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x5xG.ld
|
||||
STARTUP_SRC = startup_stm32f745xx.s
|
||||
TARGET_FLASH := 2048
|
||||
TARGET_FLASH := 1024
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F746xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f746.ld
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F746.ld
|
||||
STARTUP_SRC = startup_stm32f746xx.s
|
||||
TARGET_FLASH := 2048
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),$(F7X2RE_TARGETS)))
|
||||
DEVICE_FLAGS += -DSTM32F722xx
|
||||
ifndef LD_SCRIPT
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f722.ld
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_F7x2.ld
|
||||
endif
|
||||
STARTUP_SRC = startup_stm32f722xx.s
|
||||
TARGET_FLASH := 512
|
||||
|
|
|
@ -10,14 +10,16 @@ RELEASE_TARGETS += KAKUTEF4 KAKUTEF4V2 KAKUTEF7 KAKUTEF7MINI KAKUTEF7HDV
|
|||
|
||||
RELEASE_TARGETS += SPRACINGF3 SPRACINGF3EVO SPRACINGF3EVO_1SS SPRACINGF3MINI SPRACINGF4EVO SPRACINGF7DUAL
|
||||
|
||||
RELEASE_TARGETS += OMNIBUS AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
|
||||
RELEASE_TARGETS += AIRBOTF4 ASGARD32F4 ASGARD32F7 FIREWORKSV2 AIRBOTF7 OMNIBUSF7NANOV7
|
||||
RELEASE_TARGETS += OMNIBUSF4 OMNIBUSF4PRO OMNIBUSF4PRO_LEDSTRIPM5 DYSF4PRO DYSF4PROV2
|
||||
RELEASE_TARGETS += OMNIBUSF4V3 OMNIBUSF4V3_S6_SS OMNIBUSF4V3_S5S6_SS OMNIBUSF4V3_S5_S6_2SS
|
||||
RELEASE_TARGETS += OMNIBUSF7 OMNIBUSF7V2 OMNIBUSF7NXT YUPIF7
|
||||
|
||||
# MATEK targets
|
||||
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 += MATEKF765
|
||||
|
||||
RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL
|
||||
RELEASE_TARGETS += FOXEERF405 FOXEERF722DUAL FOXEERF722V2
|
||||
|
||||
RELEASE_TARGETS += SPEEDYBEEF4 FRSKYF3 FRSKYF4
|
||||
|
||||
|
@ -27,10 +29,11 @@ RELEASE_TARGETS += OMNIBUSF4V6
|
|||
|
||||
RELEASE_TARGETS += MAMBAF405 MAMBAF405US MAMBAF722
|
||||
|
||||
RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING
|
||||
# IFLIGHT targets
|
||||
RELEASE_TARGETS += IFLIGHTF7_TWING IFLIGHTF4_TWING IFLIGHTF4_SUCCEXD
|
||||
|
||||
RELEASE_TARGETS += AIKONF4
|
||||
|
||||
RELEASE_TARGETS += MATEKF765
|
||||
RELEASE_TARGETS += ZEEZF7 HGLRCF722
|
||||
|
||||
RELEASE_TARGETS += ZEEZF7
|
||||
RELEASE_TARGETS += FLYWOOF7DUAL FLYWOOF411
|
||||
|
|
|
@ -1,7 +1,25 @@
|
|||
COMMON_SRC = \
|
||||
common/log.c \
|
||||
common/printf.c \
|
||||
common/string_light.c \
|
||||
common/typeconversion.c \
|
||||
drivers/bus.c \
|
||||
drivers/bus_busdev_i2c.c \
|
||||
drivers/bus_busdev_spi.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
drivers/io.c \
|
||||
drivers/persistent.c \
|
||||
drivers/light_led.c \
|
||||
drivers/rcc.c \
|
||||
drivers/serial.c \
|
||||
drivers/system.c \
|
||||
drivers/time.c \
|
||||
fc/firmware_update_common.c \
|
||||
target/common_hardware.c
|
||||
|
||||
MAIN_SRC = \
|
||||
$(TARGET_DIR_SRC) \
|
||||
main.c \
|
||||
target/common_hardware.c \
|
||||
build/assert.c \
|
||||
build/build_config.c \
|
||||
build/debug.c \
|
||||
|
@ -13,19 +31,15 @@ COMMON_SRC = \
|
|||
common/encoding.c \
|
||||
common/filter.c \
|
||||
common/gps_conversion.c \
|
||||
common/log.c \
|
||||
common/logic_condition.c \
|
||||
common/global_functions.c \
|
||||
common/global_variables.c \
|
||||
common/maths.c \
|
||||
common/memory.c \
|
||||
common/olc.c \
|
||||
common/printf.c \
|
||||
common/streambuf.c \
|
||||
common/string_light.c \
|
||||
common/time.c \
|
||||
common/typeconversion.c \
|
||||
common/uvarint.c \
|
||||
programming/logic_condition.c \
|
||||
programming/global_variables.c \
|
||||
programming/programming_task.c \
|
||||
config/config_eeprom.c \
|
||||
config/config_streamer.c \
|
||||
config/feature.c \
|
||||
|
@ -33,21 +47,15 @@ COMMON_SRC = \
|
|||
config/general_settings.c \
|
||||
drivers/adc.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/bus.c \
|
||||
drivers/bus_busdev_i2c.c \
|
||||
drivers/bus_busdev_spi.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/display.c \
|
||||
drivers/display_canvas.c \
|
||||
drivers/display_font_metadata.c \
|
||||
drivers/display_widgets.c \
|
||||
drivers/exti.c \
|
||||
drivers/io.c \
|
||||
drivers/io_pca9685.c \
|
||||
drivers/irlock.c \
|
||||
drivers/light_led.c \
|
||||
drivers/io_pcf8574.c \
|
||||
drivers/io_port_expander.c \
|
||||
drivers/osd.c \
|
||||
drivers/persistent.c \
|
||||
drivers/resource.c \
|
||||
drivers/rx_nrf24l01.c \
|
||||
drivers/rx_spi.c \
|
||||
|
@ -58,14 +66,10 @@ COMMON_SRC = \
|
|||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pinio.c \
|
||||
drivers/rcc.c \
|
||||
drivers/rx_pwm.c \
|
||||
drivers/serial.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/sound_beeper.c \
|
||||
drivers/stack_check.c \
|
||||
drivers/system.c \
|
||||
drivers/time.c \
|
||||
drivers/timer.c \
|
||||
drivers/usb_msc.c \
|
||||
drivers/lights_io.c \
|
||||
|
@ -84,6 +88,7 @@ COMMON_SRC = \
|
|||
fc/fc_hardfaults.c \
|
||||
fc/fc_msp.c \
|
||||
fc/fc_msp_box.c \
|
||||
fc/firmware_update.c \
|
||||
fc/rc_smoothing.c \
|
||||
fc/rc_adjustments.c \
|
||||
fc/rc_controls.c \
|
||||
|
@ -104,6 +109,7 @@ COMMON_SRC = \
|
|||
flight/gyroanalyse.c \
|
||||
flight/rpm_filter.c \
|
||||
flight/dynamic_gyro_notch.c \
|
||||
flight/kalman.c \
|
||||
io/beeper.c \
|
||||
io/esc_serialshot.c \
|
||||
io/servo_sbus.c \
|
||||
|
@ -200,6 +206,7 @@ COMMON_SRC = \
|
|||
io/osd_common.c \
|
||||
io/osd_grid.c \
|
||||
io/osd_hud.c \
|
||||
io/smartport_master.c \
|
||||
navigation/navigation.c \
|
||||
navigation/navigation_fixedwing.c \
|
||||
navigation/navigation_fw_launch.c \
|
||||
|
@ -232,25 +239,31 @@ COMMON_SRC = \
|
|||
io/vtx_ffpv24g.c \
|
||||
io/vtx_control.c
|
||||
|
||||
BL_SRC = \
|
||||
bl_main.c
|
||||
|
||||
COMMON_DEVICE_SRC = \
|
||||
$(CMSIS_SRC) \
|
||||
$(DEVICE_STDPERIPH_SRC)
|
||||
|
||||
TARGET_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC)
|
||||
TARGET_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(MAIN_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC)
|
||||
TARGET_BL_SRC := $(STARTUP_SRC) $(COMMON_DEVICE_SRC) $(BL_SRC) $(COMMON_SRC) $(MCU_COMMON_SRC)
|
||||
|
||||
#excludes
|
||||
TARGET_SRC := $(filter-out $(MCU_EXCLUDES), $(TARGET_SRC))
|
||||
|
||||
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
|
||||
TARGET_SRC += \
|
||||
FLASH_SRC += \
|
||||
drivers/flash.c \
|
||||
drivers/flash_m25p16.c \
|
||||
io/flashfs.c \
|
||||
$(MSC_SRC)
|
||||
TARGET_SRC += $(FLASH_SRC)
|
||||
TARGET_BL_SRC += $(FLASH_SRC)
|
||||
endif
|
||||
|
||||
ifneq ($(filter SDCARD,$(FEATURES)),)
|
||||
TARGET_SRC += \
|
||||
SDCARD_SRC += \
|
||||
drivers/sdcard/sdcard.c \
|
||||
drivers/sdcard/sdcard_spi.c \
|
||||
drivers/sdcard/sdcard_sdio.c \
|
||||
|
@ -258,6 +271,8 @@ TARGET_SRC += \
|
|||
io/asyncfatfs/asyncfatfs.c \
|
||||
io/asyncfatfs/fat_standard.c \
|
||||
$(MSC_SRC)
|
||||
TARGET_SRC += $(SDCARD_SRC)
|
||||
TARGET_BL_SRC += $(SDCARD_SRC)
|
||||
endif
|
||||
|
||||
ifneq ($(filter VCP,$(FEATURES)),)
|
||||
|
|
|
@ -5,6 +5,10 @@ VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS)))
|
|||
VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS)
|
||||
VALID_TARGETS := $(sort $(VALID_TARGETS))
|
||||
|
||||
VALID_BL_TARGETS := $(addsuffix _bl,$(VALID_TARGETS))
|
||||
VALID_TARGETS_FOR_BL := $(addsuffix _for_bl,$(VALID_TARGETS))
|
||||
VALID_TARGETS_WITH_BL := $(addsuffix _with_bl,$(VALID_TARGETS))
|
||||
|
||||
CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) )
|
||||
TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) )
|
||||
STFLASH_TARGETS = $(addprefix st-flash_,$(VALID_TARGETS) )
|
||||
|
@ -20,7 +24,7 @@ endif
|
|||
-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)
|
||||
F7_TARGETS = $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F745XG_TARGETS) $(F765XG_TARGETS) $(F765XI_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?)
|
||||
|
@ -31,34 +35,37 @@ $(error Target '$(TARGET)' has not specified a valid STM group, must be one of F
|
|||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
TARGET_MCU := STM32F303
|
||||
TARGET_MCU := STM32F303
|
||||
TARGET_MCU_GROUP := STM32F3
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F405_TARGETS)))
|
||||
TARGET_MCU := STM32F405
|
||||
TARGET_MCU := STM32F405
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
|
||||
TARGET_MCU := STM32F411
|
||||
TARGET_MCU := STM32F411
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F427_TARGETS)))
|
||||
TARGET_MCU := STM32F427
|
||||
TARGET_MCU := STM32F427
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F446_TARGETS)))
|
||||
TARGET_MCU := STM32F446
|
||||
TARGET_MCU := STM32F446
|
||||
TARGET_MCU_GROUP := STM32F4
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X2RE_TARGETS)))
|
||||
TARGET_MCU := STM32F7X2RE
|
||||
TARGET_MCU := STM32F7X2RE
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XE_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XE
|
||||
TARGET_MCU := STM32F7X5XE
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XG_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XG
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F745XG_TARGETS)))
|
||||
TARGET_MCU := STM32F745XG
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X5XI_TARGETS)))
|
||||
TARGET_MCU := STM32F7X5XI
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F765XG_TARGETS)))
|
||||
TARGET_MCU := STM32F765XG
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F765XI_TARGETS)))
|
||||
TARGET_MCU := STM32F765XI
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else ifeq ($(TARGET),$(filter $(TARGET), $(F7X6XG_TARGETS)))
|
||||
TARGET_MCU := STM32F7X6XG
|
||||
TARGET_MCU := STM32F7X6XG
|
||||
TARGET_MCU_GROUP := STM32F7
|
||||
else
|
||||
$(error Unknown target MCU specified.)
|
||||
|
@ -66,12 +73,12 @@ 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_3_TARGETS := 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 KAKUTEF7HDV ZEEZF7
|
||||
GROUP_8_TARGETS := MATEKF765 MATEKF722PX KAKUTEF7HDV ZEEZF7 FOXEERF722V2
|
||||
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
|
||||
|
|
489
src/bl/bl_main.c
Normal file
489
src/bl/bl_main.c
Normal file
|
@ -0,0 +1,489 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
/*#include "common/log.h"*/
|
||||
#include "common/maths.h"
|
||||
/*#include "common/printf.h"*/
|
||||
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/persistent.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/sdcard/sdcard.h"
|
||||
#include "drivers/system.h"
|
||||
#include "drivers/time.h"
|
||||
|
||||
#include "fc/firmware_update_common.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
|
||||
|
||||
#if !(defined(STM32F405xx) || defined(STM32F722xx) || defined(STM32F765XG) || defined(STM32F7X5XI))
|
||||
#error Unsupported MCU
|
||||
#endif
|
||||
|
||||
#if !(defined(USE_FLASHFS) || defined(USE_SDCARD))
|
||||
#error No storage backend available
|
||||
#endif
|
||||
|
||||
|
||||
typedef struct {
|
||||
uint16_t size;
|
||||
uint8_t count;
|
||||
} flashSectorDef_t;
|
||||
|
||||
#if defined(STM32F405xx)
|
||||
#define SECTOR_COUNT 12
|
||||
flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 7 }, { 0, 0 } };
|
||||
|
||||
#elif defined(STM32F722xx)
|
||||
#define SECTOR_COUNT 8
|
||||
flashSectorDef_t flashSectors[] = { { 16, 4 }, { 64, 1 }, { 128, 3 }, { 0, 0 } };
|
||||
|
||||
#elif defined(STM32F765XG)
|
||||
#define SECTOR_COUNT 8
|
||||
flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 3 }, { 0, 0 } };
|
||||
|
||||
#elif defined(STM32F7X5XI)
|
||||
#define SECTOR_COUNT 8
|
||||
flashSectorDef_t flashSectors[] = { { 32, 4 }, { 128, 1 }, { 256, 7 }, { 0, 0 } };
|
||||
|
||||
#endif
|
||||
|
||||
#if defined(STM32F4)
|
||||
#define flashLock() FLASH_Lock()
|
||||
#define flashUnlock() FLASH_Unlock()
|
||||
#elif defined(STM32F7)
|
||||
#define flashLock() HAL_FLASH_Lock()
|
||||
#define flashUnlock() HAL_FLASH_Unlock()
|
||||
#endif
|
||||
|
||||
static bool dataBackEndInitialized = false;
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
static afatfsFilePtr_t flashDataFile = NULL;
|
||||
|
||||
static void flashDataFileOpenCallback(afatfsFilePtr_t file)
|
||||
{
|
||||
flashDataFile = file;
|
||||
}
|
||||
#endif
|
||||
|
||||
static void init(void)
|
||||
{
|
||||
#ifdef USE_HAL_DRIVER
|
||||
HAL_Init();
|
||||
#endif
|
||||
|
||||
/*printfSupportInit();*/
|
||||
|
||||
systemInit();
|
||||
|
||||
__enable_irq();
|
||||
|
||||
// initialize IO (needed for all IO operations)
|
||||
IOInitGlobal();
|
||||
|
||||
ledInit(false);
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
for(int x = 0; x < 10; ++x) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
delay(200);
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
static bool dataBackendInit(void)
|
||||
{
|
||||
if (dataBackEndInitialized) return true;
|
||||
|
||||
busInit();
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
sdcardInsertionDetectInit();
|
||||
sdcard_init();
|
||||
afatfs_init();
|
||||
|
||||
afatfsError_e sdError = afatfs_getLastError();
|
||||
while ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) && ((sdError = afatfs_getLastError()) == AFATFS_ERROR_NONE)) {
|
||||
afatfs_poll();
|
||||
}
|
||||
|
||||
if (sdError != AFATFS_ERROR_NONE) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS) && defined(USE_FLASH_M25P16)
|
||||
if (!flashInit()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
dataBackEndInitialized = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
typedef void resetHandler_t(void);
|
||||
|
||||
typedef struct isrVector_s {
|
||||
uint32_t stackEnd;
|
||||
resetHandler_t *resetHandler;
|
||||
} isrVector_t;
|
||||
|
||||
static void do_jump(uint32_t address)
|
||||
{
|
||||
#ifdef STM32F7
|
||||
__DSB();
|
||||
__DMB();
|
||||
__ISB();
|
||||
#endif
|
||||
|
||||
volatile isrVector_t *bootloaderVector = (isrVector_t *)address;
|
||||
__set_MSP(bootloaderVector->stackEnd);
|
||||
bootloaderVector->resetHandler();
|
||||
}
|
||||
|
||||
void bootloader_jump_to_app(void)
|
||||
{
|
||||
FLASH->ACR &= (~FLASH_ACR_PRFTEN);
|
||||
|
||||
#if defined(STM32F4)
|
||||
RCC_APB1PeriphResetCmd(~0, DISABLE);
|
||||
RCC_APB2PeriphResetCmd(~0, DISABLE);
|
||||
#elif defined(STM32F7)
|
||||
RCC->APB1ENR = 0;
|
||||
RCC->APB1LPENR = 0;
|
||||
RCC->APB2ENR = 0;
|
||||
RCC->APB2LPENR = 0;
|
||||
#endif
|
||||
|
||||
__disable_irq();
|
||||
|
||||
do_jump(FIRMWARE_START_ADDRESS);
|
||||
}
|
||||
|
||||
// find sector specified address is in (assume than the config section doesn't span more than 1 sector)
|
||||
// returns -1 if not found
|
||||
int8_t mcuFlashAddressSectorIndex(uint32_t address)
|
||||
{
|
||||
uint32_t sectorStartAddress = FLASH_START_ADDRESS;
|
||||
uint8_t sector = 0;
|
||||
flashSectorDef_t *sectorDef = flashSectors;
|
||||
|
||||
do {
|
||||
for (unsigned j = 0; j < sectorDef->count; ++j) {
|
||||
uint32_t sectorEndAddress = sectorStartAddress + sectorDef->size * 1024;
|
||||
/*if ((CONFIG_START_ADDRESS >= sectorStartAddress) && (CONFIG_START_ADDRESS < sectorEndAddress) && (CONFIG_END_ADDRESS <= sectorEndAddress)) {*/
|
||||
if ((address >= sectorStartAddress) && (address < sectorEndAddress)) {
|
||||
return sector;
|
||||
}
|
||||
sectorStartAddress = sectorEndAddress;
|
||||
sector += 1;
|
||||
}
|
||||
sectorDef += 1;
|
||||
} while (sectorDef->count);
|
||||
|
||||
return -1;
|
||||
}
|
||||
|
||||
uint32_t mcuFlashSectorID(uint8_t sectorIndex)
|
||||
{
|
||||
#if defined(STM32F4)
|
||||
if (sectorIndex < 12) {
|
||||
return sectorIndex * 8;
|
||||
} else {
|
||||
return 0x80 + (sectorIndex - 12) * 8;
|
||||
}
|
||||
#elif defined(STM32F7)
|
||||
return sectorIndex;
|
||||
#endif
|
||||
}
|
||||
|
||||
bool mcuFlashSectorErase(uint8_t sectorIndex)
|
||||
{
|
||||
#if defined(STM32F4)
|
||||
return (FLASH_EraseSector(mcuFlashSectorID(sectorIndex), VoltageRange_3) == FLASH_COMPLETE);
|
||||
#elif defined(STM32F7)
|
||||
FLASH_EraseInitTypeDef EraseInitStruct = {
|
||||
.TypeErase = FLASH_TYPEERASE_SECTORS,
|
||||
.VoltageRange = FLASH_VOLTAGE_RANGE_3, // 2.7-3.6V
|
||||
.NbSectors = 1
|
||||
};
|
||||
EraseInitStruct.Sector = mcuFlashSectorID(sectorIndex);
|
||||
uint32_t SECTORError;
|
||||
const HAL_StatusTypeDef status = HAL_FLASHEx_Erase(&EraseInitStruct, &SECTORError);
|
||||
return (status == HAL_OK);
|
||||
#else
|
||||
#error Unsupported MCU
|
||||
#endif
|
||||
}
|
||||
|
||||
bool mcuFirmwareFlashErase(bool includeConfig)
|
||||
{
|
||||
int8_t firmwareSectorIndex = mcuFlashAddressSectorIndex(FIRMWARE_START_ADDRESS);
|
||||
int8_t configSectorIndex = mcuFlashAddressSectorIndex(CONFIG_START_ADDRESS);
|
||||
|
||||
if ((firmwareSectorIndex == -1) || (configSectorIndex == -1)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_ON;
|
||||
for (unsigned i = firmwareSectorIndex; i < SECTOR_COUNT; ++i) {
|
||||
if (includeConfig || (!includeConfig && (i != (uint8_t)configSectorIndex))) {
|
||||
if (!mcuFlashSectorErase(i)) {
|
||||
LED1_OFF;
|
||||
return false;
|
||||
}
|
||||
LED0_TOGGLE;
|
||||
}
|
||||
}
|
||||
|
||||
LED1_OFF;
|
||||
return true;
|
||||
}
|
||||
|
||||
bool mcuFlashWriteWord(uint32_t address, uint32_t data)
|
||||
{
|
||||
#if defined(STM32F4)
|
||||
const FLASH_Status status = FLASH_ProgramWord(address, data);
|
||||
return (status == FLASH_COMPLETE);
|
||||
#elif defined(STM32F7)
|
||||
const HAL_StatusTypeDef status = HAL_FLASH_Program(FLASH_TYPEPROGRAM_WORD, address, (uint64_t)data);
|
||||
return (status == HAL_OK);
|
||||
#else
|
||||
#error Unsupported MCU
|
||||
#endif
|
||||
}
|
||||
|
||||
typedef enum {
|
||||
FLASH_OPERATION_UPDATE,
|
||||
FLASH_OPERATION_ROLLBACK
|
||||
} flashOperation_e;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
bool afatfs_fseekWorkAround(afatfsFilePtr_t file, uint32_t forward)
|
||||
{
|
||||
uint8_t buffer[256];
|
||||
while (forward > 0) {
|
||||
uint32_t bytesRead = afatfs_freadSync(file, buffer, MIN(forward, (uint16_t)256));
|
||||
if (bytesRead < 256) {
|
||||
return false;
|
||||
}
|
||||
forward -= bytesRead;
|
||||
}
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
bool flash(flashOperation_e flashOperation)
|
||||
{
|
||||
if (!dataBackendInit()) {
|
||||
return false;
|
||||
}
|
||||
|
||||
uint32_t buffer;
|
||||
uint32_t flashDstAddress = FIRMWARE_START_ADDRESS + sizeof(buffer); // Write the first bytes last so that we can check that the firmware has been written fully
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
const char * const flashDataFileName = (flashOperation == FLASH_OPERATION_UPDATE ? FIRMWARE_UPDATE_FIRMWARE_FILENAME : FIRMWARE_UPDATE_BACKUP_FILENAME);
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY)
|
||||
|| !afatfs_fopen(flashDataFileName, "r", flashDataFileOpenCallback)
|
||||
|| (afatfs_fileSize(flashDataFile) > AVAILABLE_FIRMWARE_SPACE)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartitionType_e srcFlashPartitionType = (flashOperation == FLASH_OPERATION_UPDATE ? FLASH_PARTITION_TYPE_UPDATE_FIRMWARE : FLASH_PARTITION_TYPE_FULL_BACKUP);
|
||||
flashPartition_t *flashDataPartition = flashPartitionFindByType(srcFlashPartitionType);
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
uint32_t flashDataPartitionSize = (flashDataPartition->endSector - flashDataPartition->startSector + 1) * (flashGeometry->sectorSize * flashGeometry->pageSize);
|
||||
firmwareUpdateMetadata_t updateMetadata;
|
||||
|
||||
if (!flashDataPartition || !firmwareUpdateMetadataRead(&updateMetadata)
|
||||
|| (updateMetadata.firmwareSize > flashDataPartitionSize)
|
||||
|| (updateMetadata.firmwareSize > AVAILABLE_FIRMWARE_SPACE)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
flashUnlock();
|
||||
bool flashSucceeded = false;
|
||||
|
||||
if (!mcuFirmwareFlashErase(flashOperation != FLASH_OPERATION_UPDATE)) goto flashFailed;
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
uint32_t counter = 0;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
|
||||
if (afatfs_fseekSync(flashDataFile, sizeof(buffer), AFATFS_SEEK_SET) == AFATFS_OPERATION_FAILURE) {
|
||||
goto flashFailed;
|
||||
}
|
||||
|
||||
while (!afatfs_feof(flashDataFile)) {
|
||||
|
||||
if ((flashOperation == FLASH_OPERATION_UPDATE) && (flashDstAddress == CONFIG_START_ADDRESS)) {
|
||||
// skip config region
|
||||
const uint32_t configSize = CONFIG_END_ADDRESS - CONFIG_START_ADDRESS;
|
||||
/*if (afatfs_fseekSync(flashDataFile, configSize, AFATFS_SEEK_CUR) == AFATFS_OPERATION_FAILURE) {*/
|
||||
if (!afatfs_fseekWorkAround(flashDataFile, configSize)) { // workaround fseek bug, should be ^^^^^^^^^
|
||||
goto flashFailed;
|
||||
}
|
||||
flashDstAddress += configSize;
|
||||
}
|
||||
|
||||
afatfs_freadSync(flashDataFile, (uint8_t *)&buffer, sizeof(buffer));
|
||||
|
||||
if (!mcuFlashWriteWord(flashDstAddress, buffer)) {
|
||||
goto flashFailed;
|
||||
}
|
||||
|
||||
flashDstAddress += sizeof(buffer);
|
||||
|
||||
if (++counter % (10*1024/4) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
if ((afatfs_fseekSync(flashDataFile, 0, AFATFS_SEEK_SET) == AFATFS_OPERATION_FAILURE)
|
||||
|| (afatfs_freadSync(flashDataFile, (uint8_t *)&buffer, sizeof(buffer)) != sizeof(buffer))) {
|
||||
goto flashFailed;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
const uint32_t flashSrcStartAddress = flashDataPartition->startSector * flashGeometry->sectorSize;
|
||||
uint32_t flashSrcAddress = flashSrcStartAddress + sizeof(buffer);
|
||||
const uint32_t flashDstEndAddress = (flashOperation == FLASH_OPERATION_UPDATE ? FIRMWARE_START_ADDRESS + updateMetadata.firmwareSize : FLASH_END);
|
||||
|
||||
while (flashDstAddress < flashDstEndAddress) {
|
||||
|
||||
if ((flashOperation == FLASH_OPERATION_UPDATE) && (flashDstAddress == CONFIG_START_ADDRESS)) {
|
||||
// skip config region
|
||||
const uint32_t configSize = CONFIG_END_ADDRESS - CONFIG_START_ADDRESS;
|
||||
flashSrcAddress += configSize;
|
||||
flashDstAddress += configSize;
|
||||
|
||||
if (flashDstAddress >= flashDstEndAddress) {
|
||||
goto flashFailed;
|
||||
}
|
||||
}
|
||||
|
||||
flashReadBytes(flashSrcAddress, (uint8_t*)&buffer, sizeof(buffer));
|
||||
if (!mcuFlashWriteWord(flashDstAddress, buffer)) {
|
||||
goto flashFailed;
|
||||
}
|
||||
|
||||
flashSrcAddress += sizeof(buffer);
|
||||
flashDstAddress += sizeof(buffer);
|
||||
|
||||
if (++counter % (10*1024/4) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
flashReadBytes(flashSrcStartAddress, (uint8_t*)&buffer, sizeof(buffer));
|
||||
|
||||
#endif
|
||||
|
||||
if (!mcuFlashWriteWord(FIRMWARE_START_ADDRESS, buffer)) {
|
||||
goto flashFailed;
|
||||
}
|
||||
|
||||
flashSucceeded = true;
|
||||
|
||||
flashFailed:
|
||||
|
||||
flashLock();
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
return flashSucceeded;
|
||||
}
|
||||
|
||||
#if defined(USE_FLASHFS)
|
||||
bool dataflashChipEraseUpdatePartition(void)
|
||||
{
|
||||
flashPartition_t *flashDataPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE);
|
||||
if (!flashDataPartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
|
||||
LED0_OFF;
|
||||
|
||||
for (unsigned i = flashDataPartition->startSector; i <= flashDataPartition->endSector; i++) {
|
||||
uint32_t flashAddress = flashGeometry->sectorSize * i;
|
||||
flashEraseSector(flashAddress);
|
||||
flashWaitForReady(1000);
|
||||
LED0_TOGGLE;
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
|
||||
return true;
|
||||
}
|
||||
#endif
|
||||
|
||||
int main(void)
|
||||
{
|
||||
init();
|
||||
|
||||
uint32_t bootloaderRequest = persistentObjectRead(PERSISTENT_OBJECT_RESET_REASON);
|
||||
if ((bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_UPDATE) || (bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_ROLLBACK)) {
|
||||
flashOperation_e flashOperation = (bootloaderRequest == RESET_BOOTLOADER_FIRMWARE_UPDATE ? FLASH_OPERATION_UPDATE : FLASH_OPERATION_ROLLBACK);
|
||||
const bool success = flash(flashOperation);
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, success ? RESET_BOOTLOADER_FIRMWARE_UPDATE_SUCCESS : RESET_BOOTLOADER_FIRMWARE_UPDATE_FAILED);
|
||||
} else if (*(uint32_t*)FIRMWARE_START_ADDRESS == 0xFFFFFFFF) {
|
||||
if (!flash(FLASH_OPERATION_ROLLBACK)) {
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
while (true) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
delay(2000);
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
bootloader_jump_to_app();
|
||||
|
||||
return 0;
|
||||
}
|
276
src/main/CMakeLists.txt
Normal file
276
src/main/CMakeLists.txt
Normal file
|
@ -0,0 +1,276 @@
|
|||
set(COMMON_SRC
|
||||
main.c
|
||||
|
||||
target/common_hardware.c
|
||||
|
||||
build/assert.c
|
||||
build/build_config.c
|
||||
build/debug.c
|
||||
build/version.c
|
||||
|
||||
common/bitarray.c
|
||||
common/calibration.c
|
||||
common/colorconversion.c
|
||||
common/crc.c
|
||||
common/encoding.c
|
||||
common/filter.c
|
||||
common/gps_conversion.c
|
||||
common/log.c
|
||||
common/logic_condition.c
|
||||
common/global_functions.c
|
||||
common/global_variables.c
|
||||
common/maths.c
|
||||
common/memory.c
|
||||
common/olc.c
|
||||
common/printf.c
|
||||
common/streambuf.c
|
||||
common/string_light.c
|
||||
common/time.c
|
||||
common/typeconversion.c
|
||||
common/uvarint.c
|
||||
|
||||
config/config_eeprom.c
|
||||
config/config_streamer.c
|
||||
config/feature.c
|
||||
config/parameter_group.c
|
||||
config/general_settings.c
|
||||
|
||||
drivers/adc.c
|
||||
drivers/buf_writer.c
|
||||
drivers/bus.c
|
||||
drivers/bus_busdev_i2c.c
|
||||
drivers/bus_busdev_spi.c
|
||||
drivers/bus_i2c_soft.c
|
||||
drivers/bus_spi.c
|
||||
drivers/display.c
|
||||
drivers/display_canvas.c
|
||||
drivers/display_font_metadata.c
|
||||
drivers/exti.c
|
||||
drivers/io.c
|
||||
drivers/io_pca9685.c
|
||||
drivers/irlock.c
|
||||
drivers/light_led.c
|
||||
drivers/osd.c
|
||||
drivers/persistent.c
|
||||
drivers/resource.c
|
||||
drivers/rx_nrf24l01.c
|
||||
drivers/rx_spi.c
|
||||
drivers/rx_xn297.c
|
||||
drivers/pitotmeter_adc.c
|
||||
drivers/pitotmeter_virtual.c
|
||||
drivers/pwm_esc_detect.c
|
||||
drivers/pwm_mapping.c
|
||||
drivers/pwm_output.c
|
||||
drivers/pinio.c
|
||||
drivers/rcc.c
|
||||
drivers/rx_pwm.c
|
||||
drivers/serial.c
|
||||
drivers/serial_uart.c
|
||||
drivers/sound_beeper.c
|
||||
drivers/stack_check.c
|
||||
drivers/system.c
|
||||
drivers/time.c
|
||||
drivers/timer.c
|
||||
drivers/usb_msc.c
|
||||
drivers/lights_io.c
|
||||
drivers/1-wire.c
|
||||
drivers/1-wire/ds_crc.c
|
||||
drivers/1-wire/ds2482.c
|
||||
drivers/temperature/ds18b20.c
|
||||
drivers/temperature/lm75.c
|
||||
drivers/pitotmeter_ms4525.c
|
||||
|
||||
fc/cli.c
|
||||
fc/config.c
|
||||
fc/controlrate_profile.c
|
||||
fc/fc_core.c
|
||||
fc/fc_init.c
|
||||
fc/fc_tasks.c
|
||||
fc/fc_hardfaults.c
|
||||
fc/fc_msp.c
|
||||
fc/fc_msp_box.c
|
||||
fc/rc_smoothing.c
|
||||
fc/rc_adjustments.c
|
||||
fc/rc_controls.c
|
||||
fc/rc_curves.c
|
||||
fc/rc_modes.c
|
||||
fc/runtime_config.c
|
||||
fc/settings.c
|
||||
fc/stats.c
|
||||
|
||||
flight/failsafe.c
|
||||
flight/hil.c
|
||||
flight/imu.c
|
||||
flight/mixer.c
|
||||
flight/pid.c
|
||||
flight/pid_autotune.c
|
||||
flight/rth_estimator.c
|
||||
flight/servos.c
|
||||
flight/wind_estimator.c
|
||||
flight/gyroanalyse.c
|
||||
flight/rpm_filter.c
|
||||
flight/dynamic_gyro_notch.c
|
||||
|
||||
io/beeper.c
|
||||
io/esc_serialshot.c
|
||||
io/servo_sbus.c
|
||||
io/frsky_osd.c
|
||||
io/osd_dji_hd.c
|
||||
io/lights.c
|
||||
io/piniobox.c
|
||||
io/pwmdriver_i2c.c
|
||||
io/serial.c
|
||||
io/serial_4way.c
|
||||
io/serial_4way_avrootloader.c
|
||||
io/serial_4way_stk500v2.c
|
||||
io/statusindicator.c
|
||||
io/rcdevice.c
|
||||
io/rcdevice_cam.c
|
||||
|
||||
msp/msp_serial.c
|
||||
|
||||
rx/crsf.c
|
||||
rx/eleres.c
|
||||
rx/fport.c
|
||||
rx/ibus.c
|
||||
rx/jetiexbus.c
|
||||
rx/msp.c
|
||||
rx/msp_override.c
|
||||
rx/nrf24_cx10.c
|
||||
rx/nrf24_inav.c
|
||||
rx/nrf24_h8_3d.c
|
||||
rx/nrf24_syma.c
|
||||
rx/nrf24_v202.c
|
||||
rx/pwm.c
|
||||
rx/frsky_crc.c
|
||||
rx/rx.c
|
||||
rx/rx_spi.c
|
||||
rx/sbus.c
|
||||
rx/sbus_channels.c
|
||||
rx/spektrum.c
|
||||
rx/sumd.c
|
||||
rx/sumh.c
|
||||
rx/uib_rx.c
|
||||
rx/xbus.c
|
||||
|
||||
scheduler/scheduler.c
|
||||
|
||||
sensors/acceleration.c
|
||||
sensors/battery.c
|
||||
sensors/boardalignment.c
|
||||
sensors/compass.c
|
||||
sensors/diagnostics.c
|
||||
sensors/gyro.c
|
||||
sensors/initialisation.c
|
||||
sensors/esc_sensor.c
|
||||
sensors/irlock.c
|
||||
sensors/temperature.c
|
||||
|
||||
uav_interconnect/uav_interconnect_bus.c
|
||||
uav_interconnect/uav_interconnect_rangefinder.c
|
||||
|
||||
blackbox/blackbox.c
|
||||
blackbox/blackbox_encoding.c
|
||||
blackbox/blackbox_io.c
|
||||
|
||||
cms/cms.c
|
||||
cms/cms_menu_battery.c
|
||||
cms/cms_menu_blackbox.c
|
||||
cms/cms_menu_builtin.c
|
||||
cms/cms_menu_imu.c
|
||||
cms/cms_menu_ledstrip.c
|
||||
cms/cms_menu_misc.c
|
||||
cms/cms_menu_mixer_servo.c
|
||||
cms/cms_menu_navigation.c
|
||||
cms/cms_menu_osd.c
|
||||
cms/cms_menu_saveexit.c
|
||||
cms/cms_menu_vtx.c
|
||||
|
||||
drivers/accgyro/accgyro_mpu6000.c
|
||||
drivers/accgyro/accgyro_mpu6500.c
|
||||
drivers/barometer/barometer_bmp085.c
|
||||
drivers/barometer/barometer_bmp280.c
|
||||
drivers/barometer/barometer_ms56xx.c
|
||||
drivers/compass/compass_ak8975.c
|
||||
drivers/compass/compass_hmc5883l.c
|
||||
drivers/compass/compass_mag3110.c
|
||||
drivers/compass/compass_qmc5883l.c
|
||||
drivers/compass/compass_ist8308.c
|
||||
drivers/compass/compass_ist8310.c
|
||||
drivers/compass/compass_lis3mdl.c
|
||||
drivers/display_ug2864hsweg01.c
|
||||
drivers/flash.c
|
||||
drivers/flash_m25p16.c
|
||||
drivers/light_ws2811strip.c
|
||||
drivers/max7456.c
|
||||
drivers/rangefinder/rangefinder_hcsr04.c
|
||||
drivers/rangefinder/rangefinder_hcsr04_i2c.c
|
||||
drivers/rangefinder/rangefinder_srf10.c
|
||||
drivers/rangefinder/rangefinder_vl53l0x.c
|
||||
drivers/rangefinder/rangefinder_virtual.c
|
||||
drivers/opflow/opflow_fake.c
|
||||
drivers/opflow/opflow_virtual.c
|
||||
drivers/pitotmeter_adc.c
|
||||
drivers/vtx_common.c
|
||||
|
||||
io/rangefinder_msp.c
|
||||
io/rangefinder_benewake.c
|
||||
io/opflow_cxof.c
|
||||
io/opflow_msp.c
|
||||
io/dashboard.c
|
||||
io/displayport_frsky_osd.c
|
||||
io/displayport_max7456.c
|
||||
io/displayport_msp.c
|
||||
io/displayport_oled.c
|
||||
io/displayport_hott.c
|
||||
io/flashfs.c
|
||||
io/gps.c
|
||||
io/gps_ublox.c
|
||||
io/gps_nmea.c
|
||||
io/gps_naza.c
|
||||
io/ledstrip.c
|
||||
io/osd.c
|
||||
io/osd_canvas.c
|
||||
io/osd_common.c
|
||||
io/osd_grid.c
|
||||
io/osd_hud.c
|
||||
|
||||
navigation/navigation.c
|
||||
navigation/navigation_fixedwing.c
|
||||
navigation/navigation_fw_launch.c
|
||||
navigation/navigation_geo.c
|
||||
navigation/navigation_multicopter.c
|
||||
navigation/navigation_pos_estimator.c
|
||||
navigation/navigation_pos_estimator_agl.c
|
||||
navigation/navigation_pos_estimator_flow.c
|
||||
navigation/navigation_rover_boat.c
|
||||
|
||||
sensors/barometer.c
|
||||
sensors/pitotmeter.c
|
||||
sensors/rangefinder.c
|
||||
sensors/opflow.c
|
||||
|
||||
telemetry/crsf.c
|
||||
telemetry/frsky.c
|
||||
telemetry/frsky_d.c
|
||||
telemetry/hott.c
|
||||
telemetry/ibus_shared.c
|
||||
telemetry/ibus.c
|
||||
telemetry/ltm.c
|
||||
telemetry/mavlink.c
|
||||
telemetry/msp_shared.c
|
||||
telemetry/smartport.c
|
||||
telemetry/sim.c
|
||||
telemetry/telemetry.c
|
||||
|
||||
io/vtx.c
|
||||
io/vtx_string.c
|
||||
io/vtx_smartaudio.c
|
||||
io/vtx_tramp.c
|
||||
io/vtx_ffpv24g.c
|
||||
io/vtx_control.c
|
||||
)
|
||||
|
||||
main_sources(COMMON_SRC)
|
||||
|
||||
add_subdirectory(target)
|
|
@ -1717,8 +1717,6 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf_type", "%d", pidProfile()->dterm_lpf_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_hz", "%d", pidProfile()->dterm_lpf2_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_lpf2_type", "%d", pidProfile()->dterm_lpf2_type);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_hz", "%d", pidProfile()->dterm_soft_notch_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_notch_cutoff", "%d", pidProfile()->dterm_soft_notch_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE("deadband", "%d", rcControlsConfig()->deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("yaw_deadband", "%d", rcControlsConfig()->yaw_deadband);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_lpf", "%d", gyroConfig()->gyro_lpf);
|
||||
|
@ -1728,10 +1726,10 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchRange", "%d", gyroConfig()->dynamicGyroNotchRange);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchQ", "%d", gyroConfig()->dynamicGyroNotchQ);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dynamicGyroNotchMinHz", "%d", gyroConfig()->dynamicGyroNotchMinHz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_soft_notch_hz_1,
|
||||
gyroConfig()->gyro_soft_notch_hz_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_soft_notch_cutoff_1,
|
||||
gyroConfig()->gyro_soft_notch_cutoff_2);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_hz", "%d,%d", gyroConfig()->gyro_notch_hz,
|
||||
0);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_notch_cutoff", "%d,%d", gyroConfig()->gyro_notch_cutoff,
|
||||
1);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_lpf_hz", "%d", accelerometerConfig()->acc_lpf_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_hardware", "%d", accelerometerConfig()->acc_hardware);
|
||||
BLACKBOX_PRINT_HEADER_LINE("baro_hardware", "%d", barometerConfig()->baro_hardware);
|
||||
|
@ -1747,7 +1745,6 @@ static bool blackboxWriteSysinfo(void)
|
|||
BLACKBOX_PRINT_HEADER_LINE("acc_notch_hz", "%d", accelerometerConfig()->acc_notch_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("acc_notch_cutoff", "%d", accelerometerConfig()->acc_notch_cutoff);
|
||||
BLACKBOX_PRINT_HEADER_LINE("gyro_stage2_lowpass_hz", "%d", gyroConfig()->gyro_stage2_lowpass_hz);
|
||||
BLACKBOX_PRINT_HEADER_LINE("dterm_setpoint_weight", "%f", (double)pidProfile()->dterm_setpoint_weight);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimit", "%d", pidProfile()->pidSumLimit);
|
||||
BLACKBOX_PRINT_HEADER_LINE("pidSumLimitYaw", "%d", pidProfile()->pidSumLimitYaw);
|
||||
BLACKBOX_PRINT_HEADER_LINE("axisAccelerationLimitYaw", "%d", pidProfile()->axisAccelerationLimitYaw);
|
||||
|
|
|
@ -71,5 +71,11 @@ typedef enum {
|
|||
DEBUG_DYNAMIC_FILTER,
|
||||
DEBUG_DYNAMIC_FILTER_FREQUENCY,
|
||||
DEBUG_IRLOCK,
|
||||
DEBUG_CD,
|
||||
DEBUG_KALMAN,
|
||||
DEBUG_SPM_CELLS, // Smartport master FLVSS
|
||||
DEBUG_SPM_VS600, // Smartport master VS600 VTX
|
||||
DEBUG_SPM_VARIO, // Smartport master variometer
|
||||
DEBUG_PCF8574,
|
||||
DEBUG_COUNT
|
||||
} debugType_e;
|
||||
|
|
|
@ -16,8 +16,8 @@
|
|||
*/
|
||||
|
||||
#define FC_VERSION_MAJOR 2 // increment when a major release is made (big new feature, etc)
|
||||
#define FC_VERSION_MINOR 5 // increment when a minor release is made (small new feature, change etc)
|
||||
#define FC_VERSION_PATCH_LEVEL 1 // increment when a bug is fixed
|
||||
#define FC_VERSION_MINOR 6 // 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
|
||||
#define STR(x) STR_HELPER(x)
|
||||
|
|
|
@ -1314,6 +1314,7 @@ void cmsUpdate(uint32_t currentTimeUs)
|
|||
rcDelayMs = BUTTON_PAUSE; // Tends to overshoot if BUTTON_TIME
|
||||
}
|
||||
} else {
|
||||
displayBeginTransaction(pCurrentDisplay, DISPLAY_TRANSACTION_OPT_RESET_DRAWING);
|
||||
|
||||
// Check if we're yielding and its's time to stop it
|
||||
if (cmsYieldUntil > 0 && currentTimeMs > cmsYieldUntil) {
|
||||
|
@ -1339,6 +1340,7 @@ void cmsUpdate(uint32_t currentTimeUs)
|
|||
displayHeartbeat(pCurrentDisplay);
|
||||
lastCmsHeartBeatMs = currentTimeMs;
|
||||
}
|
||||
displayCommitTransaction(pCurrentDisplay);
|
||||
}
|
||||
|
||||
// Some key (command), notably flash erase, takes too long to use the
|
||||
|
|
|
@ -202,7 +202,7 @@ static const OSD_Entry cmsx_menuServoMixerEntries[] =
|
|||
OSD_UINT8_CALLBACK_ENTRY("SERVO MIX", cmsx_menuServoMixerIndexOnChange, (&(const OSD_UINT8_t){ &tmpcurrentServoMixerIndex, 1, MAX_SERVO_RULES, 1})),
|
||||
OSD_UINT8_DYN_ENTRY("SERVO", (&(const OSD_UINT8_t){ &tmpServoMixer.targetChannel, 0, MAX_SUPPORTED_SERVOS, 1})),
|
||||
OSD_TAB_DYN_ENTRY("INPUT", (&(const OSD_TAB_t){ &tmpServoMixer.inputSource, SERVO_MIXER_INPUT_CMS_NAMES_COUNT - 1, servoMixerInputCmsNames})),
|
||||
OSD_INT16_DYN_ENTRY("WEIGHT", (&(const OSD_INT16_t){&tmpServoMixer.rate, 0, 1000, 1})),
|
||||
OSD_INT16_DYN_ENTRY("WEIGHT", (&(const OSD_INT16_t){&tmpServoMixer.rate, -1000, 1000, 1})),
|
||||
OSD_UINT8_DYN_ENTRY("SPEED", (&(const OSD_UINT8_t){&tmpServoMixer.speed, 0, 255, 1})),
|
||||
OSD_BACK_AND_END_ENTRY
|
||||
};
|
||||
|
|
|
@ -75,7 +75,7 @@ static long cmsx_osdElementOnChange(displayPort_t *displayPort, const void *ptr)
|
|||
{
|
||||
UNUSED(ptr);
|
||||
|
||||
uint16_t *pos = &osdConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem];
|
||||
uint16_t *pos = &osdLayoutsConfigMutable()->item_pos[osdCurrentLayout][osdCurrentItem];
|
||||
*pos = OSD_POS(osdCurrentElementColumn, osdCurrentElementRow);
|
||||
if (osdCurrentElementVisible) {
|
||||
*pos |= OSD_VISIBLE_FLAG;
|
||||
|
@ -125,7 +125,7 @@ static CMS_Menu cmsx_menuOsdElementActions = {
|
|||
static long osdElemActionsOnEnter(const OSD_Entry *from)
|
||||
{
|
||||
osdCurrentItem = from->itemId;
|
||||
uint16_t pos = osdConfig()->item_pos[osdCurrentLayout][osdCurrentItem];
|
||||
uint16_t pos = osdLayoutsConfig()->item_pos[osdCurrentLayout][osdCurrentItem];
|
||||
osdCurrentElementColumn = OSD_X(pos);
|
||||
osdCurrentElementRow = OSD_Y(pos);
|
||||
osdCurrentElementVisible = OSD_VISIBLE(pos) ? 1 : 0;
|
||||
|
@ -184,6 +184,7 @@ static const OSD_Entry menuOsdElemsEntries[] =
|
|||
OSD_ELEMENT_ENTRY("GPS HDOP", OSD_GPS_HDOP),
|
||||
OSD_ELEMENT_ENTRY("3D SPEED", OSD_3D_SPEED),
|
||||
OSD_ELEMENT_ENTRY("PLUS CODE", OSD_PLUS_CODE),
|
||||
OSD_ELEMENT_ENTRY("AZIMUTH", OSD_AZIMUTH),
|
||||
#endif // GPS
|
||||
OSD_ELEMENT_ENTRY("HEADING", OSD_HEADING),
|
||||
OSD_ELEMENT_ENTRY("HEADING GR.", OSD_HEADING_GRAPH),
|
||||
|
|
|
@ -232,39 +232,3 @@ FAST_CODE void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint
|
|||
filter->y1 = y1;
|
||||
filter->y2 = y2;
|
||||
}
|
||||
|
||||
/*
|
||||
* FIR filter
|
||||
*/
|
||||
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength)
|
||||
{
|
||||
filter->buf = buf;
|
||||
filter->bufLength = bufLength;
|
||||
filter->coeffs = coeffs;
|
||||
filter->coeffsLength = coeffsLength;
|
||||
memset(filter->buf, 0, sizeof(float) * filter->bufLength);
|
||||
}
|
||||
|
||||
/*
|
||||
* FIR filter initialisation
|
||||
* If FIR filter is just used for averaging, coeffs can be set to NULL
|
||||
*/
|
||||
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs)
|
||||
{
|
||||
firFilterInit2(filter, buf, bufLength, coeffs, bufLength);
|
||||
}
|
||||
|
||||
void firFilterUpdate(firFilter_t *filter, float input)
|
||||
{
|
||||
memmove(&filter->buf[1], &filter->buf[0], (filter->bufLength-1) * sizeof(float));
|
||||
filter->buf[0] = input;
|
||||
}
|
||||
|
||||
float firFilterApply(const firFilter_t *filter)
|
||||
{
|
||||
float ret = 0.0f;
|
||||
for (int ii = 0; ii < filter->coeffsLength; ++ii) {
|
||||
ret += filter->coeffs[ii] * filter->buf[ii];
|
||||
}
|
||||
return ret;
|
||||
}
|
||||
|
|
|
@ -81,8 +81,3 @@ float biquadFilterReset(biquadFilter_t *filter, float value);
|
|||
float biquadFilterApplyDF1(biquadFilter_t *filter, float input);
|
||||
float filterGetNotchQ(float centerFrequencyHz, float cutoffFrequencyHz);
|
||||
void biquadFilterUpdate(biquadFilter_t *filter, float filterFreq, uint32_t refreshRate, float Q, biquadFilterType_e filterType);
|
||||
|
||||
void firFilterInit(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs);
|
||||
void firFilterInit2(firFilter_t *filter, float *buf, uint8_t bufLength, const float *coeffs, uint8_t coeffsLength);
|
||||
void firFilterUpdate(firFilter_t *filter, float input);
|
||||
float firFilterApply(const firFilter_t *filter);
|
|
@ -1,183 +0,0 @@
|
|||
/*
|
||||
* 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 "config/config_reset.h"
|
||||
#include "config/parameter_group.h"
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
#include "common/utils.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/global_functions.h"
|
||||
#include "common/logic_condition.h"
|
||||
|
||||
#include "io/vtx.h"
|
||||
#include "drivers/vtx_common.h"
|
||||
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
|
||||
#include "common/axis.h"
|
||||
|
||||
PG_REGISTER_ARRAY_WITH_RESET_FN(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions, PG_GLOBAL_FUNCTIONS, 0);
|
||||
|
||||
EXTENDED_FASTRAM uint64_t globalFunctionsFlags = 0;
|
||||
EXTENDED_FASTRAM globalFunctionState_t globalFunctionsStates[MAX_GLOBAL_FUNCTIONS];
|
||||
EXTENDED_FASTRAM int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST];
|
||||
|
||||
void pgResetFn_globalFunctions(globalFunction_t *instance)
|
||||
{
|
||||
for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
|
||||
RESET_CONFIG(globalFunction_t, &instance[i],
|
||||
.enabled = 0,
|
||||
.conditionId = -1,
|
||||
.action = 0,
|
||||
.withValue = {
|
||||
.type = LOGIC_CONDITION_OPERAND_TYPE_VALUE,
|
||||
.value = 0
|
||||
},
|
||||
.flags = 0
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
void globalFunctionsProcess(int8_t functionId) {
|
||||
//Process only activated functions
|
||||
if (globalFunctions(functionId)->enabled) {
|
||||
|
||||
const int conditionValue = logicConditionGetValue(globalFunctions(functionId)->conditionId);
|
||||
const int previousValue = globalFunctionsStates[functionId].active;
|
||||
|
||||
globalFunctionsStates[functionId].active = (bool) conditionValue;
|
||||
globalFunctionsStates[functionId].value = logicConditionGetOperandValue(
|
||||
globalFunctions(functionId)->withValue.type,
|
||||
globalFunctions(functionId)->withValue.value
|
||||
);
|
||||
|
||||
switch (globalFunctions(functionId)->action) {
|
||||
case GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY:
|
||||
if (conditionValue) {
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE:
|
||||
if (conditionValue) {
|
||||
globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] = globalFunctionsStates[functionId].value;
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW:
|
||||
if (conditionValue) {
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL:
|
||||
if (conditionValue && !previousValue) {
|
||||
vtxDeviceCapability_t vtxDeviceCapability;
|
||||
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
|
||||
vtxSettingsConfigMutable()->power = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_POWER, vtxDeviceCapability.powerCount);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_SET_VTX_BAND:
|
||||
if (conditionValue && !previousValue) {
|
||||
vtxDeviceCapability_t vtxDeviceCapability;
|
||||
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
|
||||
vtxSettingsConfigMutable()->band = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_BAND, VTX_SETTINGS_MAX_BAND);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL:
|
||||
if (conditionValue && !previousValue) {
|
||||
vtxDeviceCapability_t vtxDeviceCapability;
|
||||
if (vtxCommonGetDeviceCapability(vtxCommonDevice(), &vtxDeviceCapability)) {
|
||||
vtxSettingsConfigMutable()->channel = constrain(globalFunctionsStates[functionId].value, VTX_SETTINGS_MIN_CHANNEL, VTX_SETTINGS_MAX_CHANNEL);
|
||||
}
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_INVERT_ROLL:
|
||||
if (conditionValue) {
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_INVERT_PITCH:
|
||||
if (conditionValue) {
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_INVERT_YAW:
|
||||
if (conditionValue) {
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW);
|
||||
}
|
||||
break;
|
||||
case GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE:
|
||||
if (conditionValue) {
|
||||
globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE] = globalFunctionsStates[functionId].value;
|
||||
GLOBAL_FUNCTION_FLAG_ENABLE(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE);
|
||||
}
|
||||
break;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
void NOINLINE globalFunctionsUpdateTask(timeUs_t currentTimeUs) {
|
||||
UNUSED(currentTimeUs);
|
||||
|
||||
//Disable all flags
|
||||
globalFunctionsFlags = 0;
|
||||
|
||||
for (uint8_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
|
||||
globalFunctionsProcess(i);
|
||||
}
|
||||
}
|
||||
|
||||
float NOINLINE getThrottleScale(float globalThrottleScale) {
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE)) {
|
||||
return constrainf(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE] / 100.0f, 0.0f, 1.0f);
|
||||
} else {
|
||||
return globalThrottleScale;
|
||||
}
|
||||
}
|
||||
|
||||
int16_t getRcCommandOverride(int16_t command[], uint8_t axis) {
|
||||
int16_t outputValue = command[axis];
|
||||
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_ROLL) {
|
||||
outputValue = command[FD_YAW];
|
||||
} else if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW) && axis == FD_YAW) {
|
||||
outputValue = command[FD_ROLL];
|
||||
}
|
||||
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL) && axis == FD_ROLL) {
|
||||
outputValue *= -1;
|
||||
}
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH) && axis == FD_PITCH) {
|
||||
outputValue *= -1;
|
||||
}
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW) && axis == FD_YAW) {
|
||||
outputValue *= -1;
|
||||
}
|
||||
|
||||
return outputValue;
|
||||
}
|
||||
|
||||
#endif
|
|
@ -1,80 +0,0 @@
|
|||
/*
|
||||
* 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/logic_condition.h"
|
||||
|
||||
#define MAX_GLOBAL_FUNCTIONS 8
|
||||
|
||||
typedef enum {
|
||||
GLOBAL_FUNCTION_ACTION_OVERRIDE_ARMING_SAFETY = 0, // 0
|
||||
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE_SCALE, // 1
|
||||
GLOBAL_FUNCTION_ACTION_SWAP_ROLL_YAW, // 2
|
||||
GLOBAL_FUNCTION_ACTION_SET_VTX_POWER_LEVEL, // 3
|
||||
GLOBAL_FUNCTION_ACTION_INVERT_ROLL, // 4
|
||||
GLOBAL_FUNCTION_ACTION_INVERT_PITCH, // 5
|
||||
GLOBAL_FUNCTION_ACTION_INVERT_YAW, // 6
|
||||
GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE, // 7
|
||||
GLOBAL_FUNCTION_ACTION_SET_VTX_BAND, // 8
|
||||
GLOBAL_FUNCTION_ACTION_SET_VTX_CHANNEL, // 9
|
||||
GLOBAL_FUNCTION_ACTION_LAST
|
||||
} globalFunctionActions_e;
|
||||
|
||||
typedef enum {
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY = (1 << 0),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE_SCALE = (1 << 1),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_SWAP_ROLL_YAW = (1 << 2),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_ROLL = (1 << 3),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_PITCH = (1 << 4),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_INVERT_YAW = (1 << 5),
|
||||
GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE = (1 << 6),
|
||||
} globalFunctionFlags_t;
|
||||
|
||||
typedef struct globalFunction_s {
|
||||
uint8_t enabled;
|
||||
int8_t conditionId;
|
||||
uint8_t action;
|
||||
logicOperand_t withValue;
|
||||
uint8_t flags;
|
||||
} globalFunction_t;
|
||||
|
||||
typedef struct globalFunctionState_s {
|
||||
uint8_t active;
|
||||
int value;
|
||||
uint8_t flags;
|
||||
} globalFunctionState_t;
|
||||
|
||||
extern uint64_t globalFunctionsFlags;
|
||||
|
||||
#define GLOBAL_FUNCTION_FLAG_DISABLE(mask) (globalFunctionsFlags &= ~(mask))
|
||||
#define GLOBAL_FUNCTION_FLAG_ENABLE(mask) (globalFunctionsFlags |= (mask))
|
||||
#define GLOBAL_FUNCTION_FLAG(mask) (globalFunctionsFlags & (mask))
|
||||
|
||||
PG_DECLARE_ARRAY(globalFunction_t, MAX_GLOBAL_FUNCTIONS, globalFunctions);
|
||||
extern int globalFunctionValues[GLOBAL_FUNCTION_ACTION_LAST];
|
||||
|
||||
void globalFunctionsUpdateTask(timeUs_t currentTimeUs);
|
||||
float getThrottleScale(float globalThrottleScale);
|
||||
int16_t getRcCommandOverride(int16_t command[], uint8_t axis);
|
|
@ -52,6 +52,7 @@
|
|||
#define BUILD_BUG_ON(condition) ((void)sizeof(char[1 - 2*!!(condition)]))
|
||||
|
||||
#define BIT(x) (1 << (x))
|
||||
#define GET_BIT(value, bit) ((value >> bit) & 1)
|
||||
|
||||
#define STATIC_ASSERT(condition, name) \
|
||||
typedef char assert_failed_ ## name [(condition) ? 1 : -1 ] __attribute__((unused))
|
||||
|
@ -112,3 +113,5 @@ void * memcpy_fn ( void * destination, const void * source, size_t num ) asm("me
|
|||
#define UNREACHABLE() __builtin_unreachable()
|
||||
|
||||
#define ALIGNED(x) __attribute__ ((aligned(x)))
|
||||
|
||||
#define PACKED __attribute__((packed))
|
||||
|
|
|
@ -111,7 +111,9 @@
|
|||
#define PG_ESC_SENSOR_CONFIG 1021
|
||||
#define PG_RPM_FILTER_CONFIG 1022
|
||||
#define PG_GLOBAL_VARIABLE_CONFIG 1023
|
||||
#define PG_INAV_END 1023
|
||||
#define PG_SMARTPORT_MASTER_CONFIG 1024
|
||||
#define PG_OSD_LAYOUTS_CONFIG 1025
|
||||
#define PG_INAV_END 1025
|
||||
|
||||
// OSD configuration (subject to change)
|
||||
//#define PG_OSD_FONT_CONFIG 2047
|
||||
|
|
345
src/main/drivers/barometer/barometer_dps310.c
Normal file
345
src/main/drivers/barometer/barometer_dps310.c
Normal file
|
@ -0,0 +1,345 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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/.
|
||||
*
|
||||
* Copyright: INAVFLIGHT OU
|
||||
*/
|
||||
|
||||
#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 "drivers/io.h"
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/time.h"
|
||||
#include "drivers/barometer/barometer.h"
|
||||
#include "drivers/barometer/barometer_dps310.h"
|
||||
|
||||
#if defined(USE_BARO) && defined(USE_BARO_DPS310)
|
||||
|
||||
#define DPS310_REG_PSR_B2 0x00
|
||||
#define DPS310_REG_PSR_B1 0x01
|
||||
#define DPS310_REG_PSR_B0 0x02
|
||||
#define DPS310_REG_TMP_B2 0x03
|
||||
#define DPS310_REG_TMP_B1 0x04
|
||||
#define DPS310_REG_TMP_B0 0x05
|
||||
#define DPS310_REG_PRS_CFG 0x06
|
||||
#define DPS310_REG_TMP_CFG 0x07
|
||||
#define DPS310_REG_MEAS_CFG 0x08
|
||||
#define DPS310_REG_CFG_REG 0x09
|
||||
|
||||
#define DPS310_REG_RESET 0x0C
|
||||
#define DPS310_REG_ID 0x0D
|
||||
|
||||
#define DPS310_REG_COEF 0x10
|
||||
#define DPS310_REG_COEF_SRCE 0x28
|
||||
|
||||
|
||||
#define DPS310_ID_REV_AND_PROD_ID (0x10)
|
||||
|
||||
#define DPS310_RESET_BIT_SOFT_RST (0x09) // 0b1001
|
||||
|
||||
#define DPS310_MEAS_CFG_COEF_RDY (1 << 7)
|
||||
#define DPS310_MEAS_CFG_SENSOR_RDY (1 << 6)
|
||||
#define DPS310_MEAS_CFG_TMP_RDY (1 << 5)
|
||||
#define DPS310_MEAS_CFG_PRS_RDY (1 << 4)
|
||||
|
||||
#define DPS310_MEAS_CFG_MEAS_CTRL_MASK (0x7)
|
||||
#define DPS310_MEAS_CFG_MEAS_CTRL_CONT (0x7)
|
||||
#define DPS310_MEAS_CFG_MEAS_TEMP_SING (0x2)
|
||||
#define DPS310_MEAS_CFG_MEAS_IDLE (0x0)
|
||||
|
||||
#define DPS310_PRS_CFG_BIT_PM_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec.
|
||||
#define DPS310_PRS_CFG_BIT_PM_PRC_16 (0x04) // 0100 - 16 times (Standard).
|
||||
|
||||
#define DPS310_TMP_CFG_BIT_TMP_EXT (0x80) //
|
||||
#define DPS310_TMP_CFG_BIT_TMP_RATE_32HZ (0x50) // 101 - 32 measurements pr. sec.
|
||||
#define DPS310_TMP_CFG_BIT_TMP_PRC_16 (0x04) // 0100 - 16 times (Standard).
|
||||
|
||||
#define DPS310_CFG_REG_BIT_P_SHIFT (0x04)
|
||||
#define DPS310_CFG_REG_BIT_T_SHIFT (0x08)
|
||||
|
||||
#define DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE (0x80)
|
||||
|
||||
typedef struct {
|
||||
int16_t c0; // 12bit
|
||||
int16_t c1; // 12bit
|
||||
int32_t c00; // 20bit
|
||||
int32_t c10; // 20bit
|
||||
int16_t c01; // 16bit
|
||||
int16_t c11; // 16bit
|
||||
int16_t c20; // 16bit
|
||||
int16_t c21; // 16bit
|
||||
int16_t c30; // 16bit
|
||||
} calibrationCoefficients_t;
|
||||
|
||||
typedef struct {
|
||||
calibrationCoefficients_t calib;
|
||||
float pressure; // Pa
|
||||
float temperature; // DegC
|
||||
} baroState_t;
|
||||
|
||||
static baroState_t baroState;
|
||||
|
||||
|
||||
// Helper functions
|
||||
static uint8_t registerRead(busDevice_t * busDev, uint8_t reg)
|
||||
{
|
||||
uint8_t buf;
|
||||
busRead(busDev, reg, &buf);
|
||||
return buf;
|
||||
}
|
||||
|
||||
static void registerWrite(busDevice_t * busDev, uint8_t reg, uint8_t value)
|
||||
{
|
||||
busWrite(busDev, reg, value);
|
||||
}
|
||||
|
||||
static void registerWriteBits(busDevice_t * busDev, uint8_t reg, uint8_t mask, uint8_t bits)
|
||||
{
|
||||
uint8_t val = registerRead(busDev, reg);
|
||||
|
||||
if ((val & mask) != bits) {
|
||||
val = (val & (~mask)) | bits;
|
||||
registerWrite(busDev, reg, val);
|
||||
}
|
||||
}
|
||||
|
||||
static void registerSetBits(busDevice_t * busDev, uint8_t reg, uint8_t setbits)
|
||||
{
|
||||
registerWriteBits(busDev, reg, setbits, setbits);
|
||||
}
|
||||
|
||||
static int32_t getTwosComplement(uint32_t raw, uint8_t length)
|
||||
{
|
||||
if (raw & ((int)1 << (length - 1))) {
|
||||
return ((int32_t)raw) - ((int32_t)1 << length);
|
||||
}
|
||||
else {
|
||||
return raw;
|
||||
}
|
||||
}
|
||||
|
||||
static bool deviceConfigure(busDevice_t * busDev)
|
||||
{
|
||||
// Trigger a chip reset
|
||||
registerSetBits(busDev, DPS310_REG_RESET, DPS310_RESET_BIT_SOFT_RST);
|
||||
|
||||
// Sleep 40ms
|
||||
delay(40);
|
||||
|
||||
uint8_t status = registerRead(busDev, DPS310_REG_MEAS_CFG);
|
||||
|
||||
// Check if coefficients are available
|
||||
if ((status & DPS310_MEAS_CFG_COEF_RDY) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// Check if sensor initialization is complete
|
||||
if ((status & DPS310_MEAS_CFG_SENSOR_RDY) == 0) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// 1. Read the pressure calibration coefficients (c00, c10, c20, c30, c01, c11, and c21) from the Calibration Coefficient register.
|
||||
// Note: The coefficients read from the coefficient register are 2's complement numbers.
|
||||
uint8_t coef[18];
|
||||
if (!busReadBuf(busDev, DPS310_REG_COEF, coef, sizeof(coef))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// 0x11 c0 [3:0] + 0x10 c0 [11:4]
|
||||
baroState.calib.c0 = getTwosComplement(((uint32_t)coef[0] << 4) | (((uint32_t)coef[1] >> 4) & 0x0F), 12);
|
||||
|
||||
// 0x11 c1 [11:8] + 0x12 c1 [7:0]
|
||||
baroState.calib.c1 = getTwosComplement((((uint32_t)coef[1] & 0x0F) << 8) | (uint32_t)coef[2], 12);
|
||||
|
||||
// 0x13 c00 [19:12] + 0x14 c00 [11:4] + 0x15 c00 [3:0]
|
||||
baroState.calib.c00 = getTwosComplement(((uint32_t)coef[3] << 12) | ((uint32_t)coef[4] << 4) | (((uint32_t)coef[5] >> 4) & 0x0F), 20);
|
||||
|
||||
// 0x15 c10 [19:16] + 0x16 c10 [15:8] + 0x17 c10 [7:0]
|
||||
baroState.calib.c10 = getTwosComplement((((uint32_t)coef[5] & 0x0F) << 16) | ((uint32_t)coef[6] << 8) | (uint32_t)coef[7], 20);
|
||||
|
||||
// 0x18 c01 [15:8] + 0x19 c01 [7:0]
|
||||
baroState.calib.c01 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16);
|
||||
|
||||
// 0x1A c11 [15:8] + 0x1B c11 [7:0]
|
||||
baroState.calib.c11 = getTwosComplement(((uint32_t)coef[8] << 8) | (uint32_t)coef[9], 16);
|
||||
|
||||
// 0x1C c20 [15:8] + 0x1D c20 [7:0]
|
||||
baroState.calib.c20 = getTwosComplement(((uint32_t)coef[12] << 8) | (uint32_t)coef[13], 16);
|
||||
|
||||
// 0x1E c21 [15:8] + 0x1F c21 [7:0]
|
||||
baroState.calib.c21 = getTwosComplement(((uint32_t)coef[14] << 8) | (uint32_t)coef[15], 16);
|
||||
|
||||
// 0x20 c30 [15:8] + 0x21 c30 [7:0]
|
||||
baroState.calib.c30 = getTwosComplement(((uint32_t)coef[16] << 8) | (uint32_t)coef[17], 16);
|
||||
|
||||
// MEAS_CFG: Make sure the device is in IDLE mode
|
||||
registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_IDLE);
|
||||
|
||||
// Fix IC with a fuse bit problem, which lead to a wrong temperature
|
||||
// Should not affect ICs without this problem
|
||||
registerWrite(busDev, 0x0E, 0xA5);
|
||||
registerWrite(busDev, 0x0F, 0x96);
|
||||
registerWrite(busDev, 0x62, 0x02);
|
||||
registerWrite(busDev, 0x0E, 0x00);
|
||||
registerWrite(busDev, 0x0F, 0x00);
|
||||
|
||||
// Make ONE temperature measurement and flush it
|
||||
registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_TEMP_SING);
|
||||
delay(40);
|
||||
|
||||
// PRS_CFG: pressure measurement rate (32 Hz) and oversampling (16 time standard)
|
||||
registerSetBits(busDev, DPS310_REG_PRS_CFG, DPS310_PRS_CFG_BIT_PM_RATE_32HZ | DPS310_PRS_CFG_BIT_PM_PRC_16);
|
||||
|
||||
// TMP_CFG: temperature measurement rate (32 Hz) and oversampling (16 times)
|
||||
const uint8_t TMP_COEF_SRCE = registerRead(busDev, DPS310_REG_COEF_SRCE) & DPS310_COEF_SRCE_BIT_TMP_COEF_SRCE;
|
||||
registerSetBits(busDev, DPS310_REG_TMP_CFG, DPS310_TMP_CFG_BIT_TMP_RATE_32HZ | DPS310_TMP_CFG_BIT_TMP_PRC_16 | TMP_COEF_SRCE);
|
||||
|
||||
// CFG_REG: set pressure and temperature result bit-shift (required when the oversampling rate is >8 times)
|
||||
registerSetBits(busDev, DPS310_REG_CFG_REG, DPS310_CFG_REG_BIT_T_SHIFT | DPS310_CFG_REG_BIT_P_SHIFT);
|
||||
|
||||
// MEAS_CFG: Continuous pressure and temperature measurement
|
||||
registerWriteBits(busDev, DPS310_REG_MEAS_CFG, DPS310_MEAS_CFG_MEAS_CTRL_MASK, DPS310_MEAS_CFG_MEAS_CTRL_CONT);
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceReadMeasurement(baroDev_t *baro)
|
||||
{
|
||||
// 1. Check if pressure is ready
|
||||
bool pressure_ready = registerRead(baro->busDev, DPS310_REG_MEAS_CFG) & DPS310_MEAS_CFG_PRS_RDY;
|
||||
if (!pressure_ready) {
|
||||
return false;
|
||||
}
|
||||
|
||||
// 2. Choose scaling factors kT (for temperature) and kP (for pressure) based on the chosen precision rate.
|
||||
// The scaling factors are listed in Table 9.
|
||||
static float kT = 253952; // 16 times (Standard)
|
||||
static float kP = 253952; // 16 times (Standard)
|
||||
|
||||
// 3. Read the pressure and temperature result from the registers
|
||||
// Read PSR_B2, PSR_B1, PSR_B0, TMP_B2, TMP_B1, TMP_B0
|
||||
uint8_t buf[6];
|
||||
if (!busReadBuf(baro->busDev, DPS310_REG_PSR_B2, buf, 6)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
const int32_t Praw = getTwosComplement((buf[0] << 16) + (buf[1] << 8) + buf[2], 24);
|
||||
const int32_t Traw = getTwosComplement((buf[3] << 16) + (buf[4] << 8) + buf[5], 24);
|
||||
|
||||
// 4. Calculate scaled measurement results.
|
||||
const float Praw_sc = Praw / kP;
|
||||
const float Traw_sc = Traw / kT;
|
||||
|
||||
// 5. Calculate compensated measurement results.
|
||||
const float c00 = baroState.calib.c00;
|
||||
const float c01 = baroState.calib.c01;
|
||||
const float c10 = baroState.calib.c10;
|
||||
const float c11 = baroState.calib.c11;
|
||||
const float c20 = baroState.calib.c20;
|
||||
const float c21 = baroState.calib.c21;
|
||||
const float c30 = baroState.calib.c30;
|
||||
|
||||
const float c0 = baroState.calib.c0;
|
||||
const float c1 = baroState.calib.c1;
|
||||
|
||||
baroState.pressure = c00 + Praw_sc * (c10 + Praw_sc * (c20 + Praw_sc * c30)) + Traw_sc * c01 + Traw_sc * Praw_sc * (c11 + Praw_sc * c21);
|
||||
baroState.temperature = c0 * 0.5f + c1 * Traw_sc;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool deviceCalculate(baroDev_t *baro, int32_t *pressure, int32_t *temperature)
|
||||
{
|
||||
UNUSED(baro);
|
||||
|
||||
if (pressure) {
|
||||
*pressure = baroState.pressure;
|
||||
}
|
||||
|
||||
if (temperature) {
|
||||
*temperature = (baroState.temperature * 100); // to centidegrees
|
||||
}
|
||||
|
||||
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[1];
|
||||
|
||||
delay(100);
|
||||
|
||||
bool ack = busReadBuf(busDev, DPS310_REG_ID, chipId, 1);
|
||||
|
||||
if (ack && chipId[0] == DPS310_ID_REV_AND_PROD_ID) {
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool baroDPS310Detect(baroDev_t *baro)
|
||||
{
|
||||
baro->busDev = busDeviceInit(BUSTYPE_ANY, DEVHW_DPS310, 0, OWNER_BARO);
|
||||
if (baro->busDev == NULL) {
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(baro->busDev)) {
|
||||
busDeviceDeInit(baro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceConfigure(baro->busDev)) {
|
||||
busDeviceDeInit(baro->busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
const uint32_t baroDelay = 1000000 / 32 / 2; // twice the sample rate to capture all new data
|
||||
|
||||
baro->ut_delay = 0;
|
||||
baro->start_ut = NULL;
|
||||
baro->get_ut = NULL;
|
||||
|
||||
baro->up_delay = baroDelay;
|
||||
baro->start_up = NULL;
|
||||
baro->get_up = deviceReadMeasurement;
|
||||
|
||||
baro->calculate = deviceCalculate;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
29
src/main/drivers/barometer/barometer_dps310.h
Normal file
29
src/main/drivers/barometer/barometer_dps310.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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/.
|
||||
*
|
||||
* Copyright: INAVFLIGHT OU
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
bool baroDPS310Detect(baroDev_t *baro);
|
|
@ -104,6 +104,7 @@ typedef enum {
|
|||
DEVHW_LPS25H,
|
||||
DEVHW_SPL06,
|
||||
DEVHW_BMP388,
|
||||
DEVHW_DPS310,
|
||||
|
||||
/* Compass chips */
|
||||
DEVHW_HMC5883,
|
||||
|
@ -144,6 +145,7 @@ typedef enum {
|
|||
DEVHW_UG2864, // I2C OLED display
|
||||
DEVHW_SDCARD, // Generic SD-Card
|
||||
DEVHW_IRLOCK, // IR-Lock visual positioning hardware
|
||||
DEVHW_PCF8574, // 8-bit I/O expander
|
||||
} devHardwareType_e;
|
||||
|
||||
typedef enum {
|
||||
|
|
|
@ -273,3 +273,8 @@ void displayCanvasContextPop(displayCanvas_t *displayCanvas)
|
|||
displayCanvas->vTable->contextPop(displayCanvas);
|
||||
}
|
||||
}
|
||||
|
||||
bool displayCanvasGetWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas)
|
||||
{
|
||||
return displayCanvas && displayCanvas->vTable->getWidgets ? displayCanvas->vTable->getWidgets(widgets, displayCanvas) : false;
|
||||
}
|
||||
|
|
|
@ -29,6 +29,8 @@
|
|||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
typedef struct displayWidgets_s displayWidgets_t;
|
||||
|
||||
typedef enum {
|
||||
DISPLAY_CANVAS_BITMAP_OPT_INVERT_COLORS = 1 << 0,
|
||||
DISPLAY_CANVAS_BITMAP_OPT_SOLID_BACKGROUND = 1 << 1,
|
||||
|
@ -100,8 +102,9 @@ typedef struct displayCanvasVTable_s {
|
|||
|
||||
void (*contextPush)(displayCanvas_t *displayCanvas);
|
||||
void (*contextPop)(displayCanvas_t *displayCanvas);
|
||||
} displayCanvasVTable_t;
|
||||
|
||||
bool (*getWidgets)(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas);
|
||||
} displayCanvasVTable_t;
|
||||
|
||||
void displayCanvasSetStrokeColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color);
|
||||
void displayCanvasSetFillColor(displayCanvas_t *displayCanvas, displayCanvasColor_e color);
|
||||
|
@ -141,3 +144,5 @@ void displayCanvasCtmRotate(displayCanvas_t *displayCanvas, float r);
|
|||
|
||||
void displayCanvasContextPush(displayCanvas_t *displayCanvas);
|
||||
void displayCanvasContextPop(displayCanvas_t *displayCanvas);
|
||||
|
||||
bool displayCanvasGetWidgets(displayWidgets_t *widgets, const displayCanvas_t *displayCanvas);
|
||||
|
|
33
src/main/drivers/display_widgets.c
Normal file
33
src/main/drivers/display_widgets.c
Normal file
|
@ -0,0 +1,33 @@
|
|||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_CANVAS)
|
||||
|
||||
#include "drivers/display_widgets.h"
|
||||
|
||||
int displayWidgetsSupportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType)
|
||||
{
|
||||
return widgets->vTable->supportedInstances ? widgets->vTable->supportedInstances(widgets, widgetType) : 0;
|
||||
}
|
||||
|
||||
bool displayWidgetsConfigureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config)
|
||||
{
|
||||
return widgets->vTable->configureAHI ? widgets->vTable->configureAHI(widgets, instance, config) : false;
|
||||
}
|
||||
|
||||
bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data)
|
||||
{
|
||||
return widgets->vTable->drawAHI ? widgets->vTable->drawAHI(widgets, instance, data) : false;
|
||||
}
|
||||
|
||||
bool displayWidgetsConfigureSidebar(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config)
|
||||
{
|
||||
return widgets->vTable->configureSidebar ? widgets->vTable->configureSidebar(widgets, instance, config) : false;
|
||||
}
|
||||
|
||||
bool displayWidgetsDrawSidebar(displayWidgets_t *widgets, unsigned instance, int32_t data)
|
||||
{
|
||||
return widgets->vTable->drawSidebar ? widgets->vTable->drawSidebar(widgets, instance, data) : false;
|
||||
}
|
||||
|
||||
#endif
|
77
src/main/drivers/display_widgets.h
Normal file
77
src/main/drivers/display_widgets.h
Normal file
|
@ -0,0 +1,77 @@
|
|||
#pragma once
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "drivers/osd.h"
|
||||
|
||||
typedef struct widgetRect_s {
|
||||
int x;
|
||||
int y;
|
||||
unsigned w;
|
||||
unsigned h;
|
||||
} widgetRect_t;
|
||||
|
||||
typedef enum {
|
||||
DISPLAY_WIDGET_TYPE_AHI,
|
||||
DISPLAY_WIDGET_TYPE_SIDEBAR,
|
||||
} displayWidgetType_e;
|
||||
|
||||
typedef enum {
|
||||
DISPLAY_WIDGET_AHI_STYLE_STAIRCASE = 0,
|
||||
DISPLAY_WIDGET_AHI_STYLE_LINE = 1,
|
||||
} widgetAHIStyle_e;
|
||||
|
||||
typedef enum {
|
||||
DISPLAY_WIDGET_AHI_OPTION_SHOW_CORNERS = 1 << 0,
|
||||
} widgetAHIOptions_t;
|
||||
|
||||
typedef struct widgetAHIConfiguration_s {
|
||||
widgetRect_t rect;
|
||||
widgetAHIStyle_e style;
|
||||
widgetAHIOptions_t options;
|
||||
unsigned crosshairMargin;
|
||||
unsigned strokeWidth;
|
||||
} widgetAHIConfiguration_t;
|
||||
|
||||
typedef struct widgetAHIData_s {
|
||||
float pitch; // radians
|
||||
float roll; // radians
|
||||
} widgetAHIData_t;
|
||||
|
||||
typedef enum
|
||||
{
|
||||
DISPLAY_WIDGET_SIDEBAR_OPTION_LEFT = 1 << 0, // Display the sidebar oriented to the left. Default is to the right
|
||||
DISPLAY_WIDGET_SIDEBAR_OPTION_REVERSE = 1 << 1, // Reverse the sidebar direction, so positive values move it down
|
||||
DISPLAY_WIDGET_SIDEBAR_OPTION_UNLABELED = 1 << 2, // Don't display the central label with the value.
|
||||
DISPLAY_WIDGET_SIDEBAR_OPTION_STATIC = 1 << 3, // The sidebar doesn't scroll nor display values along it.
|
||||
} widgetSidebarOptions_t;
|
||||
|
||||
typedef struct widgetSidebarConfiguration_s {
|
||||
widgetRect_t rect;
|
||||
widgetSidebarOptions_t options;
|
||||
uint8_t divisions; // How many divisions the sidebar will have
|
||||
uint16_t counts_per_step; // How much the value increases/decreases per division BEFORE applying the unit scale
|
||||
osdUnit_t unit; // The unit used to display the values in the sidebar
|
||||
} widgetSidebarConfiguration_t;
|
||||
|
||||
typedef struct displayWidgetsVTable_s displayWidgetsVTable_t;
|
||||
|
||||
typedef struct displayWidgets_s {
|
||||
const displayWidgetsVTable_t *vTable;
|
||||
void *device;
|
||||
} displayWidgets_t;
|
||||
|
||||
typedef struct displayWidgetsVTable_s {
|
||||
int (*supportedInstances)(displayWidgets_t *widgets, displayWidgetType_e widgetType);
|
||||
bool (*configureAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config);
|
||||
bool (*drawAHI)(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data);
|
||||
bool (*configureSidebar)(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config);
|
||||
bool (*drawSidebar)(displayWidgets_t *widgets, unsigned instance, int32_t data);
|
||||
} displayWidgetsVTable_t;
|
||||
|
||||
int displayWidgetsSupportedInstances(displayWidgets_t *widgets, displayWidgetType_e widgetType);
|
||||
bool displayWidgetsConfigureAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIConfiguration_t *config);
|
||||
bool displayWidgetsDrawAHI(displayWidgets_t *widgets, unsigned instance, const widgetAHIData_t *data);
|
||||
bool displayWidgetsConfigureSidebar(displayWidgets_t *widgets, unsigned instance, const widgetSidebarConfiguration_t *config);
|
||||
bool displayWidgetsDrawSidebar(displayWidgets_t *widgets, unsigned instance, int32_t data);
|
|
@ -30,6 +30,9 @@
|
|||
|
||||
#include "flash.h"
|
||||
#include "flash_m25p16.h"
|
||||
|
||||
#include "common/time.h"
|
||||
|
||||
#include "drivers/bus_spi.h"
|
||||
#include "drivers/io.h"
|
||||
#include "drivers/time.h"
|
||||
|
@ -37,6 +40,7 @@
|
|||
static flashPartitionTable_t flashPartitionTable;
|
||||
static int flashPartitions = 0;
|
||||
|
||||
|
||||
#ifdef USE_SPI
|
||||
static bool flashSpiInit(void)
|
||||
{
|
||||
|
@ -64,7 +68,7 @@ bool flashIsReady(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
bool flashWaitForReady(uint32_t timeoutMillis)
|
||||
bool flashWaitForReady(timeMs_t timeoutMillis)
|
||||
{
|
||||
#ifdef USE_FLASH_M25P16
|
||||
return m25p16_waitForReady(timeoutMillis);
|
||||
|
|
|
@ -22,7 +22,7 @@
|
|||
|
||||
#include <stdint.h>
|
||||
|
||||
//#include "drivers/io.h"
|
||||
#include "common/time.h"
|
||||
|
||||
//#ifdef USE_FLASHFS
|
||||
|
||||
|
@ -39,7 +39,7 @@ typedef struct flashGeometry_s {
|
|||
bool flashInit(void);
|
||||
|
||||
bool flashIsReady(void);
|
||||
bool flashWaitForReady(uint32_t timeoutMillis);
|
||||
bool flashWaitForReady(timeMs_t timeoutMillis);
|
||||
void flashEraseSector(uint32_t address);
|
||||
void flashEraseCompletely(void);
|
||||
#if 0
|
||||
|
|
84
src/main/drivers/io_pcf8574.c
Normal file
84
src/main/drivers/io_pcf8574.c
Normal file
|
@ -0,0 +1,84 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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 <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include "drivers/bus.h"
|
||||
#include "drivers/io_pcf8574.h"
|
||||
#include "drivers/time.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
#define PCF8574_WRITE_ADDRESS 0x40
|
||||
#define PCF8574_READ_ADDRESS 0x41
|
||||
|
||||
static busDevice_t *busDev;
|
||||
|
||||
static bool deviceDetect(busDevice_t *busDev)
|
||||
{
|
||||
for (int retry = 0; retry < 5; retry++)
|
||||
{
|
||||
uint8_t sig;
|
||||
|
||||
delay(150);
|
||||
|
||||
bool ack = busRead(busDev, 0x00, &sig);
|
||||
if (ack)
|
||||
{
|
||||
return true;
|
||||
}
|
||||
};
|
||||
|
||||
return false;
|
||||
}
|
||||
|
||||
bool pcf8574Init(void)
|
||||
{
|
||||
busDev = busDeviceInit(BUSTYPE_I2C, DEVHW_PCF8574, 0, 0);
|
||||
if (busDev == NULL)
|
||||
{
|
||||
DEBUG_SET(DEBUG_PCF8574, 0, 1);
|
||||
return false;
|
||||
}
|
||||
|
||||
if (!deviceDetect(busDev))
|
||||
{
|
||||
DEBUG_SET(DEBUG_PCF8574, 0, 2);
|
||||
busDeviceDeInit(busDev);
|
||||
return false;
|
||||
}
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void pcf8574Write(uint8_t data)
|
||||
{
|
||||
busWrite(busDev, PCF8574_WRITE_ADDRESS, data);
|
||||
}
|
||||
|
||||
uint8_t pcf8574Read(void)
|
||||
{
|
||||
uint8_t data;
|
||||
busRead(busDev, PCF8574_READ_ADDRESS, &data);
|
||||
return data;
|
||||
}
|
29
src/main/drivers/io_pcf8574.h
Normal file
29
src/main/drivers/io_pcf8574.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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
|
||||
|
||||
bool pcf8574Init(void);
|
||||
void pcf8574Write(uint8_t data);
|
||||
uint8_t pcf8574Read(void);
|
67
src/main/drivers/io_port_expander.c
Normal file
67
src/main/drivers/io_port_expander.c
Normal file
|
@ -0,0 +1,67 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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 <stdbool.h>
|
||||
#include "platform.h"
|
||||
#include "drivers/io_port_expander.h"
|
||||
#include "drivers/io_pcf8574.h"
|
||||
|
||||
#ifdef USE_I2C_IO_EXPANDER
|
||||
|
||||
static ioPortExpanderState_t ioPortExpanderState;
|
||||
|
||||
void ioPortExpanderInit(void)
|
||||
{
|
||||
|
||||
ioPortExpanderState.active = pcf8574Init();
|
||||
|
||||
if (ioPortExpanderState.active) {
|
||||
ioPortExpanderState.state = 0x00;
|
||||
pcf8574Write(ioPortExpanderState.state); //Set all ports to OFF
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void ioPortExpanderSet(uint8_t pin, uint8_t value)
|
||||
{
|
||||
if (pin > 7) {
|
||||
return;
|
||||
}
|
||||
|
||||
//Cast to 0/1
|
||||
value = (bool) value;
|
||||
|
||||
ioPortExpanderState.state ^= (-value ^ ioPortExpanderState.state) & (1UL << pin);
|
||||
ioPortExpanderState.shouldSync = true;
|
||||
}
|
||||
|
||||
void ioPortExpanderSync(void)
|
||||
{
|
||||
if (ioPortExpanderState.active && ioPortExpanderState.shouldSync) {
|
||||
pcf8574Write(ioPortExpanderState.state);
|
||||
ioPortExpanderState.shouldSync = false;;
|
||||
}
|
||||
}
|
||||
|
||||
#endif
|
37
src/main/drivers/io_port_expander.h
Normal file
37
src/main/drivers/io_port_expander.h
Normal file
|
@ -0,0 +1,37 @@
|
|||
/*
|
||||
* This file is part of INAV.
|
||||
*
|
||||
* 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 "stdint.h"
|
||||
|
||||
typedef struct ioPortExpanderState_s {
|
||||
uint8_t active;
|
||||
uint8_t state;
|
||||
uint8_t shouldSync;
|
||||
} ioPortExpanderState_t;
|
||||
|
||||
void ioPortExpanderInit(void);
|
||||
void ioPortExpanderSync(void);
|
||||
void ioPortExpanderSet(uint8_t pin, uint8_t value);
|
|
@ -23,8 +23,13 @@
|
|||
*
|
||||
*/
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#if defined(USE_OSD)
|
||||
|
||||
#include "drivers/display_canvas.h"
|
||||
#include "drivers/osd.h"
|
||||
#include "drivers/osd_symbols.h"
|
||||
|
||||
uint16_t osdCharacterGridBuffer[OSD_CHARACTER_GRID_BUFFER_SIZE] ALIGNED(4);
|
||||
|
||||
|
@ -32,8 +37,9 @@ void osdCharacterGridBufferClear(void)
|
|||
{
|
||||
uint32_t *ptr = (uint32_t *)osdCharacterGridBuffer;
|
||||
uint32_t *end = (uint32_t *)(ARRAYEND(osdCharacterGridBuffer));
|
||||
uint32_t blank32 = SYM_BLANK << 24 | SYM_BLANK << 16 | SYM_BLANK << 8 | SYM_BLANK;
|
||||
for (; ptr < end; ptr++) {
|
||||
*ptr = 0;
|
||||
*ptr = blank32;
|
||||
}
|
||||
}
|
||||
|
||||
|
@ -72,9 +78,9 @@ void osdGridBufferClearGridRect(int x, int y, int w, int h)
|
|||
osdGridBufferConstrainRect(&x, &y, &w, &h, OSD_CHARACTER_GRID_MAX_WIDTH, OSD_CHARACTER_GRID_MAX_HEIGHT);
|
||||
int maxX = x + w;
|
||||
int maxY = y + h;
|
||||
for (int ii = x; ii <= maxX + w; ii++) {
|
||||
for (int ii = x; ii <= maxX; ii++) {
|
||||
for (int jj = y; jj <= maxY; jj++) {
|
||||
*osdCharacterGridBufferGetEntryPtr(ii, jj) = 0;
|
||||
*osdCharacterGridBufferGetEntryPtr(ii, jj) = SYM_BLANK;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
@ -102,3 +108,5 @@ uint16_t *osdCharacterGridBufferGetEntryPtr(unsigned x, unsigned y)
|
|||
unsigned pos = y * OSD_CHARACTER_GRID_MAX_WIDTH + x;
|
||||
return &osdCharacterGridBuffer[pos];
|
||||
}
|
||||
|
||||
#endif
|
||||
|
|
|
@ -61,14 +61,23 @@ typedef struct osdCharacter_s {
|
|||
uint8_t data[OSD_CHAR_BYTES];
|
||||
} osdCharacter_t;
|
||||
|
||||
typedef struct osdUnit_t
|
||||
{
|
||||
uint16_t scale; // The scale between the value and the represented unit. e.g. if you're providing cms but you want to draw meters this should be 100 ([0, 1023])
|
||||
uint16_t symbol; // Symbol to append/prepend to the value when it's not scaled [0, 511]
|
||||
uint16_t divisor; // If abs(value) > divisor, divide it by this. e.g. for meters and km you'd set this to 1000 [0, UINT16_MAX)
|
||||
uint16_t divided_symbol; // Symbol to append/prepend to the value when it's divided (e.g. the km symbol) [0, 511]
|
||||
} osdUnit_t;
|
||||
|
||||
#define OSD_CHARACTER_GRID_MAX_WIDTH 30
|
||||
#define OSD_CHARACTER_GRID_MAX_HEIGHT 16
|
||||
#define OSD_CHARACTER_GRID_BUFFER_SIZE (OSD_CHARACTER_GRID_MAX_WIDTH * OSD_CHARACTER_GRID_MAX_HEIGHT)
|
||||
|
||||
extern uint16_t osdCharacterGridBuffer[OSD_CHARACTER_GRID_BUFFER_SIZE] ALIGNED(4);
|
||||
|
||||
// Sets all buffer entries to 0
|
||||
// Sets all buffer entries to SYM_BLANK
|
||||
void osdCharacterGridBufferClear(void);
|
||||
void osdGridBufferClearGridRect(int x, int y, int w, int h);
|
||||
void osdGridBufferClearPixelRect(displayCanvas_t *canvas, int x, int y, int w, int h);
|
||||
|
||||
uint16_t *osdCharacterGridBufferGetEntryPtr(unsigned x, unsigned y);
|
||||
|
|
|
@ -118,7 +118,7 @@
|
|||
|
||||
#define SYM_RPM 0x8B // 139 RPM
|
||||
#define SYM_WAYPOINT 0x8C // 140 Waypoint
|
||||
// 0x8D // 141 -
|
||||
#define SYM_AZIMUTH 0x8D // 141 Azimuth
|
||||
// 0x8E // 142 -
|
||||
// 0x8F // 143 -
|
||||
|
||||
|
|
|
@ -35,8 +35,12 @@ typedef enum {
|
|||
|
||||
// Values for PERSISTENT_OBJECT_RESET_REASON
|
||||
#define RESET_NONE 0
|
||||
#define RESET_BOOTLOADER_REQUEST_ROM 1
|
||||
#define RESET_BOOTLOADER_REQUEST_ROM 1 // DFU request
|
||||
#define RESET_MSC_REQUEST 2 // MSC invocation was requested
|
||||
#define RESET_BOOTLOADER_FIRMWARE_UPDATE 3 // Bootloader request to flash stored firmware update
|
||||
#define RESET_BOOTLOADER_FIRMWARE_ROLLBACK 4 // Bootloader request to rollback to stored firmware and config backup
|
||||
#define RESET_BOOTLOADER_FIRMWARE_UPDATE_SUCCESS 5
|
||||
#define RESET_BOOTLOADER_FIRMWARE_UPDATE_FAILED 6
|
||||
|
||||
void persistentObjectInit(void);
|
||||
uint32_t persistentObjectRead(persistentObjectId_e id);
|
||||
|
|
|
@ -111,3 +111,11 @@ bool serialIsConnected(const serialPort_t *instance)
|
|||
// If API is not defined - assume connected
|
||||
return true;
|
||||
}
|
||||
|
||||
bool serialIsIdle(serialPort_t *instance)
|
||||
{
|
||||
if (instance->vTable->isIdle)
|
||||
return instance->vTable->isIdle(instance);
|
||||
else
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -95,6 +95,8 @@ struct serialPortVTable {
|
|||
|
||||
bool (*isConnected)(const serialPort_t *instance);
|
||||
|
||||
bool (*isIdle)(serialPort_t *instance);
|
||||
|
||||
// Optional functions used to buffer large writes.
|
||||
void (*beginWrite)(serialPort_t *instance);
|
||||
void (*endWrite)(serialPort_t *instance);
|
||||
|
@ -111,6 +113,7 @@ bool isSerialTransmitBufferEmpty(const serialPort_t *instance);
|
|||
void serialPrint(serialPort_t *instance, const char *str);
|
||||
uint32_t serialGetBaudRate(serialPort_t *instance);
|
||||
bool serialIsConnected(const serialPort_t *instance);
|
||||
bool serialIsIdle(serialPort_t *instance);
|
||||
|
||||
// A shim that adapts the bufWriter API to the serialWriteBuf() API.
|
||||
void serialWriteBufShim(void *instance, const uint8_t *data, int count);
|
||||
|
|
|
@ -628,7 +628,8 @@ static const struct serialPortVTable softSerialVTable = {
|
|||
.isConnected = NULL,
|
||||
.writeBuf = NULL,
|
||||
.beginWrite = NULL,
|
||||
.endWrite = NULL
|
||||
.endWrite = NULL,
|
||||
.isIdle = NULL,
|
||||
};
|
||||
|
||||
#endif
|
||||
|
|
|
@ -247,6 +247,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
|
|||
USART_ITConfig(s->USARTx, USART_IT_TXE, ENABLE);
|
||||
}
|
||||
|
||||
bool isUartIdle(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
if(USART_GetFlagStatus(s->USARTx, USART_FLAG_IDLE)) {
|
||||
uartClearIdleFlag(s);
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const struct serialPortVTable uartVTable[] = {
|
||||
{
|
||||
.serialWrite = uartWrite,
|
||||
|
@ -260,5 +271,6 @@ const struct serialPortVTable uartVTable[] = {
|
|||
.writeBuf = NULL,
|
||||
.beginWrite = NULL,
|
||||
.endWrite = NULL,
|
||||
.isIdle = isUartIdle,
|
||||
}
|
||||
};
|
||||
|
|
|
@ -64,6 +64,7 @@ typedef struct {
|
|||
} uartPort_t;
|
||||
|
||||
void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins);
|
||||
void uartClearIdleFlag(uartPort_t *s);
|
||||
serialPort_t *uartOpen(USART_TypeDef *USARTx, serialReceiveCallbackPtr rxCallback, void *rxCallbackData, uint32_t baudRate, portMode_t mode, portOptions_t options);
|
||||
|
||||
// serialPort API
|
||||
|
|
|
@ -246,6 +246,17 @@ void uartWrite(serialPort_t *instance, uint8_t ch)
|
|||
__HAL_UART_ENABLE_IT(&s->Handle, UART_IT_TXE);
|
||||
}
|
||||
|
||||
bool isUartIdle(serialPort_t *instance)
|
||||
{
|
||||
uartPort_t *s = (uartPort_t *)instance;
|
||||
if(__HAL_UART_GET_FLAG(&s->Handle, UART_FLAG_IDLE)) {
|
||||
__HAL_UART_CLEAR_IDLEFLAG(&s->Handle);
|
||||
return true;
|
||||
} else {
|
||||
return false;
|
||||
}
|
||||
}
|
||||
|
||||
const struct serialPortVTable uartVTable[] = {
|
||||
{
|
||||
.serialWrite = uartWrite,
|
||||
|
@ -259,5 +270,6 @@ const struct serialPortVTable uartVTable[] = {
|
|||
.writeBuf = NULL,
|
||||
.beginWrite = NULL,
|
||||
.endWrite = NULL,
|
||||
.isIdle = isUartIdle,
|
||||
}
|
||||
};
|
||||
|
|
|
@ -351,6 +351,11 @@ void usartIrqHandler(uartPort_t *s)
|
|||
}
|
||||
}
|
||||
|
||||
void uartClearIdleFlag(uartPort_t *s)
|
||||
{
|
||||
USART_ClearITPendingBit(s->USARTx, USART_IT_IDLE);
|
||||
}
|
||||
|
||||
#ifdef USE_UART1
|
||||
void USART1_IRQHandler(void)
|
||||
{
|
||||
|
|
|
@ -253,6 +253,12 @@ void uartGetPortPins(UARTDevice_e device, serialPortPins_t * pins)
|
|||
}
|
||||
}
|
||||
|
||||
void uartClearIdleFlag(uartPort_t *s)
|
||||
{
|
||||
(void) s->USARTx->SR;
|
||||
(void) s->USARTx->DR;
|
||||
}
|
||||
|
||||
uartPort_t *serialUART(UARTDevice_e device, uint32_t baudRate, portMode_t mode, portOptions_t options)
|
||||
{
|
||||
uartPort_t *s;
|
||||
|
|
|
@ -187,7 +187,8 @@ static const struct serialPortVTable usbVTable[] = {
|
|||
.isConnected = usbVcpIsConnected,
|
||||
.writeBuf = usbVcpWriteBuf,
|
||||
.beginWrite = usbVcpBeginWrite,
|
||||
.endWrite = usbVcpEndWrite
|
||||
.endWrite = usbVcpEndWrite,
|
||||
.isIdle = NULL,
|
||||
}
|
||||
};
|
||||
|
||||
|
|
|
@ -85,10 +85,15 @@ void systemReset(void)
|
|||
NVIC_SystemReset();
|
||||
}
|
||||
|
||||
void systemResetRequest(uint32_t requestId)
|
||||
{
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, requestId);
|
||||
systemReset();
|
||||
}
|
||||
|
||||
void systemResetToBootloader(void)
|
||||
{
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_BOOTLOADER_REQUEST_ROM);
|
||||
systemReset();
|
||||
systemResetRequest(RESET_BOOTLOADER_REQUEST_ROM);
|
||||
}
|
||||
|
||||
typedef void resetHandler_t(void);
|
||||
|
|
|
@ -38,6 +38,7 @@ void failureMode(failureMode_e mode);
|
|||
|
||||
// bootloader/IAP
|
||||
void systemReset(void);
|
||||
void systemResetRequest(uint32_t requestId);
|
||||
void systemResetToBootloader(void);
|
||||
uint32_t systemBootloaderAddress(void);
|
||||
bool isMPUSoftReset(void);
|
||||
|
|
|
@ -28,6 +28,8 @@
|
|||
|
||||
#include "drivers/exti.h"
|
||||
|
||||
#include "target/system.h"
|
||||
|
||||
|
||||
void SetSysClock(void);
|
||||
|
||||
|
@ -160,7 +162,6 @@ void systemInit(void)
|
|||
cachedRccCsrValue = RCC->CSR;
|
||||
|
||||
/* Accounts for OP Bootloader, set the Vector Table base address as specified in .ld file */
|
||||
extern void *isr_vector_table_base;
|
||||
NVIC_SetVectorTable((uint32_t)&isr_vector_table_base, 0x0);
|
||||
RCC_AHB2PeriphClockCmd(RCC_AHB2Periph_OTG_FS, DISABLE);
|
||||
|
||||
|
|
|
@ -43,8 +43,7 @@ extern uint8_t __config_end;
|
|||
#include "common/memory.h"
|
||||
#include "common/time.h"
|
||||
#include "common/typeconversion.h"
|
||||
#include "common/global_functions.h"
|
||||
#include "common/global_variables.h"
|
||||
#include "programming/global_variables.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/feature.h"
|
||||
|
@ -811,27 +810,19 @@ static void cliSerial(char *cmdline)
|
|||
|
||||
switch (i) {
|
||||
case 0:
|
||||
if (baudRateIndex < BAUD_1200 || baudRateIndex > BAUD_2470000) {
|
||||
continue;
|
||||
}
|
||||
baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX);
|
||||
portConfig.msp_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 1:
|
||||
if (baudRateIndex < BAUD_9600 || baudRateIndex > BAUD_115200) {
|
||||
continue;
|
||||
}
|
||||
baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX);
|
||||
portConfig.gps_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 2:
|
||||
if (baudRateIndex != BAUD_AUTO && baudRateIndex > BAUD_115200) {
|
||||
continue;
|
||||
}
|
||||
baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX);
|
||||
portConfig.telemetry_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
case 3:
|
||||
if (baudRateIndex < BAUD_19200 || baudRateIndex > BAUD_250000) {
|
||||
continue;
|
||||
}
|
||||
baudRateIndex = constrain(baudRateIndex, BAUD_MIN, BAUD_MAX);
|
||||
portConfig.peripheral_baudrateIndex = baudRateIndex;
|
||||
break;
|
||||
}
|
||||
|
@ -1338,7 +1329,7 @@ static void cliWaypoints(char *cmdline)
|
|||
} else if (sl_strcasecmp(cmdline, "save") == 0) {
|
||||
posControl.waypointListValid = false;
|
||||
for (int i = 0; i < NAV_MAX_WAYPOINTS; i++) {
|
||||
if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND)) break;
|
||||
if (!(posControl.waypointList[i].action == NAV_WP_ACTION_WAYPOINT || posControl.waypointList[i].action == NAV_WP_ACTION_JUMP || posControl.waypointList[i].action == NAV_WP_ACTION_RTH || posControl.waypointList[i].action == NAV_WP_ACTION_HOLD_TIME || posControl.waypointList[i].action == NAV_WP_ACTION_LAND || posControl.waypointList[i].action == NAV_WP_ACTION_SET_POI || posControl.waypointList[i].action == NAV_WP_ACTION_SET_HEAD)) break;
|
||||
if (posControl.waypointList[i].flag == NAV_WP_FLAG_LAST) {
|
||||
posControl.waypointCount = i + 1;
|
||||
posControl.waypointListValid = true;
|
||||
|
@ -1682,7 +1673,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
|
|||
&& customServoMixer.inputSource == customServoMixerDefault.inputSource
|
||||
&& customServoMixer.rate == customServoMixerDefault.rate
|
||||
&& customServoMixer.speed == customServoMixerDefault.speed
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
&& customServoMixer.conditionId == customServoMixerDefault.conditionId
|
||||
#endif
|
||||
;
|
||||
|
@ -1693,7 +1684,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
|
|||
customServoMixerDefault.inputSource,
|
||||
customServoMixerDefault.rate,
|
||||
customServoMixerDefault.speed,
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
customServoMixer.conditionId
|
||||
#else
|
||||
0
|
||||
|
@ -1706,7 +1697,7 @@ static void printServoMix(uint8_t dumpMask, const servoMixer_t *customServoMixer
|
|||
customServoMixer.inputSource,
|
||||
customServoMixer.rate,
|
||||
customServoMixer.speed,
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
customServoMixer.conditionId
|
||||
#else
|
||||
0
|
||||
|
@ -1753,7 +1744,7 @@ static void cliServoMix(char *cmdline)
|
|||
customServoMixersMutable(i)->inputSource = args[INPUT];
|
||||
customServoMixersMutable(i)->rate = args[RATE];
|
||||
customServoMixersMutable(i)->speed = args[SPEED];
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
customServoMixersMutable(i)->conditionId = args[CONDITION];
|
||||
#endif
|
||||
cliServoMix("");
|
||||
|
@ -1763,7 +1754,7 @@ static void cliServoMix(char *cmdline)
|
|||
}
|
||||
}
|
||||
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
|
||||
static void printLogic(uint8_t dumpMask, const logicCondition_t *logicConditions, const logicCondition_t *defaultLogicConditions)
|
||||
{
|
||||
|
@ -1950,104 +1941,6 @@ static void cliGvar(char *cmdline) {
|
|||
|
||||
#endif
|
||||
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
|
||||
static void printGlobalFunctions(uint8_t dumpMask, const globalFunction_t *globalFunctions, const globalFunction_t *defaultGlobalFunctions)
|
||||
{
|
||||
const char *format = "gf %d %d %d %d %d %d %d";
|
||||
for (uint32_t i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
|
||||
const globalFunction_t gf = globalFunctions[i];
|
||||
|
||||
bool equalsDefault = false;
|
||||
if (defaultGlobalFunctions) {
|
||||
globalFunction_t defaultValue = defaultGlobalFunctions[i];
|
||||
equalsDefault =
|
||||
gf.enabled == defaultValue.enabled &&
|
||||
gf.conditionId == defaultValue.conditionId &&
|
||||
gf.action == defaultValue.action &&
|
||||
gf.withValue.type == defaultValue.withValue.type &&
|
||||
gf.withValue.value == defaultValue.withValue.value &&
|
||||
gf.flags == defaultValue.flags;
|
||||
|
||||
cliDefaultPrintLinef(dumpMask, equalsDefault, format,
|
||||
i,
|
||||
gf.enabled,
|
||||
gf.conditionId,
|
||||
gf.action,
|
||||
gf.withValue.type,
|
||||
gf.withValue.value,
|
||||
gf.flags
|
||||
);
|
||||
}
|
||||
cliDumpPrintLinef(dumpMask, equalsDefault, format,
|
||||
i,
|
||||
gf.enabled,
|
||||
gf.conditionId,
|
||||
gf.action,
|
||||
gf.withValue.type,
|
||||
gf.withValue.value,
|
||||
gf.flags
|
||||
);
|
||||
}
|
||||
}
|
||||
|
||||
static void cliGlobalFunctions(char *cmdline) {
|
||||
char * saveptr;
|
||||
int args[7], check = 0;
|
||||
uint8_t len = strlen(cmdline);
|
||||
|
||||
if (len == 0) {
|
||||
printGlobalFunctions(DUMP_MASTER, globalFunctions(0), NULL);
|
||||
} else if (sl_strncasecmp(cmdline, "reset", 5) == 0) {
|
||||
pgResetCopy(globalFunctionsMutable(0), PG_GLOBAL_FUNCTIONS);
|
||||
} else {
|
||||
enum {
|
||||
INDEX = 0,
|
||||
ENABLED,
|
||||
CONDITION_ID,
|
||||
ACTION,
|
||||
VALUE_TYPE,
|
||||
VALUE_VALUE,
|
||||
FLAGS,
|
||||
ARGS_COUNT
|
||||
};
|
||||
char *ptr = strtok_r(cmdline, " ", &saveptr);
|
||||
while (ptr != NULL && check < ARGS_COUNT) {
|
||||
args[check++] = fastA2I(ptr);
|
||||
ptr = strtok_r(NULL, " ", &saveptr);
|
||||
}
|
||||
|
||||
if (ptr != NULL || check != ARGS_COUNT) {
|
||||
cliShowParseError();
|
||||
return;
|
||||
}
|
||||
|
||||
int32_t i = args[INDEX];
|
||||
if (
|
||||
i >= 0 && i < MAX_GLOBAL_FUNCTIONS &&
|
||||
args[ENABLED] >= 0 && args[ENABLED] <= 1 &&
|
||||
args[CONDITION_ID] >= -1 && args[CONDITION_ID] < MAX_LOGIC_CONDITIONS &&
|
||||
args[ACTION] >= 0 && args[ACTION] < GLOBAL_FUNCTION_ACTION_LAST &&
|
||||
args[VALUE_TYPE] >= 0 && args[VALUE_TYPE] < LOGIC_CONDITION_OPERAND_TYPE_LAST &&
|
||||
args[VALUE_VALUE] >= -1000000 && args[VALUE_VALUE] <= 1000000 &&
|
||||
args[FLAGS] >= 0 && args[FLAGS] <= 255
|
||||
|
||||
) {
|
||||
globalFunctionsMutable(i)->enabled = args[ENABLED];
|
||||
globalFunctionsMutable(i)->conditionId = args[CONDITION_ID];
|
||||
globalFunctionsMutable(i)->action = args[ACTION];
|
||||
globalFunctionsMutable(i)->withValue.type = args[VALUE_TYPE];
|
||||
globalFunctionsMutable(i)->withValue.value = args[VALUE_VALUE];
|
||||
globalFunctionsMutable(i)->flags = args[FLAGS];
|
||||
|
||||
cliGlobalFunctions("");
|
||||
} else {
|
||||
cliShowParseError();
|
||||
}
|
||||
}
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
|
||||
static void cliWriteBytes(const uint8_t *buffer, int count)
|
||||
|
@ -2221,7 +2114,7 @@ static void cliFlashRead(char *cmdline)
|
|||
#endif
|
||||
|
||||
#ifdef USE_OSD
|
||||
static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const osdConfig_t *osdConfigDefault, int layout, int item)
|
||||
static void printOsdLayout(uint8_t dumpMask, const osdLayoutsConfig_t *config, const osdLayoutsConfig_t *configDefault, int layout, int item)
|
||||
{
|
||||
// "<layout> <item> <col> <row> <visible>"
|
||||
const char *format = "osd_layout %d %d %d %d %c";
|
||||
|
@ -2229,8 +2122,8 @@ static void printOsdLayout(uint8_t dumpMask, const osdConfig_t *osdConfig, const
|
|||
if (layout >= 0 && layout != ii) {
|
||||
continue;
|
||||
}
|
||||
const uint16_t *layoutItems = osdConfig->item_pos[ii];
|
||||
const uint16_t *defaultLayoutItems = osdConfigDefault->item_pos[ii];
|
||||
const uint16_t *layoutItems = config->item_pos[ii];
|
||||
const uint16_t *defaultLayoutItems = configDefault->item_pos[ii];
|
||||
for (int jj = 0; jj < OSD_ITEM_COUNT; jj++) {
|
||||
if (item >= 0 && item != jj) {
|
||||
continue;
|
||||
|
@ -2322,15 +2215,15 @@ static void cliOsdLayout(char *cmdline)
|
|||
// No args, or just layout or layout and item. If any of them not provided,
|
||||
// it will be the -1 that we used during initialization, so printOsdLayout()
|
||||
// won't use them for filtering.
|
||||
printOsdLayout(DUMP_MASTER, osdConfig(), osdConfig(), layout, item);
|
||||
printOsdLayout(DUMP_MASTER, osdLayoutsConfig(), osdLayoutsConfig(), layout, item);
|
||||
break;
|
||||
case 4:
|
||||
// No visibility provided. Keep the previous one.
|
||||
visible = OSD_VISIBLE(osdConfig()->item_pos[layout][item]);
|
||||
visible = OSD_VISIBLE(osdLayoutsConfig()->item_pos[layout][item]);
|
||||
FALLTHROUGH;
|
||||
case 5:
|
||||
// Layout, item, pos and visibility. Set the item.
|
||||
osdConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0);
|
||||
osdLayoutsConfigMutable()->item_pos[layout][item] = OSD_POS(col, row) | (visible ? OSD_VISIBLE_FLAG : 0);
|
||||
break;
|
||||
default:
|
||||
// Unhandled
|
||||
|
@ -3321,7 +3214,7 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
cliPrintHashLine("servo");
|
||||
printServo(dumpMask, servoParams_CopyArray, servoParams(0));
|
||||
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
cliPrintHashLine("logic");
|
||||
printLogic(dumpMask, logicConditions_CopyArray, logicConditions(0));
|
||||
|
||||
|
@ -3329,11 +3222,6 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
printGvar(dumpMask, globalVariableConfigs_CopyArray, globalVariableConfigs(0));
|
||||
#endif
|
||||
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
cliPrintHashLine("gf");
|
||||
printGlobalFunctions(dumpMask, globalFunctions_CopyArray, globalFunctions(0));
|
||||
#endif
|
||||
|
||||
cliPrintHashLine("feature");
|
||||
printFeature(dumpMask, &featureConfig_Copy, featureConfig());
|
||||
|
||||
|
@ -3380,7 +3268,7 @@ static void printConfig(const char *cmdline, bool doDiff)
|
|||
|
||||
#ifdef USE_OSD
|
||||
cliPrintHashLine("osd_layout");
|
||||
printOsdLayout(dumpMask, &osdConfig_Copy, osdConfig(), -1, -1);
|
||||
printOsdLayout(dumpMask, &osdLayoutsConfig_Copy, osdLayoutsConfig(), -1, -1);
|
||||
#endif
|
||||
|
||||
cliPrintHashLine("master");
|
||||
|
@ -3462,11 +3350,7 @@ static void cliMsc(char *cmdline)
|
|||
delay(1000);
|
||||
waitForSerialPortToFinishTransmitting(cliPort);
|
||||
stopPwmAllMotors();
|
||||
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_MSC_REQUEST);
|
||||
|
||||
__disable_irq();
|
||||
NVIC_SystemReset();
|
||||
systemResetRequest(RESET_MSC_REQUEST);
|
||||
} else {
|
||||
cliPrint("\r\nStorage not present or failed to initialize!");
|
||||
bufWriterFlush(cliWriter);
|
||||
|
@ -3576,7 +3460,7 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("serialpassthrough", "passthrough serial data to port", "<id> [baud] [mode] : passthrough to serial", cliSerialPassthrough),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("servo", "configure servos", NULL, cliServo),
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
CLI_COMMAND_DEF("logic", "configure logic conditions",
|
||||
"<rule> <enabled> <activatorId> <operation> <operand A type> <operand A value> <operand B type> <operand B value> <flags>\r\n"
|
||||
"\treset\r\n", cliLogic),
|
||||
|
@ -3584,11 +3468,6 @@ const clicmd_t cmdTable[] = {
|
|||
CLI_COMMAND_DEF("gvar", "configure global variables",
|
||||
"<gvar> <default> <min> <max>\r\n"
|
||||
"\treset\r\n", cliGvar),
|
||||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
CLI_COMMAND_DEF("gf", "configure global functions",
|
||||
"<rule> <enabled> <logic condition> <action> <operand type> <operand value> <flags>\r\n"
|
||||
"\treset\r\n", cliGlobalFunctions),
|
||||
#endif
|
||||
CLI_COMMAND_DEF("set", "change setting", "[<name>=<value>]", cliSet),
|
||||
CLI_COMMAND_DEF("smix", "servo mixer",
|
||||
|
|
|
@ -167,14 +167,8 @@ uint32_t getLooptime(void) {
|
|||
|
||||
void validateAndFixConfig(void)
|
||||
{
|
||||
if (gyroConfig()->gyro_soft_notch_cutoff_1 >= gyroConfig()->gyro_soft_notch_hz_1) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = 0;
|
||||
}
|
||||
if (gyroConfig()->gyro_soft_notch_cutoff_2 >= gyroConfig()->gyro_soft_notch_hz_2) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_2 = 0;
|
||||
}
|
||||
if (pidProfile()->dterm_soft_notch_cutoff >= pidProfile()->dterm_soft_notch_hz) {
|
||||
pidProfileMutable()->dterm_soft_notch_hz = 0;
|
||||
if (gyroConfig()->gyro_notch_cutoff >= gyroConfig()->gyro_notch_hz) {
|
||||
gyroConfigMutable()->gyro_notch_hz = 0;
|
||||
}
|
||||
if (accelerometerConfig()->acc_notch_cutoff >= accelerometerConfig()->acc_notch_hz) {
|
||||
accelerometerConfigMutable()->acc_notch_hz = 0;
|
||||
|
|
|
@ -32,7 +32,6 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/global_functions.h"
|
||||
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/serial.h"
|
||||
|
@ -446,11 +445,11 @@ void releaseSharedTelemetryPorts(void) {
|
|||
void tryArm(void)
|
||||
{
|
||||
updateArmingStatus();
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (
|
||||
!isArmingDisabled() ||
|
||||
emergencyArmingIsEnabled() ||
|
||||
GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_ARMING_SAFETY)
|
||||
LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_ARMING_SAFETY)
|
||||
) {
|
||||
#else
|
||||
if (
|
||||
|
@ -808,9 +807,6 @@ void taskMainPidLoop(timeUs_t currentTimeUs)
|
|||
// FIXME: throttle pitch comp for FW
|
||||
}
|
||||
|
||||
// Update PID coefficients
|
||||
updatePIDCoefficients(dT);
|
||||
|
||||
// Calculate stabilisation
|
||||
pidController(dT);
|
||||
|
||||
|
|
|
@ -35,7 +35,7 @@
|
|||
#include "common/maths.h"
|
||||
#include "common/memory.h"
|
||||
#include "common/printf.h"
|
||||
#include "common/global_variables.h"
|
||||
#include "programming/global_variables.h"
|
||||
|
||||
#include "config/config_eeprom.h"
|
||||
#include "config/feature.h"
|
||||
|
@ -83,6 +83,7 @@
|
|||
#include "msc/emfat_file.h"
|
||||
#endif
|
||||
#include "drivers/sdcard/sdcard.h"
|
||||
#include "drivers/io_port_expander.h"
|
||||
|
||||
#include "fc/cli.h"
|
||||
#include "fc/config.h"
|
||||
|
@ -90,6 +91,7 @@
|
|||
#include "fc/fc_tasks.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/runtime_config.h"
|
||||
#include "fc/firmware_update.h"
|
||||
|
||||
#include "flight/failsafe.h"
|
||||
#include "flight/imu.h"
|
||||
|
@ -114,6 +116,7 @@
|
|||
#include "io/rcdevice_cam.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/displayport_msp.h"
|
||||
#include "io/smartport_master.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/vtx_control.h"
|
||||
#include "io/vtx_smartaudio.h"
|
||||
|
@ -200,6 +203,8 @@ void init(void)
|
|||
// Initialize system and CPU clocks to their initial values
|
||||
systemInit();
|
||||
|
||||
__enable_irq();
|
||||
|
||||
// initialize IO (needed for all IO operations)
|
||||
IOInitGlobal();
|
||||
|
||||
|
@ -280,13 +285,17 @@ void init(void)
|
|||
djiOsdSerialInit();
|
||||
#endif
|
||||
|
||||
#if defined(USE_SMARTPORT_MASTER)
|
||||
smartportMasterInit();
|
||||
#endif
|
||||
|
||||
#if defined(USE_LOG)
|
||||
// LOG might use serial output, so we only can init it after serial port is ready
|
||||
// From this point on we can use LOG_*() to produce real-time debugging information
|
||||
logInit();
|
||||
#endif
|
||||
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
gvInit();
|
||||
#endif
|
||||
|
||||
|
@ -674,6 +683,10 @@ void init(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_I2C_IO_EXPANDER
|
||||
ioPortExpanderInit();
|
||||
#endif
|
||||
|
||||
// Considering that the persistent reset reason is only used during init
|
||||
persistentObjectWrite(PERSISTENT_OBJECT_RESET_REASON, RESET_NONE);
|
||||
|
||||
|
|
|
@ -35,8 +35,7 @@
|
|||
#include "common/bitarray.h"
|
||||
#include "common/time.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/global_functions.h"
|
||||
#include "common/global_variables.h"
|
||||
#include "programming/global_variables.h"
|
||||
|
||||
#include "config/parameter_group_ids.h"
|
||||
|
||||
|
@ -60,6 +59,7 @@
|
|||
#include "fc/controlrate_profile.h"
|
||||
#include "fc/fc_msp.h"
|
||||
#include "fc/fc_msp_box.h"
|
||||
#include "fc/firmware_update.h"
|
||||
#include "fc/rc_adjustments.h"
|
||||
#include "fc/rc_controls.h"
|
||||
#include "fc/rc_modes.h"
|
||||
|
@ -520,14 +520,14 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, customServoMixers(i)->inputSource);
|
||||
sbufWriteU16(dst, customServoMixers(i)->rate);
|
||||
sbufWriteU8(dst, customServoMixers(i)->speed);
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
sbufWriteU8(dst, customServoMixers(i)->conditionId);
|
||||
#else
|
||||
sbufWriteU8(dst, -1);
|
||||
#endif
|
||||
}
|
||||
break;
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
case MSP2_INAV_LOGIC_CONDITIONS:
|
||||
for (int i = 0; i < MAX_LOGIC_CONDITIONS; i++) {
|
||||
sbufWriteU8(dst, logicConditions(i)->enabled);
|
||||
|
@ -550,18 +550,6 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU32(dst, gvGet(i));
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
case MSP2_INAV_GLOBAL_FUNCTIONS:
|
||||
for (int i = 0; i < MAX_GLOBAL_FUNCTIONS; i++) {
|
||||
sbufWriteU8(dst, globalFunctions(i)->enabled);
|
||||
sbufWriteU8(dst, globalFunctions(i)->conditionId);
|
||||
sbufWriteU8(dst, globalFunctions(i)->action);
|
||||
sbufWriteU8(dst, globalFunctions(i)->withValue.type);
|
||||
sbufWriteU32(dst, globalFunctions(i)->withValue.value);
|
||||
sbufWriteU8(dst, logicConditions(i)->flags);
|
||||
}
|
||||
break;
|
||||
#endif
|
||||
case MSP2_COMMON_MOTOR_MIXER:
|
||||
for (uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||
|
@ -1104,7 +1092,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU16(dst, osdConfig()->dist_alarm);
|
||||
sbufWriteU16(dst, osdConfig()->neg_alt_alarm);
|
||||
for (int i = 0; i < OSD_ITEM_COUNT; i++) {
|
||||
sbufWriteU16(dst, osdConfig()->item_pos[0][i]);
|
||||
sbufWriteU16(dst, osdLayoutsConfig()->item_pos[0][i]);
|
||||
}
|
||||
#else
|
||||
sbufWriteU8(dst, OSD_DRIVER_NONE); // OSD not supported
|
||||
|
@ -1155,14 +1143,13 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, gyroConfig()->gyro_soft_lpf_hz);
|
||||
sbufWriteU16(dst, pidProfile()->dterm_lpf_hz);
|
||||
sbufWriteU16(dst, pidProfile()->yaw_lpf_hz);
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_1); //masterConfig.gyro_soft_notch_hz_1
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_1); //BF: masterConfig.gyro_soft_notch_cutoff_1
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_notch_hz);
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_notch_cutoff);
|
||||
sbufWriteU16(dst, 0); //BF: pidProfile()->dterm_notch_hz
|
||||
sbufWriteU16(dst, 1); //pidProfile()->dterm_notch_cutoff
|
||||
|
||||
sbufWriteU16(dst, pidProfile()->dterm_soft_notch_hz); //BF: pidProfile()->dterm_notch_hz
|
||||
sbufWriteU16(dst, pidProfile()->dterm_soft_notch_cutoff); //pidProfile()->dterm_notch_cutoff
|
||||
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_hz_2); //BF: masterConfig.gyro_soft_notch_hz_2
|
||||
sbufWriteU16(dst, gyroConfig()->gyro_soft_notch_cutoff_2); //BF: masterConfig.gyro_soft_notch_cutoff_2
|
||||
sbufWriteU16(dst, 0); //BF: masterConfig.gyro_soft_notch_hz_2
|
||||
sbufWriteU16(dst, 1); //BF: masterConfig.gyro_soft_notch_cutoff_2
|
||||
|
||||
sbufWriteU16(dst, accelerometerConfig()->acc_notch_hz);
|
||||
sbufWriteU16(dst, accelerometerConfig()->acc_notch_cutoff);
|
||||
|
@ -1177,7 +1164,7 @@ static bool mspFcProcessOutCommand(uint16_t cmdMSP, sbuf_t *dst, mspPostProcessF
|
|||
sbufWriteU8(dst, 0); //BF: pidProfile()->deltaMethod
|
||||
sbufWriteU8(dst, 0); //BF: pidProfile()->vbatPidCompensation
|
||||
sbufWriteU8(dst, 0); //BF: pidProfile()->setpointRelaxRatio
|
||||
sbufWriteU8(dst, constrain(pidProfile()->dterm_setpoint_weight * 100, 0, 255));
|
||||
sbufWriteU8(dst, 0);
|
||||
sbufWriteU16(dst, pidProfile()->pidSumLimit);
|
||||
sbufWriteU8(dst, 0); //BF: pidProfile()->itermThrottleGain
|
||||
|
||||
|
@ -1929,7 +1916,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
customServoMixersMutable(tmp_u8)->inputSource = sbufReadU8(src);
|
||||
customServoMixersMutable(tmp_u8)->rate = sbufReadU16(src);
|
||||
customServoMixersMutable(tmp_u8)->speed = sbufReadU8(src);
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
customServoMixersMutable(tmp_u8)->conditionId = sbufReadU8(src);
|
||||
#else
|
||||
sbufReadU8(src);
|
||||
|
@ -1938,7 +1925,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
case MSP2_INAV_SET_LOGIC_CONDITIONS:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 15) && (tmp_u8 < MAX_LOGIC_CONDITIONS)) {
|
||||
|
@ -1953,20 +1940,6 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
case MSP2_INAV_SET_GLOBAL_FUNCTIONS:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
if ((dataSize == 10) && (tmp_u8 < MAX_GLOBAL_FUNCTIONS)) {
|
||||
globalFunctionsMutable(tmp_u8)->enabled = sbufReadU8(src);
|
||||
globalFunctionsMutable(tmp_u8)->conditionId = sbufReadU8(src);
|
||||
globalFunctionsMutable(tmp_u8)->action = sbufReadU8(src);
|
||||
globalFunctionsMutable(tmp_u8)->withValue.type = sbufReadU8(src);
|
||||
globalFunctionsMutable(tmp_u8)->withValue.value = sbufReadU32(src);
|
||||
globalFunctionsMutable(tmp_u8)->flags = sbufReadU8(src);
|
||||
} else
|
||||
return MSP_RESULT_ERROR;
|
||||
break;
|
||||
#endif
|
||||
case MSP2_COMMON_SET_MOTOR_MIXER:
|
||||
sbufReadU8Safe(&tmp_u8, src);
|
||||
|
@ -2039,21 +2012,21 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
pidProfileMutable()->dterm_lpf_hz = constrain(sbufReadU16(src), 0, 500);
|
||||
pidProfileMutable()->yaw_lpf_hz = constrain(sbufReadU16(src), 0, 255);
|
||||
if (dataSize >= 9) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_1 = constrain(sbufReadU16(src), 0, 500);
|
||||
gyroConfigMutable()->gyro_soft_notch_cutoff_1 = constrain(sbufReadU16(src), 1, 500);
|
||||
gyroConfigMutable()->gyro_notch_hz = constrain(sbufReadU16(src), 0, 500);
|
||||
gyroConfigMutable()->gyro_notch_cutoff = constrain(sbufReadU16(src), 1, 500);
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
if (dataSize >= 13) {
|
||||
pidProfileMutable()->dterm_soft_notch_hz = constrain(sbufReadU16(src), 0, 500);
|
||||
pidProfileMutable()->dterm_soft_notch_cutoff = constrain(sbufReadU16(src), 1, 500);
|
||||
sbufReadU16(src);
|
||||
sbufReadU16(src);
|
||||
pidInitFilters();
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
if (dataSize >= 17) {
|
||||
gyroConfigMutable()->gyro_soft_notch_hz_2 = constrain(sbufReadU16(src), 0, 500);
|
||||
gyroConfigMutable()->gyro_soft_notch_cutoff_2 = constrain(sbufReadU16(src), 1, 500);
|
||||
sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_hz_2
|
||||
sbufReadU16(src); // Was gyroConfigMutable()->gyro_soft_notch_cutoff_2
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
@ -2083,7 +2056,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
sbufReadU8(src); //BF: pidProfileMutable()->deltaMethod
|
||||
sbufReadU8(src); //BF: pidProfileMutable()->vbatPidCompensation
|
||||
sbufReadU8(src); //BF: pidProfileMutable()->setpointRelaxRatio
|
||||
pidProfileMutable()->dterm_setpoint_weight = constrainf(sbufReadU8(src) / 100.0f, 0.0f, 2.0f);
|
||||
sbufReadU8(src);
|
||||
pidProfileMutable()->pidSumLimit = sbufReadU16(src);
|
||||
sbufReadU8(src); //BF: pidProfileMutable()->itermThrottleGain
|
||||
|
||||
|
@ -2308,7 +2281,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
} else {
|
||||
// set a position setting
|
||||
if ((dataSize >= 3) && (tmp_u8 < OSD_ITEM_COUNT)) // tmp_u8 == addr
|
||||
osdConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src);
|
||||
osdLayoutsConfigMutable()->item_pos[0][tmp_u8] = sbufReadU16(src);
|
||||
else
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
@ -2602,10 +2575,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
|
||||
portConfig->identifier = identifier;
|
||||
portConfig->functionMask = sbufReadU16(src);
|
||||
portConfig->msp_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->gps_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->telemetry_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->peripheral_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->msp_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->gps_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->telemetry_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->peripheral_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -2630,10 +2603,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
|
||||
portConfig->identifier = identifier;
|
||||
portConfig->functionMask = sbufReadU32(src);
|
||||
portConfig->msp_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->gps_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->telemetry_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->peripheral_baudrateIndex = sbufReadU8(src);
|
||||
portConfig->msp_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->gps_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->telemetry_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
portConfig->peripheral_baudrateIndex = constrain(sbufReadU8(src), BAUD_MIN, BAUD_MAX);
|
||||
}
|
||||
}
|
||||
break;
|
||||
|
@ -2755,7 +2728,7 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
if (!sbufReadU8Safe(&item, src)) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
if (!sbufReadU16Safe(&osdConfigMutable()->item_pos[layout][item], src)) {
|
||||
if (!sbufReadU16Safe(&osdLayoutsConfigMutable()->item_pos[layout][item], src)) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
// If the layout is not already overriden and it's different
|
||||
|
@ -2836,9 +2809,10 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
|
||||
case MSP2_INAV_SELECT_BATTERY_PROFILE:
|
||||
if (!ARMING_FLAG(ARMED)) {
|
||||
if (sbufReadU8Safe(&tmp_u8, src))
|
||||
if (!ARMING_FLAG(ARMED) && sbufReadU8Safe(&tmp_u8, src)) {
|
||||
setConfigBatteryProfileAndWriteEEPROM(tmp_u8);
|
||||
} else {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
|
||||
|
@ -2862,6 +2836,32 @@ static mspResult_e mspFcProcessInCommand(uint16_t cmdMSP, sbuf_t *src)
|
|||
break;
|
||||
#endif
|
||||
|
||||
#ifdef MSP_FIRMWARE_UPDATE
|
||||
case MSP2_INAV_FWUPDT_PREPARE:
|
||||
if (!firmwareUpdatePrepare(sbufReadU32(src))) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
case MSP2_INAV_FWUPDT_STORE:
|
||||
if (!firmwareUpdateStore(sbufPtr(src), sbufBytesRemaining(src))) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
case MSP2_INAV_FWUPDT_EXEC:
|
||||
firmwareUpdateExec(sbufReadU8(src));
|
||||
return MSP_RESULT_ERROR; // will only be reached if the update is not ready
|
||||
break;
|
||||
case MSP2_INAV_FWUPDT_ROLLBACK_PREPARE:
|
||||
if (!firmwareUpdateRollbackPrepare()) {
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
break;
|
||||
case MSP2_INAV_FWUPDT_ROLLBACK_EXEC:
|
||||
firmwareUpdateRollbackExec();
|
||||
return MSP_RESULT_ERROR; // will only be reached if the rollback is not ready
|
||||
break;
|
||||
#endif
|
||||
|
||||
default:
|
||||
return MSP_RESULT_ERROR;
|
||||
}
|
||||
|
@ -3148,11 +3148,11 @@ bool mspFCProcessInOutCommand(uint16_t cmdMSP, sbuf_t *dst, sbuf_t *src, mspResu
|
|||
*ret = MSP_RESULT_ERROR;
|
||||
break;
|
||||
}
|
||||
sbufWriteU16(dst, osdConfig()->item_pos[layout][item]);
|
||||
sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][item]);
|
||||
} else {
|
||||
// Asking for an specific layout
|
||||
for (unsigned ii = 0; ii < OSD_ITEM_COUNT; ii++) {
|
||||
sbufWriteU16(dst, osdConfig()->item_pos[layout][ii]);
|
||||
sbufWriteU16(dst, osdLayoutsConfig()->item_pos[layout][ii]);
|
||||
}
|
||||
}
|
||||
} else {
|
||||
|
|
|
@ -189,7 +189,7 @@ void initActiveBoxIds(void)
|
|||
activeBoxIds[activeBoxIdCount++] = BOXCAMSTAB;
|
||||
|
||||
#ifdef USE_GPS
|
||||
if (STATE(ALTITUDE_CONTROL) && (sensors(SENSOR_BARO) || (STATE(AIRPLANE) && feature(FEATURE_GPS)))) {
|
||||
if (STATE(ALTITUDE_CONTROL) && (sensors(SENSOR_BARO) || (feature(FEATURE_GPS) && (STATE(AIRPLANE) || positionEstimationConfig()->use_gps_no_baro)))) {
|
||||
activeBoxIds[activeBoxIdCount++] = BOXNAVALTHOLD;
|
||||
activeBoxIds[activeBoxIdCount++] = BOXSURFACE;
|
||||
}
|
||||
|
|
|
@ -26,8 +26,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/color.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/logic_condition.h"
|
||||
#include "common/global_functions.h"
|
||||
#include "programming/programming_task.h"
|
||||
|
||||
#include "drivers/accgyro/accgyro.h"
|
||||
#include "drivers/compass/compass.h"
|
||||
|
@ -62,6 +61,7 @@
|
|||
#include "io/pwmdriver_i2c.h"
|
||||
#include "io/serial.h"
|
||||
#include "io/rcdevice_cam.h"
|
||||
#include "io/smartport_master.h"
|
||||
#include "io/vtx.h"
|
||||
#include "io/osd_dji_hd.h"
|
||||
#include "io/servo_sbus.h"
|
||||
|
@ -252,6 +252,13 @@ void taskTelemetry(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
#if defined(USE_SMARTPORT_MASTER)
|
||||
void taskSmartportMaster(timeUs_t currentTimeUs)
|
||||
{
|
||||
smartportMasterHandle(currentTimeUs);
|
||||
}
|
||||
#endif
|
||||
|
||||
#ifdef USE_LED_STRIP
|
||||
void taskLedStrip(timeUs_t currentTimeUs)
|
||||
{
|
||||
|
@ -283,12 +290,19 @@ void taskUpdateOsd(timeUs_t currentTimeUs)
|
|||
}
|
||||
#endif
|
||||
|
||||
void taskUpdateAux(timeUs_t currentTimeUs)
|
||||
{
|
||||
UNUSED(currentTimeUs);
|
||||
updatePIDCoefficients();
|
||||
}
|
||||
|
||||
void fcTasksInit(void)
|
||||
{
|
||||
schedulerInit();
|
||||
|
||||
rescheduleTask(TASK_GYROPID, getLooptime());
|
||||
setTaskEnabled(TASK_GYROPID, true);
|
||||
setTaskEnabled(TASK_AUX, true);
|
||||
|
||||
setTaskEnabled(TASK_SERIAL, true);
|
||||
#ifdef BEEPER
|
||||
|
@ -355,15 +369,15 @@ void fcTasksInit(void)
|
|||
#ifdef USE_RCDEVICE
|
||||
setTaskEnabled(TASK_RCDEVICE, rcdeviceIsEnabled());
|
||||
#endif
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
setTaskEnabled(TASK_LOGIC_CONDITIONS, true);
|
||||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
setTaskEnabled(TASK_GLOBAL_FUNCTIONS, true);
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
setTaskEnabled(TASK_PROGRAMMING_FRAMEWORK, true);
|
||||
#endif
|
||||
#ifdef USE_IRLOCK
|
||||
setTaskEnabled(TASK_IRLOCK, irlockHasBeenDetected());
|
||||
#endif
|
||||
#if defined(USE_SMARTPORT_MASTER)
|
||||
setTaskEnabled(TASK_SMARTPORT_MASTER, true);
|
||||
#endif
|
||||
}
|
||||
|
||||
cfTask_t cfTasks[TASK_COUNT] = {
|
||||
|
@ -498,6 +512,15 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
},
|
||||
#endif
|
||||
|
||||
#if defined(USE_SMARTPORT_MASTER)
|
||||
[TASK_SMARTPORT_MASTER] = {
|
||||
.taskName = "SPORT MASTER",
|
||||
.taskFunc = taskSmartportMaster,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(500), // 500 Hz
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
|
||||
#ifdef USE_LED_STRIP
|
||||
[TASK_LEDSTRIP] = {
|
||||
.taskName = "LEDSTRIP",
|
||||
|
@ -578,18 +601,10 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
[TASK_LOGIC_CONDITIONS] = {
|
||||
.taskName = "LOGIC",
|
||||
.taskFunc = logicConditionUpdateTask,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
#endif
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
[TASK_GLOBAL_FUNCTIONS] = {
|
||||
.taskName = "G_FNK",
|
||||
.taskFunc = globalFunctionsUpdateTask,
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
[TASK_PROGRAMMING_FRAMEWORK] = {
|
||||
.taskName = "PROGRAMMING",
|
||||
.taskFunc = programmingFrameworkUpdateTask,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(10), // 10Hz @100msec
|
||||
.staticPriority = TASK_PRIORITY_IDLE,
|
||||
},
|
||||
|
@ -602,4 +617,10 @@ cfTask_t cfTasks[TASK_COUNT] = {
|
|||
.staticPriority = TASK_PRIORITY_LOW,
|
||||
},
|
||||
#endif
|
||||
[TASK_AUX] = {
|
||||
.taskName = "AUX",
|
||||
.taskFunc = taskUpdateAux,
|
||||
.desiredPeriod = TASK_PERIOD_HZ(TASK_AUX_RATE_HZ), // 300Hz @3,33ms
|
||||
.staticPriority = TASK_PRIORITY_HIGH,
|
||||
},
|
||||
};
|
||||
|
|
318
src/main/fc/firmware_update.c
Normal file
318
src/main/fc/firmware_update.c
Normal file
|
@ -0,0 +1,318 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
#include <string.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/crc.h"
|
||||
|
||||
#include "drivers/flash.h"
|
||||
#include "drivers/light_led.h"
|
||||
#include "drivers/persistent.h"
|
||||
#include "drivers/system.h"
|
||||
|
||||
#include "fc/firmware_update.h"
|
||||
#include "fc/firmware_update_common.h"
|
||||
#include "fc/runtime_config.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
|
||||
|
||||
#ifdef MSP_FIRMWARE_UPDATE
|
||||
|
||||
#if !(defined(USE_FLASHFS) || defined(USE_SDCARD))
|
||||
#error No storage backend available
|
||||
#endif
|
||||
|
||||
static firmwareUpdateMetadata_t updateMetadata;
|
||||
static uint8_t updateFirmwareCalcCRC = 0;
|
||||
static uint32_t receivedSize = 0;
|
||||
static bool rollbackPrepared = false;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
static uint32_t firmwareSize;
|
||||
static afatfsFilePtr_t updateFile = NULL;
|
||||
static afatfsFilePtr_t backupFile = NULL;
|
||||
|
||||
static void updateFileOpenCallback(afatfsFilePtr_t file)
|
||||
{
|
||||
updateFile = file;
|
||||
}
|
||||
|
||||
static void backupFileOpenCallback(afatfsFilePtr_t file)
|
||||
{
|
||||
backupFile = file;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
static uint32_t flashStartAddress, flashOverflowAddress;
|
||||
|
||||
#endif
|
||||
|
||||
static bool fullBackup(void)
|
||||
{
|
||||
const uint8_t *const backupSrcEnd = (const uint8_t*)FLASH_END;
|
||||
uint8_t *backupSrcPtr = (uint8_t*)&__firmware_start;
|
||||
uint32_t counter = 0;
|
||||
updateMetadata.backupCRC = 0;
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_BACKUP_FILENAME, "w+", backupFileOpenCallback)) return false;
|
||||
|
||||
while (backupSrcPtr < backupSrcEnd) {
|
||||
|
||||
const uint16_t writeBlockSize = 512;
|
||||
uint32_t justWritten = afatfs_fwriteSync(backupFile, backupSrcPtr, writeBlockSize);
|
||||
updateMetadata.backupCRC = crc8_dvb_s2_update(updateMetadata.backupCRC, backupSrcPtr, justWritten);
|
||||
|
||||
afatfs_poll();
|
||||
backupSrcPtr += justWritten;
|
||||
|
||||
if (++counter % (50*1024/512) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
afatfs_fcloseSync(backupFile);
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FULL_BACKUP);
|
||||
if (!flashPartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
const uint32_t flashSectorSize = flashGeometry->sectorSize;
|
||||
const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashSectorSize;
|
||||
const uint32_t backupSize = AVAILABLE_FIRMWARE_SPACE;
|
||||
if (backupSize > flashPartitionSize) return false;
|
||||
|
||||
uint32_t flashAddress = flashPartition->startSector * flashSectorSize;
|
||||
|
||||
const uint32_t flashPageSize = flashGeometry->pageSize;
|
||||
while (backupSrcPtr < backupSrcEnd) {
|
||||
|
||||
if (flashAddress % flashSectorSize == 0) {
|
||||
flashEraseSector(flashAddress);
|
||||
flashWaitForReady(1000);
|
||||
}
|
||||
|
||||
flashPageProgram(flashAddress, backupSrcPtr, flashPageSize);
|
||||
updateMetadata.backupCRC = crc8_dvb_s2_update(updateMetadata.backupCRC, backupSrcPtr, flashPageSize);
|
||||
|
||||
flashAddress += flashPageSize;
|
||||
backupSrcPtr += flashPageSize;
|
||||
|
||||
if (++counter % (10*1024/256) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
static bool backupIsValid(void)
|
||||
{
|
||||
if (!firmwareUpdateMetadataRead(&updateMetadata) || (updateMetadata.magic != FIRMWARE_UPDATE_METADATA_MAGIC)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
LED0_OFF;
|
||||
LED1_OFF;
|
||||
|
||||
uint32_t counter = 0;
|
||||
uint8_t calcCRC = 0;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
#define SD_BACKUP_FILE_BLOCK_READ_SIZE 512
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_BACKUP_FILENAME, "w+", backupFileOpenCallback)) return false;
|
||||
|
||||
uint32_t totalRead = 0;
|
||||
|
||||
uint8_t buffer[SD_BACKUP_FILE_BLOCK_READ_SIZE];
|
||||
while (!afatfs_feof(backupFile)) {
|
||||
|
||||
uint32_t readBytes = afatfs_freadSync(backupFile, buffer, SD_BACKUP_FILE_BLOCK_READ_SIZE);
|
||||
calcCRC = crc8_dvb_s2_update(calcCRC, buffer, readBytes);
|
||||
|
||||
totalRead += readBytes;
|
||||
|
||||
if (++counter % (50*1024/SD_BACKUP_FILE_BLOCK_READ_SIZE) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
afatfs_fcloseSync(backupFile);
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FULL_BACKUP);
|
||||
if (!flashPartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
const uint32_t flashSectorSize = flashGeometry->sectorSize;
|
||||
const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashSectorSize;
|
||||
const uint32_t backupSize = FLASH_END - (uint32_t)&__firmware_start;
|
||||
if (backupSize > flashPartitionSize) return false;
|
||||
|
||||
uint32_t flashAddress = flashPartition->startSector * flashSectorSize;
|
||||
const uint32_t flashEndAddress = flashAddress + backupSize;
|
||||
|
||||
uint8_t buffer[256];
|
||||
while (flashAddress < flashEndAddress) {
|
||||
|
||||
flashReadBytes(flashAddress, buffer, sizeof(buffer));
|
||||
calcCRC = crc8_dvb_s2_update(calcCRC, buffer, sizeof(buffer));
|
||||
|
||||
flashAddress += sizeof(buffer);
|
||||
|
||||
if (++counter % (10*1024/256) == 0) {
|
||||
LED0_TOGGLE;
|
||||
LED1_TOGGLE;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return (calcCRC == updateMetadata.backupCRC);
|
||||
}
|
||||
|
||||
bool firmwareUpdatePrepare(uint32_t updateSize)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED) || (updateSize > AVAILABLE_FIRMWARE_SPACE)) return false;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY) || !afatfs_fopen(FIRMWARE_UPDATE_FIRMWARE_FILENAME, "w+", updateFileOpenCallback)) return false;
|
||||
|
||||
firmwareSize = updateSize;
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartition_t *flashUpdatePartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_UPDATE_FIRMWARE);
|
||||
if (!flashUpdatePartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
|
||||
flashStartAddress = flashUpdatePartition->startSector * flashGeometry->sectorSize;
|
||||
flashOverflowAddress = ((flashUpdatePartition->endSector + 1) * flashGeometry->sectorSize);
|
||||
receivedSize = 0;
|
||||
|
||||
uint32_t partitionSize = (flashUpdatePartition->endSector - flashUpdatePartition->startSector + 1) * (flashGeometry->sectorSize * flashGeometry->pageSize);
|
||||
|
||||
if (updateSize > partitionSize) {
|
||||
return false;
|
||||
}
|
||||
|
||||
updateMetadata.firmwareSize = updateSize;
|
||||
|
||||
#endif
|
||||
|
||||
updateFirmwareCalcCRC = 0;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool firmwareUpdateStore(uint8_t *data, uint16_t length)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
|
||||
if (!updateFile || !firmwareSize || (receivedSize + length > firmwareSize)
|
||||
|| (afatfs_fwriteSync(updateFile, data, length) != length)) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
if (!updateMetadata.firmwareSize || (receivedSize + length > updateMetadata.firmwareSize)) return false;
|
||||
|
||||
const uint32_t flashAddress = flashStartAddress + receivedSize;
|
||||
|
||||
if ((flashAddress + length > flashOverflowAddress) || (receivedSize + length > updateMetadata.firmwareSize)) {
|
||||
updateMetadata.firmwareSize = 0;
|
||||
return false;
|
||||
}
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
const uint32_t flashSectorSize = flashGeometry->sectorSize;
|
||||
|
||||
if (flashAddress % flashSectorSize == 0) {
|
||||
flashEraseSector(flashAddress);
|
||||
flashWaitForReady(1000);
|
||||
}
|
||||
|
||||
flashPageProgram(flashAddress, data, length);
|
||||
|
||||
#endif
|
||||
|
||||
updateFirmwareCalcCRC = crc8_dvb_s2_update(updateFirmwareCalcCRC, data, length);
|
||||
receivedSize += length;
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
void firmwareUpdateExec(uint8_t expectCRC)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED)) return;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
if (!afatfs_fclose(updateFile, NULL)) return;
|
||||
if (firmwareSize && (receivedSize == firmwareSize) &&
|
||||
(updateFirmwareCalcCRC == expectCRC) && fullBackup() && firmwareUpdateMetadataWrite(&updateMetadata)) {
|
||||
systemResetRequest(RESET_BOOTLOADER_FIRMWARE_UPDATE);
|
||||
}
|
||||
#elif defined(USE_FLASHFS)
|
||||
if (updateMetadata.firmwareSize && (receivedSize == updateMetadata.firmwareSize) &&
|
||||
(updateFirmwareCalcCRC == expectCRC) && fullBackup() && firmwareUpdateMetadataWrite(&updateMetadata)) {
|
||||
systemResetRequest(RESET_BOOTLOADER_FIRMWARE_UPDATE);
|
||||
}
|
||||
#endif
|
||||
|
||||
}
|
||||
|
||||
bool firmwareUpdateRollbackPrepare(void)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED) || !(rollbackPrepared || backupIsValid())) return false;
|
||||
|
||||
rollbackPrepared = true;
|
||||
return true;
|
||||
}
|
||||
|
||||
void firmwareUpdateRollbackExec(void)
|
||||
{
|
||||
if (ARMING_FLAG(ARMED) || !firmwareUpdateRollbackPrepare()) return;
|
||||
|
||||
systemResetRequest(RESET_BOOTLOADER_FIRMWARE_ROLLBACK);
|
||||
}
|
||||
|
||||
#endif
|
29
src/main/fc/firmware_update.h
Normal file
29
src/main/fc/firmware_update.h
Normal file
|
@ -0,0 +1,29 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
bool firmwareUpdatePrepare(uint32_t firmwareSize);
|
||||
bool firmwareUpdateStore(uint8_t *data, uint16_t length);
|
||||
void firmwareUpdateExec(uint8_t expectCRC);
|
||||
bool firmwareUpdateRollbackPrepare(void);
|
||||
void firmwareUpdateRollbackExec(void);
|
||||
|
||||
bool writeMeta(void); // XXX temp
|
87
src/main/fc/firmware_update_common.c
Normal file
87
src/main/fc/firmware_update_common.c
Normal file
|
@ -0,0 +1,87 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#include "common/log.h"
|
||||
|
||||
#include "drivers/flash.h"
|
||||
|
||||
#include "fc/firmware_update_common.h"
|
||||
|
||||
#include "io/asyncfatfs/asyncfatfs.h"
|
||||
|
||||
#ifdef MSP_FIRMWARE_UPDATE
|
||||
|
||||
#if !(defined(USE_FLASHFS) || defined(USE_SDCARD))
|
||||
#error No storage backend available
|
||||
#endif
|
||||
|
||||
#ifdef USE_SDCARD
|
||||
static afatfsFilePtr_t metaFile = NULL;
|
||||
|
||||
static void metaFileOpenCallback(afatfsFilePtr_t file)
|
||||
{
|
||||
metaFile = file;
|
||||
}
|
||||
#endif
|
||||
|
||||
bool firmwareUpdateMetadataRead(firmwareUpdateMetadata_t *updateMetadata)
|
||||
{
|
||||
#if defined(USE_SDCARD)
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY)
|
||||
|| !afatfs_fopen(FIRMWARE_UPDATE_META_FILENAME, "r", metaFileOpenCallback)
|
||||
|| (afatfs_freadSync(metaFile, (uint8_t *)updateMetadata, sizeof(*updateMetadata)) != sizeof(*updateMetadata))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META);
|
||||
if (!flashPartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
uint32_t flashAddress = flashPartition->startSector * flashGeometry->sectorSize;
|
||||
|
||||
if (!flashReadBytes(flashAddress, (uint8_t *)updateMetadata, sizeof(*updateMetadata))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
bool firmwareUpdateMetadataWrite(firmwareUpdateMetadata_t *updateMetadata)
|
||||
{
|
||||
updateMetadata->magic = FIRMWARE_UPDATE_METADATA_MAGIC;
|
||||
|
||||
#if defined(USE_SDCARD)
|
||||
if ((afatfs_getFilesystemState() != AFATFS_FILESYSTEM_STATE_READY)
|
||||
|| !afatfs_fopen(FIRMWARE_UPDATE_META_FILENAME, "w+", metaFileOpenCallback)
|
||||
|| (afatfs_fwriteSync(metaFile, (uint8_t *)updateMetadata, sizeof(*updateMetadata)) != sizeof(*updateMetadata))) {
|
||||
return false;
|
||||
}
|
||||
|
||||
afatfs_fcloseSync(metaFile);
|
||||
|
||||
#elif defined(USE_FLASHFS)
|
||||
flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_FIRMWARE_UPDATE_META);
|
||||
if (!flashPartition) return false;
|
||||
|
||||
const flashGeometry_t *flashGeometry = flashGetGeometry();
|
||||
const uint32_t flashPartitionSize = (flashPartition->endSector - flashPartition->startSector + 1) * flashGeometry->sectorSize;
|
||||
uint32_t flashAddress = flashPartition->startSector * flashGeometry->sectorSize;
|
||||
|
||||
if (flashPartitionSize < sizeof(*updateMetadata)) return false;
|
||||
|
||||
flashEraseSector(flashAddress);
|
||||
flashWaitForReady(1000);
|
||||
flashPageProgram(flashAddress, (uint8_t *)updateMetadata, sizeof(*updateMetadata));
|
||||
|
||||
#endif
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
#endif
|
55
src/main/fc/firmware_update_common.h
Normal file
55
src/main/fc/firmware_update_common.h
Normal file
|
@ -0,0 +1,55 @@
|
|||
/*
|
||||
* This file is part of iNav.
|
||||
*
|
||||
* iNav is free software. You can redistribute this software
|
||||
* and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* iNav is distributed in the hope that they will be
|
||||
* useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#include <stdint.h>
|
||||
|
||||
#include "platform.h"
|
||||
|
||||
#define FIRMWARE_UPDATE_FIRMWARE_FILENAME "firmware.upt"
|
||||
#define FIRMWARE_UPDATE_BACKUP_FILENAME "firmware.bak"
|
||||
#define FIRMWARE_UPDATE_META_FILENAME "update.mta"
|
||||
|
||||
#define FIRMWARE_UPDATE_METADATA_MAGIC 0xAABBCCDD
|
||||
|
||||
#undef FLASH_END
|
||||
|
||||
#define FIRMWARE_START_ADDRESS ((uint32_t)&__firmware_start)
|
||||
#define FLASH_START_ADDRESS 0x08000000UL
|
||||
#define FLASH_END (FLASH_START_ADDRESS + FLASH_SIZE * 1024)
|
||||
#define CONFIG_START_ADDRESS ((uint32_t)&__config_start)
|
||||
#define CONFIG_END_ADDRESS ((uint32_t)&__config_end)
|
||||
|
||||
#define AVAILABLE_FIRMWARE_SPACE (FLASH_END - FIRMWARE_START_ADDRESS)
|
||||
|
||||
extern uint8_t __firmware_start; // set via linker
|
||||
extern uint8_t __config_start;
|
||||
extern uint8_t __config_end;
|
||||
|
||||
typedef struct {
|
||||
uint32_t magic;
|
||||
#ifdef USE_FLASHFS
|
||||
uint32_t firmwareSize;
|
||||
bool dataFlashErased;
|
||||
#endif
|
||||
uint8_t backupCRC;
|
||||
} firmwareUpdateMetadata_t;
|
||||
|
||||
bool firmwareUpdateMetadataRead(firmwareUpdateMetadata_t *updateMetadata);
|
||||
bool firmwareUpdateMetadataWrite(firmwareUpdateMetadata_t *updateMetadata);
|
File diff suppressed because it is too large
Load diff
126
src/main/flight/kalman.c
Executable file
126
src/main/flight/kalman.c
Executable file
|
@ -0,0 +1,126 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
#include "platform.h"
|
||||
#ifdef USE_GYRO_KALMAN
|
||||
|
||||
FILE_COMPILE_FOR_SPEED
|
||||
|
||||
#include <string.h>
|
||||
#include "arm_math.h"
|
||||
|
||||
#include "kalman.h"
|
||||
#include "build/debug.h"
|
||||
|
||||
kalman_t kalmanFilterStateRate[XYZ_AXIS_COUNT];
|
||||
float setPoint[XYZ_AXIS_COUNT];
|
||||
|
||||
static void gyroKalmanInitAxis(kalman_t *filter)
|
||||
{
|
||||
memset(filter, 0, sizeof(kalman_t));
|
||||
filter->q = gyroConfig()->kalman_q * 0.03f; //add multiplier to make tuning easier
|
||||
filter->r = 88.0f; //seeding R at 88.0f
|
||||
filter->p = 30.0f; //seeding P at 30.0f
|
||||
filter->e = 1.0f;
|
||||
filter->s = gyroConfig()->kalman_sharpness / 10.0f;
|
||||
filter->w = gyroConfig()->kalman_w * 8;
|
||||
filter->inverseN = 1.0f / (float)(filter->w);
|
||||
}
|
||||
|
||||
void gyroKalmanSetSetpoint(uint8_t axis, float rate)
|
||||
{
|
||||
setPoint[axis] = rate;
|
||||
}
|
||||
|
||||
void gyroKalmanInitialize(void)
|
||||
{
|
||||
gyroKalmanInitAxis(&kalmanFilterStateRate[X]);
|
||||
gyroKalmanInitAxis(&kalmanFilterStateRate[Y]);
|
||||
gyroKalmanInitAxis(&kalmanFilterStateRate[Z]);
|
||||
}
|
||||
|
||||
float kalman_process(kalman_t *kalmanState, float input, float target)
|
||||
{
|
||||
float targetAbs = fabsf(target);
|
||||
//project the state ahead using acceleration
|
||||
kalmanState->x += (kalmanState->x - kalmanState->lastX);
|
||||
|
||||
//figure out how much to boost or reduce our error in the estimate based on setpoint target.
|
||||
//this should be close to 0 as we approach the sepoint and really high the futher away we are from the setpoint.
|
||||
//update last state
|
||||
kalmanState->lastX = kalmanState->x;
|
||||
|
||||
if (kalmanState->lastX != 0.0f)
|
||||
{
|
||||
// calculate the error and add multiply sharpness boost
|
||||
float errorMultiplier = fabsf(target - kalmanState->x) * kalmanState->s;
|
||||
|
||||
// give a boost to the setpoint, used to caluclate the kalman q, based on the error and setpoint/gyrodata
|
||||
errorMultiplier = constrainf(errorMultiplier * fabsf(1.0f - (target / kalmanState->lastX)) + 1.0f, 1.0f, 50.0f);
|
||||
|
||||
kalmanState->e = fabsf(1.0f - (((targetAbs + 1.0f) * errorMultiplier) / fabsf(kalmanState->lastX)));
|
||||
}
|
||||
|
||||
//prediction update
|
||||
kalmanState->p = kalmanState->p + (kalmanState->q * kalmanState->e);
|
||||
|
||||
//measurement update
|
||||
kalmanState->k = kalmanState->p / (kalmanState->p + kalmanState->r);
|
||||
kalmanState->x += kalmanState->k * (input - kalmanState->x);
|
||||
kalmanState->p = (1.0f - kalmanState->k) * kalmanState->p;
|
||||
return kalmanState->x;
|
||||
}
|
||||
|
||||
static void updateAxisVariance(kalman_t *kalmanState, float rate)
|
||||
{
|
||||
kalmanState->axisWindow[kalmanState->windex] = rate;
|
||||
|
||||
kalmanState->axisSumMean += kalmanState->axisWindow[kalmanState->windex];
|
||||
float varianceElement = kalmanState->axisWindow[kalmanState->windex] - kalmanState->axisMean;
|
||||
varianceElement = varianceElement * varianceElement;
|
||||
kalmanState->axisSumVar += varianceElement;
|
||||
kalmanState->varianceWindow[kalmanState->windex] = varianceElement;
|
||||
|
||||
kalmanState->windex++;
|
||||
if (kalmanState->windex >= kalmanState->w) {
|
||||
kalmanState->windex = 0;
|
||||
}
|
||||
|
||||
kalmanState->axisSumMean -= kalmanState->axisWindow[kalmanState->windex];
|
||||
kalmanState->axisSumVar -= kalmanState->varianceWindow[kalmanState->windex];
|
||||
|
||||
//New mean
|
||||
kalmanState->axisMean = kalmanState->axisSumMean * kalmanState->inverseN;
|
||||
kalmanState->axisVar = kalmanState->axisSumVar * kalmanState->inverseN;
|
||||
|
||||
float squirt;
|
||||
arm_sqrt_f32(kalmanState->axisVar, &squirt);
|
||||
kalmanState->r = squirt * VARIANCE_SCALE;
|
||||
}
|
||||
|
||||
float gyroKalmanUpdate(uint8_t axis, float input)
|
||||
{
|
||||
updateAxisVariance(&kalmanFilterStateRate[axis], input);
|
||||
|
||||
DEBUG_SET(DEBUG_KALMAN, axis, kalmanFilterStateRate[axis].k * 1000.0f); //Kalman gain
|
||||
|
||||
return kalman_process(&kalmanFilterStateRate[axis], input, setPoint[axis]);
|
||||
}
|
||||
|
||||
#endif
|
54
src/main/flight/kalman.h
Executable file
54
src/main/flight/kalman.h
Executable file
|
@ -0,0 +1,54 @@
|
|||
/*
|
||||
* This file is part of Cleanflight and Betaflight.
|
||||
*
|
||||
* Cleanflight and Betaflight are free software. You can redistribute
|
||||
* this software and/or modify this software under the terms of the
|
||||
* GNU General Public License as published by the Free Software
|
||||
* Foundation, either version 3 of the License, or (at your option)
|
||||
* any later version.
|
||||
*
|
||||
* Cleanflight and Betaflight are distributed in the hope that they
|
||||
* will be useful, but WITHOUT ANY WARRANTY; without even the implied
|
||||
* warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
||||
* See the GNU General Public License for more details.
|
||||
*
|
||||
* You should have received a copy of the GNU General Public License
|
||||
* along with this software.
|
||||
*
|
||||
* If not, see <http://www.gnu.org/licenses/>.
|
||||
*/
|
||||
|
||||
#pragma once
|
||||
|
||||
#include "sensors/gyro.h"
|
||||
#include "common/filter.h"
|
||||
|
||||
#define MAX_KALMAN_WINDOW_SIZE 512
|
||||
|
||||
#define VARIANCE_SCALE 0.67f
|
||||
|
||||
typedef struct kalman
|
||||
{
|
||||
float q; //process noise covariance
|
||||
float r; //measurement noise covariance
|
||||
float p; //estimation error covariance matrix
|
||||
float k; //kalman gain
|
||||
float x; //state
|
||||
float lastX; //previous state
|
||||
float e;
|
||||
float s;
|
||||
|
||||
float axisVar;
|
||||
uint16_t windex;
|
||||
float axisWindow[MAX_KALMAN_WINDOW_SIZE];
|
||||
float varianceWindow[MAX_KALMAN_WINDOW_SIZE];
|
||||
float axisSumMean;
|
||||
float axisMean;
|
||||
float axisSumVar;
|
||||
float inverseN;
|
||||
uint16_t w;
|
||||
} kalman_t;
|
||||
|
||||
void gyroKalmanInitialize(void);
|
||||
float gyroKalmanUpdate(uint8_t axis, float input);
|
||||
void gyroKalmanSetSetpoint(uint8_t axis, float rate);
|
|
@ -29,7 +29,6 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/utils.h"
|
||||
#include "common/global_functions.h"
|
||||
|
||||
#include "config/feature.h"
|
||||
#include "config/parameter_group.h"
|
||||
|
@ -479,11 +478,11 @@ void FAST_CODE mixTable(const float dT)
|
|||
int16_t throttleMin, throttleMax;
|
||||
|
||||
// Find min and max throttle based on condition.
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
if (GLOBAL_FUNCTION_FLAG(GLOBAL_FUNCTION_FLAG_OVERRIDE_THROTTLE)) {
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (LOGIC_CONDITION_GLOBAL_FLAG(LOGIC_CONDITION_GLOBAL_FLAG_OVERRIDE_THROTTLE)) {
|
||||
throttleRangeMin = throttleIdleValue;
|
||||
throttleRangeMax = motorConfig()->maxthrottle;
|
||||
mixerThrottleCommand = constrain(globalFunctionValues[GLOBAL_FUNCTION_ACTION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax);
|
||||
mixerThrottleCommand = constrain(logicConditionValuesByType[LOGIC_CONDITION_OVERRIDE_THROTTLE], throttleRangeMin, throttleRangeMax);
|
||||
} else
|
||||
#endif
|
||||
if (feature(FEATURE_REVERSIBLE_MOTORS)) {
|
||||
|
@ -514,7 +513,7 @@ void FAST_CODE mixTable(const float dT)
|
|||
throttleRangeMax = motorConfig()->maxthrottle;
|
||||
|
||||
// Throttle scaling to limit max throttle when battery is full
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * getThrottleScale(motorConfig()->throttleScale)) + throttleRangeMin;
|
||||
#else
|
||||
mixerThrottleCommand = ((mixerThrottleCommand - throttleRangeMin) * motorConfig()->throttleScale) + throttleRangeMin;
|
||||
|
|
|
@ -44,6 +44,7 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "flight/imu.h"
|
||||
#include "flight/mixer.h"
|
||||
#include "flight/rpm_filter.h"
|
||||
#include "flight/kalman.h"
|
||||
|
||||
#include "io/gps.h"
|
||||
|
||||
|
@ -56,13 +57,17 @@ FILE_COMPILE_FOR_SPEED
|
|||
#include "sensors/acceleration.h"
|
||||
#include "sensors/compass.h"
|
||||
#include "sensors/pitotmeter.h"
|
||||
#include "common/global_functions.h"
|
||||
|
||||
#include "scheduler/scheduler.h"
|
||||
|
||||
#include "programming/logic_condition.h"
|
||||
|
||||
typedef struct {
|
||||
float kP; // Proportional gain
|
||||
float kI; // Integral gain
|
||||
float kD; // Derivative gain
|
||||
float kFF; // Feed-forward gain
|
||||
float kCD; // Control Derivative
|
||||
float kT; // Back-calculation tracking gain
|
||||
|
||||
float gyroRate;
|
||||
|
@ -85,22 +90,23 @@ typedef struct {
|
|||
pt1Filter_t ptermLpfState;
|
||||
filter_t dtermLpfState;
|
||||
filter_t dtermLpf2State;
|
||||
// Dterm notch filtering
|
||||
biquadFilter_t deltaNotchFilter;
|
||||
|
||||
float stickPosition;
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
float previousRateTarget;
|
||||
float previousRateGyro;
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
pt1Filter_t dBoostLpf;
|
||||
biquadFilter_t dBoostGyroLpf;
|
||||
#endif
|
||||
uint16_t pidSumLimit;
|
||||
filterApply4FnPtr ptermFilterApplyFn;
|
||||
bool itermLimitActive;
|
||||
|
||||
biquadFilter_t rateTargetFilter;
|
||||
} pidState_t;
|
||||
|
||||
STATIC_FASTRAM filterApplyFnPtr notchFilterApplyFn;
|
||||
STATIC_FASTRAM bool pidFiltersConfigured = false;
|
||||
static EXTENDED_FASTRAM float headingHoldCosZLimit;
|
||||
static EXTENDED_FASTRAM int16_t headingHoldTarget;
|
||||
|
@ -115,8 +121,7 @@ FASTRAM int16_t axisPID[FLIGHT_DYNAMICS_INDEX_COUNT];
|
|||
int32_t axisPID_P[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_I[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_D[FLIGHT_DYNAMICS_INDEX_COUNT], axisPID_Setpoint[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
#endif
|
||||
|
||||
STATIC_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
|
||||
static EXTENDED_FASTRAM pidState_t pidState[FLIGHT_DYNAMICS_INDEX_COUNT];
|
||||
static EXTENDED_FASTRAM pt1Filter_t windupLpf[XYZ_AXIS_COUNT];
|
||||
static EXTENDED_FASTRAM uint8_t itermRelax;
|
||||
static EXTENDED_FASTRAM uint8_t itermRelaxType;
|
||||
|
@ -148,15 +153,16 @@ typedef void (*pidControllerFnPtr)(pidState_t *pidState, flight_dynamics_index_t
|
|||
static EXTENDED_FASTRAM pidControllerFnPtr pidControllerApplyFn;
|
||||
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpfFilterApplyFn;
|
||||
static EXTENDED_FASTRAM filterApplyFnPtr dTermLpf2FilterApplyFn;
|
||||
static EXTENDED_FASTRAM bool levelingEnabled = false;
|
||||
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 12);
|
||||
PG_REGISTER_PROFILE_WITH_RESET_TEMPLATE(pidProfile_t, pidProfile, PG_PID_PROFILE, 13);
|
||||
|
||||
PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
||||
.bank_mc = {
|
||||
.pid = {
|
||||
[PID_ROLL] = { 40, 30, 23, 0 },
|
||||
[PID_PITCH] = { 40, 30, 23, 0 },
|
||||
[PID_YAW] = { 85, 45, 0, 0 },
|
||||
[PID_ROLL] = { 40, 30, 23, 60 },
|
||||
[PID_PITCH] = { 40, 30, 23, 60 },
|
||||
[PID_YAW] = { 85, 45, 0, 60 },
|
||||
[PID_LEVEL] = {
|
||||
.P = 20, // Self-level strength
|
||||
.I = 15, // Self-leveing low-pass frequency (0 - disabled)
|
||||
|
@ -230,15 +236,11 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
}
|
||||
},
|
||||
|
||||
.dterm_soft_notch_hz = 0,
|
||||
.dterm_soft_notch_cutoff = 1,
|
||||
.dterm_lpf_type = 1, //Default to BIQUAD
|
||||
.dterm_lpf_hz = 40,
|
||||
.dterm_lpf2_type = 1, //Default to BIQUAD
|
||||
.dterm_lpf2_hz = 0, // Off by default
|
||||
.yaw_lpf_hz = 0,
|
||||
.dterm_setpoint_weight = 1.0f,
|
||||
.use_dterm_fir_filter = 1,
|
||||
|
||||
.itermWindupPointPercent = 50, // Percent
|
||||
|
||||
|
@ -259,6 +261,9 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
|
||||
.loiter_direction = NAV_LOITER_RIGHT,
|
||||
.navVelXyDTermLpfHz = NAV_ACCEL_CUTOFF_FREQUENCY_HZ,
|
||||
.navVelXyDtermAttenuation = 90,
|
||||
.navVelXyDtermAttenuationStart = 10,
|
||||
.navVelXyDtermAttenuationEnd = 60,
|
||||
.iterm_relax_type = ITERM_RELAX_SETPOINT,
|
||||
.iterm_relax_cutoff = MC_ITERM_RELAX_CUTOFF_DEFAULT,
|
||||
.iterm_relax = ITERM_RELAX_RP,
|
||||
|
@ -270,6 +275,7 @@ PG_RESET_TEMPLATE(pidProfile_t, pidProfile,
|
|||
.antigravityCutoff = ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF,
|
||||
.pidControllerType = PID_TYPE_AUTO,
|
||||
.navFwPosHdgPidsumLimit = PID_SUM_LIMIT_YAW_DEFAULT,
|
||||
.controlDerivativeLpfHz = 30,
|
||||
);
|
||||
|
||||
bool pidInitFilters(void)
|
||||
|
@ -280,38 +286,6 @@ bool pidInitFilters(void)
|
|||
return false;
|
||||
}
|
||||
|
||||
static float dtermCoeffs[PID_GYRO_RATE_BUF_LENGTH];
|
||||
|
||||
if (pidProfile()->use_dterm_fir_filter) {
|
||||
// Calculate derivative using 5-point noise-robust differentiators without time delay (one-sided or forward filters)
|
||||
// by Pavel Holoborodko, see http://www.holoborodko.com/pavel/numerical-methods/numerical-derivative/smooth-low-noise-differentiators/
|
||||
// h[0] = 5/8, h[-1] = 1/4, h[-2] = -1, h[-3] = -1/4, h[-4] = 3/8
|
||||
dtermCoeffs[0] = 5.0f/8;
|
||||
dtermCoeffs[1] = 2.0f/8;
|
||||
dtermCoeffs[2] = -8.0f/8;
|
||||
dtermCoeffs[3] = -2.0f/8;
|
||||
dtermCoeffs[4] = 3.0f/8;
|
||||
} else {
|
||||
//simple d(t) - d(t-1) differentiator
|
||||
dtermCoeffs[0] = 1.0f;
|
||||
dtermCoeffs[1] = -1.0f;
|
||||
dtermCoeffs[2] = 0.0f;
|
||||
dtermCoeffs[3] = 0.0f;
|
||||
dtermCoeffs[4] = 0.0f;
|
||||
}
|
||||
|
||||
for (int axis = 0; axis < 3; ++ axis) {
|
||||
firFilterInit(&pidState[axis].gyroRateFilter, pidState[axis].gyroRateBuf, PID_GYRO_RATE_BUF_LENGTH, dtermCoeffs);
|
||||
}
|
||||
|
||||
notchFilterApplyFn = nullFilterApply;
|
||||
if (pidProfile()->dterm_soft_notch_hz != 0) {
|
||||
notchFilterApplyFn = (filterApplyFnPtr)biquadFilterApply;
|
||||
for (int axis = 0; axis < 3; ++ axis) {
|
||||
biquadFilterInitNotch(&pidState[axis].deltaNotchFilter, refreshRate, pidProfile()->dterm_soft_notch_hz, pidProfile()->dterm_soft_notch_cutoff);
|
||||
}
|
||||
}
|
||||
|
||||
// Init other filters
|
||||
if (pidProfile()->dterm_lpf_hz) {
|
||||
for (int axis = 0; axis < 3; ++ axis) {
|
||||
|
@ -339,7 +313,7 @@ bool pidInitFilters(void)
|
|||
}
|
||||
|
||||
#ifdef USE_ANTIGRAVITY
|
||||
pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, refreshRate * 1e-6f);
|
||||
pt1FilterInit(&antigravityThrottleLpf, pidProfile()->antigravityCutoff, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f);
|
||||
#endif
|
||||
|
||||
#ifdef USE_D_BOOST
|
||||
|
@ -348,6 +322,12 @@ bool pidInitFilters(void)
|
|||
}
|
||||
#endif
|
||||
|
||||
if (pidProfile()->controlDerivativeLpfHz) {
|
||||
for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) {
|
||||
biquadFilterInitLPF(&pidState[axis].rateTargetFilter, pidProfile()->controlDerivativeLpfHz, getLooptime());
|
||||
}
|
||||
}
|
||||
|
||||
pidFiltersConfigured = true;
|
||||
|
||||
return true;
|
||||
|
@ -356,7 +336,7 @@ bool pidInitFilters(void)
|
|||
void pidResetTPAFilter(void)
|
||||
{
|
||||
if (usedPidControllerType == PID_TYPE_PIFF && currentControlRateProfile->throttle.fixedWingTauMs > 0) {
|
||||
pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, getLooptime() * 1e-6f);
|
||||
pt1FilterInitRC(&fixedWingTpaFilter, currentControlRateProfile->throttle.fixedWingTauMs * 1e-3f, TASK_PERIOD_HZ(TASK_AUX_RATE_HZ) * 1e-6f);
|
||||
pt1FilterReset(&fixedWingTpaFilter, getThrottleIdleValue());
|
||||
}
|
||||
}
|
||||
|
@ -448,13 +428,13 @@ void schedulePidGainsUpdate(void)
|
|||
pidGainsUpdateRequired = true;
|
||||
}
|
||||
|
||||
void FAST_CODE NOINLINE updatePIDCoefficients(float dT)
|
||||
void updatePIDCoefficients()
|
||||
{
|
||||
STATIC_FASTRAM uint16_t prevThrottle = 0;
|
||||
|
||||
// Check if throttle changed. Different logic for fixed wing vs multirotor
|
||||
if (usedPidControllerType == PID_TYPE_PIFF && (currentControlRateProfile->throttle.fixedWingTauMs > 0)) {
|
||||
uint16_t filteredThrottle = pt1FilterApply3(&fixedWingTpaFilter, rcCommand[THROTTLE], dT);
|
||||
uint16_t filteredThrottle = pt1FilterApply(&fixedWingTpaFilter, rcCommand[THROTTLE]);
|
||||
if (filteredThrottle != prevThrottle) {
|
||||
prevThrottle = filteredThrottle;
|
||||
pidGainsUpdateRequired = true;
|
||||
|
@ -470,6 +450,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT)
|
|||
#ifdef USE_ANTIGRAVITY
|
||||
if (usedPidControllerType == PID_TYPE_PID) {
|
||||
antigravityThrottleHpf = rcCommand[THROTTLE] - pt1FilterApply(&antigravityThrottleLpf, rcCommand[THROTTLE]);
|
||||
iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain);
|
||||
}
|
||||
#endif
|
||||
|
||||
|
@ -496,6 +477,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT)
|
|||
pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kD = 0.0f;
|
||||
pidState[axis].kFF = pidBank()->pid[axis].FF / FP_PID_RATE_FF_MULTIPLIER * tpaFactor;
|
||||
pidState[axis].kCD = 0.0f;
|
||||
pidState[axis].kT = 0.0f;
|
||||
}
|
||||
else {
|
||||
|
@ -503,6 +485,7 @@ void FAST_CODE NOINLINE updatePIDCoefficients(float dT)
|
|||
pidState[axis].kP = pidBank()->pid[axis].P / FP_PID_RATE_P_MULTIPLIER * axisTPA;
|
||||
pidState[axis].kI = pidBank()->pid[axis].I / FP_PID_RATE_I_MULTIPLIER;
|
||||
pidState[axis].kD = pidBank()->pid[axis].D / FP_PID_RATE_D_MULTIPLIER * axisTPA;
|
||||
pidState[axis].kCD = pidBank()->pid[axis].FF / FP_PID_RATE_D_FF_MULTIPLIER * axisTPA;
|
||||
pidState[axis].kFF = 0.0f;
|
||||
|
||||
// Tracking anti-windup requires P/I/D to be all defined which is only true for MC
|
||||
|
@ -591,7 +574,7 @@ bool isFixedWingItermLimitActive(float stickPosition)
|
|||
* Iterm anti windup whould be active only when pilot controls the rotation
|
||||
* velocity directly, not when ANGLE or HORIZON are used
|
||||
*/
|
||||
if (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) {
|
||||
if (levelingEnabled) {
|
||||
return false;
|
||||
}
|
||||
|
||||
|
@ -689,9 +672,6 @@ static float FAST_CODE applyDBoost(pidState_t *pidState, float dT) {
|
|||
dBoost = scaleRangef(acceleration, 0.0f, dBoostMaxAtAlleceleration, 1.0f, dBoostFactor);
|
||||
dBoost = pt1FilterApply4(&pidState->dBoostLpf, dBoost, D_BOOST_LPF_HZ, dT);
|
||||
dBoost = constrainf(dBoost, 1.0f, dBoostFactor);
|
||||
|
||||
pidState->previousRateTarget = pidState->rateTarget;
|
||||
pidState->previousRateGyro = pidState->gyroRate;
|
||||
}
|
||||
|
||||
return dBoost;
|
||||
|
@ -709,34 +689,38 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
|
|||
const float rateError = pidState->rateTarget - pidState->gyroRate;
|
||||
const float newPTerm = pTermProcess(pidState, rateError, dT);
|
||||
|
||||
const float rateTargetDelta = pidState->rateTarget - pidState->previousRateTarget;
|
||||
const float rateTargetDeltaFiltered = biquadFilterApply(&pidState->rateTargetFilter, rateTargetDelta);
|
||||
|
||||
/*
|
||||
* Compute Control Derivative
|
||||
* CD is enabled only when ANGLE and HORIZON modes are not enabled!
|
||||
*/
|
||||
float newCDTerm;
|
||||
if (levelingEnabled) {
|
||||
newCDTerm = 0.0F;
|
||||
} else {
|
||||
newCDTerm = rateTargetDeltaFiltered * (pidState->kCD / dT);
|
||||
}
|
||||
DEBUG_SET(DEBUG_CD, axis, newCDTerm);
|
||||
|
||||
// Calculate new D-term
|
||||
float newDTerm;
|
||||
if (pidState->kD == 0) {
|
||||
// optimisation for when D8 is zero, often used by YAW axis
|
||||
newDTerm = 0;
|
||||
} else {
|
||||
// Calculate delta for Dterm calculation. Apply filters before derivative to minimize effects of dterm kick
|
||||
const float deltaFiltered = pidProfile()->dterm_setpoint_weight * pidState->rateTarget - pidState->gyroRate;
|
||||
float delta = pidState->previousRateGyro - pidState->gyroRate;
|
||||
|
||||
firFilterUpdate(&pidState->gyroRateFilter, deltaFiltered);
|
||||
newDTerm = firFilterApply(&pidState->gyroRateFilter);
|
||||
|
||||
// Apply D-term notch
|
||||
newDTerm = notchFilterApplyFn(&pidState->deltaNotchFilter, newDTerm);
|
||||
|
||||
// Apply additional lowpass
|
||||
newDTerm = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, newDTerm);
|
||||
newDTerm = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, newDTerm);
|
||||
delta = dTermLpfFilterApplyFn((filter_t *) &pidState->dtermLpfState, delta);
|
||||
delta = dTermLpf2FilterApplyFn((filter_t *) &pidState->dtermLpf2State, delta);
|
||||
|
||||
// Calculate derivative
|
||||
newDTerm = newDTerm * (pidState->kD / dT) * applyDBoost(pidState, dT);
|
||||
|
||||
// Additionally constrain D
|
||||
newDTerm = constrainf(newDTerm, -300.0f, 300.0f);
|
||||
newDTerm = delta * (pidState->kD / dT) * applyDBoost(pidState, dT);
|
||||
}
|
||||
|
||||
// TODO: Get feedback from mixer on available correction range for each axis
|
||||
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf;
|
||||
const float newOutput = newPTerm + newDTerm + pidState->errorGyroIf + newCDTerm;
|
||||
const float newOutputLimited = constrainf(newOutput, -pidState->pidSumLimit, +pidState->pidSumLimit);
|
||||
|
||||
float itermErrorRate = rateError;
|
||||
|
@ -760,6 +744,9 @@ static void FAST_CODE NOINLINE pidApplyMulticopterRateController(pidState_t *pid
|
|||
axisPID_D[axis] = newDTerm;
|
||||
axisPID_Setpoint[axis] = pidState->rateTarget;
|
||||
#endif
|
||||
|
||||
pidState->previousRateTarget = pidState->rateTarget;
|
||||
pidState->previousRateGyro = pidState->gyroRate;
|
||||
}
|
||||
|
||||
void updateHeadingHoldTarget(int16_t heading)
|
||||
|
@ -978,7 +965,7 @@ void FAST_CODE pidController(float dT)
|
|||
if (axis == FD_YAW && headingHoldState == HEADING_HOLD_ENABLED) {
|
||||
rateTarget = pidHeadingHold(dT);
|
||||
} else {
|
||||
#ifdef USE_GLOBAL_FUNCTIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
rateTarget = pidRcCommandToRate(getRcCommandOverride(rcCommand, axis), currentControlRateProfile->stabilized.rates[axis]);
|
||||
#else
|
||||
rateTarget = pidRcCommandToRate(rcCommand[axis], currentControlRateProfile->stabilized.rates[axis]);
|
||||
|
@ -987,6 +974,9 @@ void FAST_CODE pidController(float dT)
|
|||
|
||||
// Limit desired rate to something gyro can measure reliably
|
||||
pidState[axis].rateTarget = constrainf(rateTarget, -GYRO_SATURATION_LIMIT, +GYRO_SATURATION_LIMIT);
|
||||
#ifdef USE_GYRO_KALMAN
|
||||
gyroKalmanSetSetpoint(axis, pidState[axis].rateTarget);
|
||||
#endif
|
||||
}
|
||||
|
||||
// Step 3: Run control for ANGLE_MODE, HORIZON_MODE, and HEADING_LOCK
|
||||
|
@ -995,6 +985,9 @@ void FAST_CODE pidController(float dT)
|
|||
pidLevel(&pidState[FD_ROLL], FD_ROLL, horizonRateMagnitude, dT);
|
||||
pidLevel(&pidState[FD_PITCH], FD_PITCH, horizonRateMagnitude, dT);
|
||||
canUseFpvCameraMix = false; // FPVANGLEMIX is incompatible with ANGLE/HORIZON
|
||||
levelingEnabled = true;
|
||||
} else {
|
||||
levelingEnabled = false;
|
||||
}
|
||||
|
||||
if (FLIGHT_MODE(TURN_ASSISTANT) || navigationRequiresTurnAssistance()) {
|
||||
|
@ -1009,10 +1002,6 @@ void FAST_CODE pidController(float dT)
|
|||
// Prevent strong Iterm accumulation during stick inputs
|
||||
antiWindupScaler = constrainf((1.0f - getMotorMixRange()) / motorItermWindupPoint, 0.0f, 1.0f);
|
||||
|
||||
#ifdef USE_ANTIGRAVITY
|
||||
iTermAntigravityGain = scaleRangef(fabsf(antigravityThrottleHpf) * antigravityAccelerator, 0.0f, 1000.0f, 1.0f, antigravityGain);
|
||||
#endif
|
||||
|
||||
for (int axis = 0; axis < 3; axis++) {
|
||||
// Apply setpoint rate of change limits
|
||||
pidApplySetpointRateLimiting(&pidState[axis], axis, dT);
|
||||
|
@ -1042,8 +1031,6 @@ pidType_e pidIndexGetType(pidIndex_e pidIndex)
|
|||
|
||||
void pidInit(void)
|
||||
{
|
||||
pidResetTPAFilter();
|
||||
|
||||
// Calculate max overall tilt (max pitch + max roll combined) as a limit to heading hold
|
||||
headingHoldCosZLimit = cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_ROLL])) *
|
||||
cos_approx(DECIDEGREES_TO_RADIANS(pidProfile()->max_angle_inclination[FD_PITCH]));
|
||||
|
@ -1119,6 +1106,8 @@ void pidInit(void)
|
|||
} else {
|
||||
pidControllerApplyFn = nullRateController;
|
||||
}
|
||||
|
||||
pidResetTPAFilter();
|
||||
}
|
||||
|
||||
const pidBank_t * pidBank(void) {
|
||||
|
|
|
@ -45,6 +45,7 @@ FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13
|
|||
#define FP_PID_RATE_P_MULTIPLIER 31.0f
|
||||
#define FP_PID_RATE_I_MULTIPLIER 4.0f
|
||||
#define FP_PID_RATE_D_MULTIPLIER 1905.0f
|
||||
#define FP_PID_RATE_D_FF_MULTIPLIER 7270.0f
|
||||
#define FP_PID_LEVEL_P_MULTIPLIER 6.56f // Level P gain units is [1/sec] and angle error is [deg] => [deg/s]
|
||||
#define FP_PID_YAWHOLD_P_MULTIPLIER 80.0f
|
||||
|
||||
|
@ -53,6 +54,8 @@ FP-PID has been rescaled to match LuxFloat (and MWRewrite) from Cleanflight 1.13
|
|||
|
||||
#define ANTI_GRAVITY_THROTTLE_FILTER_CUTOFF 15 // The anti gravity throttle highpass filter cutoff
|
||||
|
||||
#define TASK_AUX_RATE_HZ 100 //In Hz
|
||||
|
||||
typedef enum {
|
||||
/* PID MC FW */
|
||||
PID_ROLL, // + +
|
||||
|
@ -104,17 +107,12 @@ typedef struct pidProfile_s {
|
|||
pidBank_t bank_fw;
|
||||
pidBank_t bank_mc;
|
||||
|
||||
uint16_t dterm_soft_notch_hz; // Dterm Notch frequency
|
||||
uint16_t dterm_soft_notch_cutoff; // Dterm Notch Cutoff frequency
|
||||
|
||||
uint8_t dterm_lpf_type; // Dterm LPF type: PT1, BIQUAD
|
||||
uint16_t dterm_lpf_hz;
|
||||
|
||||
uint8_t dterm_lpf2_type; // Dterm LPF type: PT1, BIQUAD
|
||||
uint16_t dterm_lpf2_hz;
|
||||
|
||||
uint8_t use_dterm_fir_filter; // Use classical INAV FIR differentiator. Very noise robust, can be quite slowish
|
||||
|
||||
uint8_t yaw_lpf_hz;
|
||||
|
||||
uint8_t heading_hold_rate_limit; // Maximum rotation rate HEADING_HOLD mode can feed to yaw rate PID controller
|
||||
|
@ -126,7 +124,6 @@ typedef struct pidProfile_s {
|
|||
|
||||
int16_t max_angle_inclination[ANGLE_INDEX_COUNT]; // Max possible inclination (roll and pitch axis separately
|
||||
|
||||
float dterm_setpoint_weight;
|
||||
uint16_t pidSumLimit;
|
||||
uint16_t pidSumLimitYaw;
|
||||
|
||||
|
@ -138,7 +135,9 @@ typedef struct pidProfile_s {
|
|||
|
||||
uint8_t loiter_direction; // Direction of loitering center point on right wing (clockwise - as before), or center point on left wing (counterclockwise)
|
||||
float navVelXyDTermLpfHz;
|
||||
|
||||
uint8_t navVelXyDtermAttenuation; // VEL_XY dynamic Dterm scale: Dterm will be attenuatedby this value (in percent) when UAV is traveling with more than navVelXyDtermAttenuationStart percents of max velocity
|
||||
uint8_t navVelXyDtermAttenuationStart; // VEL_XY dynamic Dterm scale: Dterm attenuation will begin at this percent of max velocity
|
||||
uint8_t navVelXyDtermAttenuationEnd; // VEL_XY dynamic Dterm scale: Dterm will be fully attenuated at this percent of max velocity
|
||||
uint8_t iterm_relax_type; // Specifies type of relax algorithm
|
||||
uint8_t iterm_relax_cutoff; // This cutoff frequency specifies a low pass filter which predicts average response of the quad to setpoint
|
||||
uint8_t iterm_relax; // Enable iterm suppression during stick input
|
||||
|
@ -151,6 +150,7 @@ typedef struct pidProfile_s {
|
|||
uint8_t antigravityCutoff;
|
||||
|
||||
uint16_t navFwPosHdgPidsumLimit;
|
||||
uint8_t controlDerivativeLpfHz;
|
||||
} pidProfile_t;
|
||||
|
||||
typedef struct pidAutotuneConfig_s {
|
||||
|
@ -180,7 +180,7 @@ struct motorConfig_s;
|
|||
struct rxConfig_s;
|
||||
|
||||
void schedulePidGainsUpdate(void);
|
||||
void updatePIDCoefficients(float dT);
|
||||
void updatePIDCoefficients(void);
|
||||
void pidController(float dT);
|
||||
|
||||
float pidRateToRcCommand(float rateDPS, uint8_t rate);
|
||||
|
|
|
@ -28,7 +28,7 @@
|
|||
#include "common/axis.h"
|
||||
#include "common/filter.h"
|
||||
#include "common/maths.h"
|
||||
#include "common/global_variables.h"
|
||||
#include "programming/global_variables.h"
|
||||
|
||||
#include "config/config_reset.h"
|
||||
#include "config/feature.h"
|
||||
|
@ -75,7 +75,7 @@ void pgResetFn_customServoMixers(servoMixer_t *instance)
|
|||
.inputSource = 0,
|
||||
.rate = 0,
|
||||
.speed = 0
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
,.conditionId = -1
|
||||
#endif
|
||||
);
|
||||
|
@ -266,7 +266,7 @@ void servoMixer(float dT)
|
|||
input[INPUT_FEATURE_FLAPS] = FLIGHT_MODE(FLAPERON) ? servoConfig()->flaperon_throw_offset : 0;
|
||||
|
||||
input[INPUT_MAX] = 500;
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
input[INPUT_GVAR_0] = constrain(gvGet(0), -1000, 1000);
|
||||
input[INPUT_GVAR_1] = constrain(gvGet(1), -1000, 1000);
|
||||
input[INPUT_GVAR_2] = constrain(gvGet(2), -1000, 1000);
|
||||
|
@ -318,7 +318,7 @@ void servoMixer(float dT)
|
|||
/*
|
||||
* Check if conditions for a rule are met, not all conditions apply all the time
|
||||
*/
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
if (!logicConditionGetValue(currentServoMixer[i].conditionId)) {
|
||||
continue;
|
||||
}
|
||||
|
|
|
@ -18,7 +18,7 @@
|
|||
#pragma once
|
||||
|
||||
#include "config/parameter_group.h"
|
||||
#include "common/logic_condition.h"
|
||||
#include "programming/logic_condition.h"
|
||||
|
||||
#define MAX_SUPPORTED_SERVOS 16
|
||||
|
||||
|
@ -105,7 +105,7 @@ typedef struct servoMixer_s {
|
|||
uint8_t inputSource; // input channel for this rule
|
||||
int16_t rate; // range [-1000;+1000] ; can be used to adjust a rate 0-1000% and a direction
|
||||
uint8_t speed; // reduces the speed of the rule, 0=unlimited speed
|
||||
#ifdef USE_LOGIC_CONDITIONS
|
||||
#ifdef USE_PROGRAMMING_FRAMEWORK
|
||||
int8_t conditionId;
|
||||
#endif
|
||||
} servoMixer_t;
|
||||
|
|
|
@ -2107,6 +2107,25 @@ afatfsOperationStatus_e afatfs_fseek(afatfsFilePtr_t file, int32_t offset, afatf
|
|||
return afatfs_fseekInternal(file, MIN((uint32_t) offset, file->logicalSize), NULL);
|
||||
}
|
||||
|
||||
/**
|
||||
* Attempt to seek the file cursor from the given point (`whence`) by the given offset, just like C's fseek().
|
||||
*
|
||||
* AFATFS_SEEK_SET with offset 0 will always return AFATFS_OPERATION_SUCCESS.
|
||||
*
|
||||
* Returns:
|
||||
* AFATFS_OPERATION_SUCCESS - The seek was completed immediately
|
||||
* AFATFS_OPERATION_IN_PROGRESS - The seek was queued and will complete later. Feel free to attempt read/write
|
||||
* operations on the file, they'll fail until the seek is complete.
|
||||
*/
|
||||
afatfsOperationStatus_e afatfs_fseekSync(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence)
|
||||
{
|
||||
while (afatfs_fileIsBusy(file)) {
|
||||
afatfs_poll();
|
||||
}
|
||||
|
||||
return afatfs_fseek(file, offset, whence);
|
||||
}
|
||||
|
||||
/**
|
||||
* Get the byte-offset of the file's cursor from the start of the file.
|
||||
*
|
||||
|
@ -2536,7 +2555,9 @@ static void afatfs_createFileContinue(afatfsFile_t *file)
|
|||
afatfsCreateFile_t *opState = &file->operation.state.createFile;
|
||||
fatDirectoryEntry_t *entry;
|
||||
afatfsOperationStatus_e status;
|
||||
#ifndef BOOTLOADER
|
||||
dateTime_t now;
|
||||
#endif
|
||||
|
||||
doMore:
|
||||
|
||||
|
@ -2596,13 +2617,17 @@ static void afatfs_createFileContinue(afatfsFile_t *file)
|
|||
|
||||
memcpy(entry->filename, opState->filename, FAT_FILENAME_LENGTH);
|
||||
entry->attrib = file->attrib;
|
||||
#ifndef BOOTLOADER
|
||||
if (rtcGetDateTimeLocal(&now)) {
|
||||
entry->creationDate = FAT_MAKE_DATE(now.year, now.month, now.day);
|
||||
entry->creationTime = FAT_MAKE_TIME(now.hours, now.minutes, now.seconds);
|
||||
} else {
|
||||
#endif
|
||||
entry->creationDate = AFATFS_DEFAULT_FILE_DATE;
|
||||
entry->creationTime = AFATFS_DEFAULT_FILE_TIME;
|
||||
#ifndef BOOTLOADER
|
||||
}
|
||||
#endif
|
||||
entry->lastWriteDate = entry->creationDate;
|
||||
entry->lastWriteTime = entry->creationTime;
|
||||
|
||||
|
@ -2867,6 +2892,20 @@ bool afatfs_fclose(afatfsFilePtr_t file, afatfsCallback_t callback)
|
|||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Close `file` immediately
|
||||
*/
|
||||
void afatfs_fcloseSync(afatfsFilePtr_t file)
|
||||
{
|
||||
for(unsigned i = 0; i < 1000; ++i) {
|
||||
afatfs_poll();
|
||||
}
|
||||
afatfs_fclose(file, NULL);
|
||||
for(unsigned i = 0; i < 1000; ++i) {
|
||||
afatfs_poll();
|
||||
}
|
||||
}
|
||||
|
||||
/**
|
||||
* Create a new directory with the given name, or open the directory if it already exists.
|
||||
*
|
||||
|
@ -2998,6 +3037,11 @@ bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t c
|
|||
return file != NULL;
|
||||
}
|
||||
|
||||
uint32_t afatfs_fileSize(afatfsFilePtr_t file)
|
||||
{
|
||||
return file->logicalSize;
|
||||
}
|
||||
|
||||
/**
|
||||
* Write a single character to the file at the current cursor position. If the cache is too busy to accept the write,
|
||||
* it is silently dropped.
|
||||
|
@ -3087,6 +3131,39 @@ uint32_t afatfs_fwrite(afatfsFilePtr_t file, const uint8_t *buffer, uint32_t len
|
|||
return writtenBytes;
|
||||
}
|
||||
|
||||
/**
|
||||
* Attempt to write `len` bytes from `buffer` into the `file`.
|
||||
*
|
||||
* Returns the number of bytes actually written
|
||||
*
|
||||
* Fewer bytes than requested will be read when EOF is reached before all the bytes could be read
|
||||
*/
|
||||
uint32_t afatfs_fwriteSync(afatfsFilePtr_t file, uint8_t *data, uint32_t length)
|
||||
{
|
||||
uint32_t written = 0;
|
||||
|
||||
while (true) {
|
||||
uint32_t leftToWrite = length - written;
|
||||
uint32_t justWritten = afatfs_fwrite(file, data + written, leftToWrite);
|
||||
/*if (justWritten != leftToWrite) LOG_E(SYSTEM, "%ld -> %ld", length, written);*/
|
||||
written += justWritten;
|
||||
|
||||
if (written < length) {
|
||||
|
||||
if (afatfs_isFull()) {
|
||||
break;
|
||||
}
|
||||
|
||||
afatfs_poll();
|
||||
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return written;
|
||||
}
|
||||
|
||||
/**
|
||||
* Attempt to read `len` bytes from `file` into the `buffer`.
|
||||
*
|
||||
|
@ -3156,6 +3233,37 @@ uint32_t afatfs_fread(afatfsFilePtr_t file, uint8_t *buffer, uint32_t len)
|
|||
return readBytes;
|
||||
}
|
||||
|
||||
/**
|
||||
* Attempt to read `len` bytes from `file` into the `buffer`.
|
||||
*
|
||||
* Returns the number of bytes actually read.
|
||||
*
|
||||
* Fewer bytes than requested will be read when EOF is reached before all the bytes could be read
|
||||
*/
|
||||
uint32_t afatfs_freadSync(afatfsFilePtr_t file, uint8_t *buffer, uint32_t length)
|
||||
{
|
||||
uint32_t bytesRead = 0;
|
||||
|
||||
while (true) {
|
||||
uint32_t leftToRead = length - bytesRead;
|
||||
uint32_t readNow = afatfs_fread(file, buffer, leftToRead);
|
||||
bytesRead += readNow;
|
||||
if (bytesRead < length) {
|
||||
|
||||
if (afatfs_feof(file)) {
|
||||
break;
|
||||
}
|
||||
|
||||
afatfs_poll();
|
||||
|
||||
} else {
|
||||
break;
|
||||
}
|
||||
}
|
||||
|
||||
return bytesRead;
|
||||
}
|
||||
|
||||
/**
|
||||
* Returns true if the file's pointer position currently lies at the end-of-file point (i.e. one byte beyond the last
|
||||
* byte in the file).
|
||||
|
|
|
@ -63,14 +63,19 @@ typedef void (*afatfsCallback_t)(void);
|
|||
bool afatfs_fopen(const char *filename, const char *mode, afatfsFileCallback_t complete);
|
||||
bool afatfs_ftruncate(afatfsFilePtr_t file, afatfsFileCallback_t callback);
|
||||
bool afatfs_fclose(afatfsFilePtr_t file, afatfsCallback_t callback);
|
||||
void afatfs_fcloseSync(afatfsFilePtr_t file);
|
||||
bool afatfs_funlink(afatfsFilePtr_t file, afatfsCallback_t callback);
|
||||
|
||||
bool afatfs_feof(afatfsFilePtr_t file);
|
||||
void afatfs_fputc(afatfsFilePtr_t file, uint8_t c);
|
||||
uint32_t afatfs_fwrite(afatfsFilePtr_t file, const uint8_t *buffer, uint32_t len);
|
||||
uint32_t afatfs_fwriteSync(afatfsFilePtr_t file, uint8_t *data, uint32_t length);
|
||||
uint32_t afatfs_fread(afatfsFilePtr_t file, uint8_t *buffer, uint32_t len);
|
||||
uint32_t afatfs_freadSync(afatfsFilePtr_t file, uint8_t *buffer, uint32_t length);
|
||||
afatfsOperationStatus_e afatfs_fseek(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence);
|
||||
afatfsOperationStatus_e afatfs_fseekSync(afatfsFilePtr_t file, int32_t offset, afatfsSeek_e whence);
|
||||
bool afatfs_ftell(afatfsFilePtr_t file, uint32_t *position);
|
||||
uint32_t afatfs_fileSize(afatfsFilePtr_t file);
|
||||
|
||||
bool afatfs_mkdir(const char *filename, afatfsFileCallback_t complete);
|
||||
bool afatfs_chdir(afatfsFilePtr_t dirHandle);
|
||||
|
|
Some files were not shown because too many files have changed in this diff Show more
Loading…
Add table
Add a link
Reference in a new issue