mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-16 12:55:19 +03:00
Rebased on to master (with merged CMS)
This commit is contained in:
commit
61a87480b3
341 changed files with 8778 additions and 8563 deletions
17
.travis.sh
17
.travis.sh
|
@ -8,7 +8,6 @@ TARGET_FILE=obj/betaflight_${TARGET}
|
||||||
TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/undefined}
|
TRAVIS_REPO_SLUG=${TRAVIS_REPO_SLUG:=$USER/undefined}
|
||||||
BUILDNAME=${BUILDNAME:=travis}
|
BUILDNAME=${BUILDNAME:=travis}
|
||||||
TRAVIS_BUILD_NUMBER=${TRAVIS_BUILD_NUMBER:=undefined}
|
TRAVIS_BUILD_NUMBER=${TRAVIS_BUILD_NUMBER:=undefined}
|
||||||
MAKEFILE="-f Makefile"
|
|
||||||
|
|
||||||
CURL_BASEOPTS=(
|
CURL_BASEOPTS=(
|
||||||
"--retry" "10"
|
"--retry" "10"
|
||||||
|
@ -22,12 +21,8 @@ CURL_PUB_BASEOPTS=(
|
||||||
"--form" "github_repo=${TRAVIS_REPO_SLUG}"
|
"--form" "github_repo=${TRAVIS_REPO_SLUG}"
|
||||||
"--form" "build_name=${BUILDNAME}" )
|
"--form" "build_name=${BUILDNAME}" )
|
||||||
|
|
||||||
# A hacky way of running the unit tests at the same time as the normal builds.
|
|
||||||
if [ $RUNTESTS ] ; then
|
|
||||||
cd ./src/test && make test
|
|
||||||
|
|
||||||
# A hacky way of building the docs at the same time as the normal builds.
|
# A hacky way of building the docs at the same time as the normal builds.
|
||||||
elif [ $PUBLISHDOCS ] ; then
|
if [ $PUBLISHDOCS ] ; then
|
||||||
if [ $PUBLISH_URL ] ; then
|
if [ $PUBLISH_URL ] ; then
|
||||||
|
|
||||||
# Patch Gimli to fix underscores_inside_words
|
# Patch Gimli to fix underscores_inside_words
|
||||||
|
@ -50,9 +45,9 @@ elif [ $PUBLISHMETA ] ; then
|
||||||
curl -k "${CURL_BASEOPTS[@]}" "${CURL_PUB_BASEOPTS[@]}" --form "recent_commits=${RECENT_COMMITS}" ${PUBLISH_URL} || true
|
curl -k "${CURL_BASEOPTS[@]}" "${CURL_PUB_BASEOPTS[@]}" --form "recent_commits=${RECENT_COMMITS}" ${PUBLISH_URL} || true
|
||||||
fi
|
fi
|
||||||
|
|
||||||
else
|
elif [ $TARGET ] ; then
|
||||||
|
make $TARGET
|
||||||
if [ $PUBLISH_URL ] ; then
|
if [ $PUBLISH_URL ] ; then
|
||||||
make -j2 $MAKEFILE
|
|
||||||
if [ -f ${TARGET_FILE}.bin ] ; then
|
if [ -f ${TARGET_FILE}.bin ] ; then
|
||||||
TARGET_FILE=${TARGET_FILE}.bin
|
TARGET_FILE=${TARGET_FILE}.bin
|
||||||
elif [ -f ${TARGET_FILE}.hex ] ; then
|
elif [ -f ${TARGET_FILE}.hex ] ; then
|
||||||
|
@ -64,7 +59,9 @@ else
|
||||||
|
|
||||||
curl -k "${CURL_BASEOPTS[@]}" "${CURL_PUB_BASEOPTS[@]}" --form "file=@${TARGET_FILE}" ${PUBLISH_URL} || true
|
curl -k "${CURL_BASEOPTS[@]}" "${CURL_PUB_BASEOPTS[@]}" --form "file=@${TARGET_FILE}" ${PUBLISH_URL} || true
|
||||||
exit 0;
|
exit 0;
|
||||||
|
fi
|
||||||
|
elif [ $GOAL ] ; then
|
||||||
|
make V=0 $GOAL
|
||||||
else
|
else
|
||||||
make -j2 $MAKEFILE
|
make V=0 all
|
||||||
fi
|
|
||||||
fi
|
fi
|
||||||
|
|
70
.travis.yml
70
.travis.yml
|
@ -1,20 +1,25 @@
|
||||||
|
|
||||||
env:
|
env:
|
||||||
# - RUNTESTS=True
|
|
||||||
# - PUBLISHMETA=True
|
# - PUBLISHMETA=True
|
||||||
# - PUBLISHDOCS=True
|
# - PUBLISHDOCS=True
|
||||||
|
# Specify the main Mafile supported goals.
|
||||||
|
- GOAL=test
|
||||||
|
- GOAL=all
|
||||||
|
# Or specify targets to run.
|
||||||
# - TARGET=AFROMINI
|
# - TARGET=AFROMINI
|
||||||
# - TARGET=BEEBRAIN
|
|
||||||
# - TARGET=AIORACERF3
|
# - TARGET=AIORACERF3
|
||||||
# - TARGET=AIR32
|
# - TARGET=AIR32
|
||||||
|
# - TARGET=AIRBOTF4
|
||||||
# - TARGET=AIRHEROF3
|
# - TARGET=AIRHEROF3
|
||||||
# - TARGET=ALIENFLIGHTF1
|
# - TARGET=ALIENFLIGHTF1
|
||||||
- TARGET=ALIENFLIGHTF3
|
# - TARGET=ALIENFLIGHTF3
|
||||||
- TARGET=ALIENFLIGHTF4
|
# - TARGET=ALIENFLIGHTF4
|
||||||
- TARGET=ANYFCF7
|
# - TARGET=ANYFCF7
|
||||||
- TARGET=BETAFLIGHTF3
|
# - TARGET=BEEBRAIN
|
||||||
- TARGET=BLUEJAYF4
|
# - TARGET=BETAFLIGHTF3
|
||||||
- TARGET=CC3D
|
# - TARGET=BLUEJAYF4
|
||||||
- TARGET=CC3D_OPBL
|
# - TARGET=CC3D
|
||||||
|
# - TARGET=CC3D_OPBL
|
||||||
# - TARGET=CHEBUZZF3
|
# - TARGET=CHEBUZZF3
|
||||||
# - TARGET=CJMCU
|
# - TARGET=CJMCU
|
||||||
# - TARGET=COLIBRI
|
# - TARGET=COLIBRI
|
||||||
|
@ -23,50 +28,51 @@ env:
|
||||||
# - TARGET=DOGE
|
# - TARGET=DOGE
|
||||||
# - TARGET=F4BY
|
# - TARGET=F4BY
|
||||||
# - TARGET=FURYF3
|
# - TARGET=FURYF3
|
||||||
- TARGET=FURYF4
|
# - TARGET=FURYF4
|
||||||
|
# - TARGET=FURYF7
|
||||||
|
# - TARGET=IMPULSERCF3
|
||||||
# - TARGET=IRCFUSIONF3
|
# - TARGET=IRCFUSIONF3
|
||||||
# - TARGET=ISHAPEDF3
|
# - TARGET=ISHAPEDF3
|
||||||
# - TARGET=KISSFC
|
# - TARGET=KISSFC
|
||||||
|
# - TARGET=LUXV2_RACE
|
||||||
# - TARGET=LUX_RACE
|
# - TARGET=LUX_RACE
|
||||||
# - TARGET=MICROSCISKY
|
# - TARGET=MICROSCISKY
|
||||||
# - TARGET=MOTOLAB
|
# - TARGET=MOTOLAB
|
||||||
- TARGET=NAZE
|
# - TARGET=NAZE
|
||||||
# - TARGET=OMNIBUS
|
# - TARGET=OMNIBUS
|
||||||
# - TARGET=OMNIBUSF4
|
# - TARGET=OMNIBUSF4
|
||||||
# - TARGET=PIKOBLX
|
# - TARGET=PIKOBLX
|
||||||
# - TARGET=RACEBASE
|
# - TARGET=RACEBASE
|
||||||
- TARGET=REVO
|
# - TARGET=RCEXPLORERF3
|
||||||
|
# - TARGET=REVO
|
||||||
|
# - TARGET=REVOLT
|
||||||
# - TARGET=REVONANO
|
# - TARGET=REVONANO
|
||||||
# - TARGET=REVO_OPBL
|
# - TARGET=REVO_OPBL
|
||||||
# - TARGET=RMDO
|
# - TARGET=RMDO
|
||||||
# - TARGET=SINGULARITY
|
# - TARGET=SINGULARITY
|
||||||
- TARGET=SIRINFPV
|
# - TARGET=SIRINFPV
|
||||||
- TARGET=SPARKY
|
# - TARGET=SOULF4
|
||||||
|
# - TARGET=SPARKY
|
||||||
# - TARGET=SPARKY2
|
# - TARGET=SPARKY2
|
||||||
# - TARGET=SPARKY_OPBL
|
# - TARGET=SPRACINGF3
|
||||||
- TARGET=SPRACINGF3
|
# - TARGET=SPRACINGF3EVO
|
||||||
- TARGET=SPRACINGF3EVO
|
|
||||||
# - TARGET=SPRACINGF3MINI
|
# - TARGET=SPRACINGF3MINI
|
||||||
- TARGET=STM32F3DISCOVERY
|
# - TARGET=STM32F3DISCOVERY
|
||||||
# - TARGET=VRRACE
|
# - TARGET=VRRACE
|
||||||
# - TARGET=X_RACERSPI
|
# - TARGET=X_RACERSPI
|
||||||
|
# - TARGET=YUPIF4
|
||||||
# - TARGET=ZCOREF3
|
# - TARGET=ZCOREF3
|
||||||
# - TARGET=RCEXPLORERF3
|
|
||||||
|
|
||||||
# use new docker environment
|
# use new docker environment
|
||||||
sudo: false
|
sudo: false
|
||||||
|
|
||||||
|
git:
|
||||||
|
depth: 5
|
||||||
|
|
||||||
addons:
|
addons:
|
||||||
apt:
|
apt:
|
||||||
packages:
|
packages:
|
||||||
- build-essential
|
|
||||||
- git
|
|
||||||
- libc6-i386
|
- libc6-i386
|
||||||
- zlib1g-dev
|
|
||||||
- libssl-dev
|
|
||||||
- wkhtmltopdf
|
|
||||||
- libxml2-dev
|
|
||||||
- libxslt-dev
|
|
||||||
|
|
||||||
# We use cpp for unit tests, and c for the main project.
|
# We use cpp for unit tests, and c for the main project.
|
||||||
language: cpp
|
language: cpp
|
||||||
|
@ -75,10 +81,17 @@ compiler: clang
|
||||||
install:
|
install:
|
||||||
- make arm_sdk_install
|
- make arm_sdk_install
|
||||||
|
|
||||||
before_script: tools/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-gcc --version
|
before_script:
|
||||||
|
- tools/gcc-arm-none-eabi-5_4-2016q3/bin/arm-none-eabi-gcc --version
|
||||||
|
- clang --version
|
||||||
|
- clang++ --version
|
||||||
|
|
||||||
script: ./.travis.sh
|
script: ./.travis.sh
|
||||||
|
|
||||||
cache: apt
|
cache:
|
||||||
|
directories:
|
||||||
|
- downloads
|
||||||
|
- tools
|
||||||
|
|
||||||
#notifications:
|
#notifications:
|
||||||
# irc: "chat.freenode.net#cleanflight"
|
# irc: "chat.freenode.net#cleanflight"
|
||||||
|
@ -93,4 +106,3 @@ notifications:
|
||||||
on_success: always # options: [always|never|change] default: always
|
on_success: always # options: [always|never|change] default: always
|
||||||
on_failure: always # options: [always|never|change] default: always
|
on_failure: always # options: [always|never|change] default: always
|
||||||
on_start: always # options: [always|never|change] default: always
|
on_start: always # options: [always|never|change] default: always
|
||||||
|
|
||||||
|
|
48
Makefile
48
Makefile
|
@ -45,10 +45,16 @@ export AT := @
|
||||||
ifndef V
|
ifndef V
|
||||||
export V0 :=
|
export V0 :=
|
||||||
export V1 := $(AT)
|
export V1 := $(AT)
|
||||||
|
export STDOUT :=
|
||||||
else ifeq ($(V), 0)
|
else ifeq ($(V), 0)
|
||||||
export V0 := $(AT)
|
export V0 := $(AT)
|
||||||
export V1 := $(AT)
|
export V1 := $(AT)
|
||||||
|
export STDOUT:= "> /dev/null"
|
||||||
|
export MAKE := $(MAKE) --no-print-directory
|
||||||
else ifeq ($(V), 1)
|
else ifeq ($(V), 1)
|
||||||
|
export V0 :=
|
||||||
|
export V1 :=
|
||||||
|
export STDOUT :=
|
||||||
endif
|
endif
|
||||||
|
|
||||||
###############################################################################
|
###############################################################################
|
||||||
|
@ -485,10 +491,12 @@ COMMON_SRC = \
|
||||||
drivers/bus_i2c_soft.c \
|
drivers/bus_i2c_soft.c \
|
||||||
drivers/bus_spi.c \
|
drivers/bus_spi.c \
|
||||||
drivers/bus_spi_soft.c \
|
drivers/bus_spi_soft.c \
|
||||||
|
drivers/display.c \
|
||||||
drivers/exti.c \
|
drivers/exti.c \
|
||||||
drivers/gyro_sync.c \
|
drivers/gyro_sync.c \
|
||||||
drivers/io.c \
|
drivers/io.c \
|
||||||
drivers/light_led.c \
|
drivers/light_led.c \
|
||||||
|
drivers/resource.c \
|
||||||
drivers/rx_nrf24l01.c \
|
drivers/rx_nrf24l01.c \
|
||||||
drivers/rx_spi.c \
|
drivers/rx_spi.c \
|
||||||
drivers/rx_xn297.c \
|
drivers/rx_xn297.c \
|
||||||
|
@ -550,6 +558,14 @@ COMMON_SRC = \
|
||||||
HIGHEND_SRC = \
|
HIGHEND_SRC = \
|
||||||
blackbox/blackbox.c \
|
blackbox/blackbox.c \
|
||||||
blackbox/blackbox_io.c \
|
blackbox/blackbox_io.c \
|
||||||
|
cms/cms.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_osd.c \
|
||||||
|
cms/cms_menu_vtx.c \
|
||||||
common/colorconversion.c \
|
common/colorconversion.c \
|
||||||
drivers/display_ug2864hsweg01.c \
|
drivers/display_ug2864hsweg01.c \
|
||||||
drivers/light_ws2811strip.c \
|
drivers/light_ws2811strip.c \
|
||||||
|
@ -559,9 +575,13 @@ HIGHEND_SRC = \
|
||||||
flight/gtune.c \
|
flight/gtune.c \
|
||||||
flight/navigation.c \
|
flight/navigation.c \
|
||||||
flight/gps_conversion.c \
|
flight/gps_conversion.c \
|
||||||
|
io/dashboard.c \
|
||||||
|
io/displayport_max7456.c \
|
||||||
|
io/displayport_msp.c \
|
||||||
|
io/displayport_oled.c \
|
||||||
io/gps.c \
|
io/gps.c \
|
||||||
io/ledstrip.c \
|
io/ledstrip.c \
|
||||||
io/dashboard.c \
|
io/osd.c \
|
||||||
sensors/sonar.c \
|
sensors/sonar.c \
|
||||||
sensors/barometer.c \
|
sensors/barometer.c \
|
||||||
telemetry/telemetry.c \
|
telemetry/telemetry.c \
|
||||||
|
@ -720,8 +740,8 @@ CCACHE :=
|
||||||
endif
|
endif
|
||||||
|
|
||||||
# Tool names
|
# Tool names
|
||||||
CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
|
CROSS_CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc
|
||||||
CPP := $(CCACHE) $(ARM_SDK_PREFIX)g++
|
CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++
|
||||||
OBJCOPY := $(ARM_SDK_PREFIX)objcopy
|
OBJCOPY := $(ARM_SDK_PREFIX)objcopy
|
||||||
SIZE := $(ARM_SDK_PREFIX)size
|
SIZE := $(ARM_SDK_PREFIX)size
|
||||||
|
|
||||||
|
@ -734,11 +754,7 @@ OPTIMIZE = -O0
|
||||||
LTO_FLAGS = $(OPTIMIZE)
|
LTO_FLAGS = $(OPTIMIZE)
|
||||||
else
|
else
|
||||||
OPTIMIZE = -Os
|
OPTIMIZE = -Os
|
||||||
ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
|
|
||||||
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
|
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
|
||||||
else
|
|
||||||
LTO_FLAGS = -flto -fuse-linker-plugin $(OPTIMIZE)
|
|
||||||
endif
|
|
||||||
endif
|
endif
|
||||||
|
|
||||||
DEBUG_FLAGS = -ggdb3 -DDEBUG
|
DEBUG_FLAGS = -ggdb3 -DDEBUG
|
||||||
|
@ -817,26 +833,26 @@ $(TARGET_BIN): $(TARGET_ELF)
|
||||||
$(V0) $(OBJCOPY) -O binary $< $@
|
$(V0) $(OBJCOPY) -O binary $< $@
|
||||||
|
|
||||||
$(TARGET_ELF): $(TARGET_OBJS)
|
$(TARGET_ELF): $(TARGET_OBJS)
|
||||||
$(V1) echo LD $(notdir $@)
|
$(V1) echo Linking $(TARGET)
|
||||||
$(V1) $(CC) -o $@ $^ $(LDFLAGS)
|
$(V1) $(CROSS_CC) -o $@ $^ $(LDFLAGS)
|
||||||
$(V0) $(SIZE) $(TARGET_ELF)
|
$(V0) $(SIZE) $(TARGET_ELF)
|
||||||
|
|
||||||
# Compile
|
# Compile
|
||||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.c
|
$(OBJECT_DIR)/$(TARGET)/%.o: %.c
|
||||||
$(V1) mkdir -p $(dir $@)
|
$(V1) mkdir -p $(dir $@)
|
||||||
$(V1) echo %% $(notdir $<)
|
$(V1) echo "%% $(notdir $<)" "$(STDOUT)"
|
||||||
$(V1) $(CC) -c -o $@ $(CFLAGS) $<
|
$(V1) $(CROSS_CC) -c -o $@ $(CFLAGS) $<
|
||||||
|
|
||||||
# Assemble
|
# Assemble
|
||||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.s
|
$(OBJECT_DIR)/$(TARGET)/%.o: %.s
|
||||||
$(V1) mkdir -p $(dir $@)
|
$(V1) mkdir -p $(dir $@)
|
||||||
$(V1) echo %% $(notdir $<)
|
$(V1) echo "%% $(notdir $<)" "$(STDOUT)"
|
||||||
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
|
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||||
|
|
||||||
$(OBJECT_DIR)/$(TARGET)/%.o: %.S
|
$(OBJECT_DIR)/$(TARGET)/%.o: %.S
|
||||||
$(V1) mkdir -p $(dir $@)
|
$(V1) mkdir -p $(dir $@)
|
||||||
$(V1) echo %% $(notdir $<)
|
$(V1) echo "%% $(notdir $<)" "$(STDOUT)"
|
||||||
$(V1) $(CC) -c -o $@ $(ASFLAGS) $<
|
$(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $<
|
||||||
|
|
||||||
## sample : Build all sample (travis) targets
|
## sample : Build all sample (travis) targets
|
||||||
sample: $(SAMPLE_TARGETS)
|
sample: $(SAMPLE_TARGETS)
|
||||||
|
@ -948,7 +964,7 @@ targets:
|
||||||
## test : run the cleanflight test suite
|
## test : run the cleanflight test suite
|
||||||
## junittest : run the cleanflight test suite, producing Junit XML result files.
|
## junittest : run the cleanflight test suite, producing Junit XML result files.
|
||||||
test junittest:
|
test junittest:
|
||||||
$(V0) cd src/test && $(MAKE) $@ || true
|
$(V0) cd src/test && $(MAKE) $@
|
||||||
|
|
||||||
# rebuild everything when makefile changes
|
# rebuild everything when makefile changes
|
||||||
$(TARGET_OBJS) : Makefile
|
$(TARGET_OBJS) : Makefile
|
||||||
|
|
2
Vagrantfile
vendored
2
Vagrantfile
vendored
|
@ -21,7 +21,7 @@ Vagrant.configure(2) do |config|
|
||||||
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi
|
apt-get remove -y binutils-arm-none-eabi gcc-arm-none-eabi
|
||||||
add-apt-repository ppa:team-gcc-arm-embedded/ppa
|
add-apt-repository ppa:team-gcc-arm-embedded/ppa
|
||||||
apt-get update
|
apt-get update
|
||||||
apt-get install -y git ccache gcc-arm-embedded=5-2016q2-1~trusty1
|
apt-get install -y git ccache gcc-arm-embedded=5-2016q3-1~trusty1
|
||||||
SHELL
|
SHELL
|
||||||
end
|
end
|
||||||
|
|
||||||
|
|
|
@ -475,6 +475,7 @@ __ALIGN_BEGIN uint8_t USBD_CDC_OtherSpeedCfgDesc[USB_CDC_CONFIG_DESC_SIZ] __ALIG
|
||||||
static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
|
(void)cfgidx;
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
USBD_CDC_HandleTypeDef *hcdc;
|
USBD_CDC_HandleTypeDef *hcdc;
|
||||||
|
|
||||||
|
@ -563,6 +564,7 @@ static uint8_t USBD_CDC_Init (USBD_HandleTypeDef *pdev,
|
||||||
static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
static uint8_t USBD_CDC_DeInit (USBD_HandleTypeDef *pdev,
|
||||||
uint8_t cfgidx)
|
uint8_t cfgidx)
|
||||||
{
|
{
|
||||||
|
(void)cfgidx;
|
||||||
uint8_t ret = 0;
|
uint8_t ret = 0;
|
||||||
|
|
||||||
/* Open EP IN */
|
/* Open EP IN */
|
||||||
|
@ -663,6 +665,7 @@ static uint8_t USBD_CDC_Setup (USBD_HandleTypeDef *pdev,
|
||||||
*/
|
*/
|
||||||
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
static uint8_t USBD_CDC_DataIn (USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
|
(void)epnum;
|
||||||
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
USBD_CDC_HandleTypeDef *hcdc = (USBD_CDC_HandleTypeDef*) pdev->pClassData;
|
||||||
|
|
||||||
if(pdev->pClassData != NULL)
|
if(pdev->pClassData != NULL)
|
||||||
|
|
|
@ -212,6 +212,7 @@ USBD_StatusTypeDef USBD_Stop (USBD_HandleTypeDef *pdev)
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_RunTestMode (USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
|
(void)pdev;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -508,6 +509,8 @@ USBD_StatusTypeDef USBD_LL_SOF(USBD_HandleTypeDef *pdev)
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
|
(void)pdev;
|
||||||
|
(void)epnum;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -519,6 +522,8 @@ USBD_StatusTypeDef USBD_LL_IsoINIncomplete(USBD_HandleTypeDef *pdev, uint8_t ep
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t epnum)
|
||||||
{
|
{
|
||||||
|
(void)pdev;
|
||||||
|
(void)epnum;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -530,6 +535,7 @@ USBD_StatusTypeDef USBD_LL_IsoOUTIncomplete(USBD_HandleTypeDef *pdev, uint8_t e
|
||||||
*/
|
*/
|
||||||
USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev)
|
USBD_StatusTypeDef USBD_LL_DevConnected(USBD_HandleTypeDef *pdev)
|
||||||
{
|
{
|
||||||
|
(void)pdev;
|
||||||
return USBD_OK;
|
return USBD_OK;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -716,6 +716,7 @@ void USBD_ParseSetupRequest(USBD_SetupReqTypedef *req, uint8_t *pdata)
|
||||||
void USBD_CtlError( USBD_HandleTypeDef *pdev ,
|
void USBD_CtlError( USBD_HandleTypeDef *pdev ,
|
||||||
USBD_SetupReqTypedef *req)
|
USBD_SetupReqTypedef *req)
|
||||||
{
|
{
|
||||||
|
(void)req;
|
||||||
USBD_LL_StallEP(pdev , 0x80);
|
USBD_LL_StallEP(pdev , 0x80);
|
||||||
USBD_LL_StallEP(pdev , 0);
|
USBD_LL_StallEP(pdev , 0);
|
||||||
}
|
}
|
||||||
|
|
|
@ -756,6 +756,7 @@ HAL_StatusTypeDef HAL_ADCEx_MultiModeStop_DMA(ADC_HandleTypeDef* hadc)
|
||||||
*/
|
*/
|
||||||
uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc)
|
uint32_t HAL_ADCEx_MultiModeGetValue(ADC_HandleTypeDef* hadc)
|
||||||
{
|
{
|
||||||
|
(void)hadc;
|
||||||
/* Return the multi mode conversion value */
|
/* Return the multi mode conversion value */
|
||||||
return ADC->CDR;
|
return ADC->CDR;
|
||||||
}
|
}
|
||||||
|
|
|
@ -2845,6 +2845,7 @@ HAL_StatusTypeDef HAL_I2C_DisableListen_IT(I2C_HandleTypeDef *hi2c)
|
||||||
*/
|
*/
|
||||||
HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress)
|
HAL_StatusTypeDef HAL_I2C_Master_Abort_IT(I2C_HandleTypeDef *hi2c, uint16_t DevAddress)
|
||||||
{
|
{
|
||||||
|
(void)DevAddress;
|
||||||
if(hi2c->Mode == HAL_I2C_MODE_MASTER)
|
if(hi2c->Mode == HAL_I2C_MODE_MASTER)
|
||||||
{
|
{
|
||||||
/* Process Locked */
|
/* Process Locked */
|
||||||
|
@ -3684,6 +3685,7 @@ static HAL_StatusTypeDef I2C_RequestMemoryRead(I2C_HandleTypeDef *hi2c, uint16_t
|
||||||
*/
|
*/
|
||||||
static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
|
static void I2C_ITAddrCplt(I2C_HandleTypeDef *hi2c, uint32_t ITFlags)
|
||||||
{
|
{
|
||||||
|
(void)ITFlags;
|
||||||
uint8_t transferdirection = 0;
|
uint8_t transferdirection = 0;
|
||||||
uint16_t slaveaddrcode = 0;
|
uint16_t slaveaddrcode = 0;
|
||||||
uint16_t ownadd1code = 0;
|
uint16_t ownadd1code = 0;
|
||||||
|
@ -4254,6 +4256,7 @@ static void I2C_DMASlaveTransmitCplt(DMA_HandleTypeDef *hdma)
|
||||||
/* No specific action, Master fully manage the generation of STOP condition */
|
/* No specific action, Master fully manage the generation of STOP condition */
|
||||||
/* Mean that this generation can arrive at any time, at the end or during DMA process */
|
/* Mean that this generation can arrive at any time, at the end or during DMA process */
|
||||||
/* So STOP condition should be manage through Interrupt treatment */
|
/* So STOP condition should be manage through Interrupt treatment */
|
||||||
|
(void)hdma;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
@ -4308,6 +4311,7 @@ static void I2C_DMASlaveReceiveCplt(DMA_HandleTypeDef *hdma)
|
||||||
/* No specific action, Master fully manage the generation of STOP condition */
|
/* No specific action, Master fully manage the generation of STOP condition */
|
||||||
/* Mean that this generation can arrive at any time, at the end or during DMA process */
|
/* Mean that this generation can arrive at any time, at the end or during DMA process */
|
||||||
/* So STOP condition should be manage through Interrupt treatment */
|
/* So STOP condition should be manage through Interrupt treatment */
|
||||||
|
(void)hdma;
|
||||||
}
|
}
|
||||||
|
|
||||||
/**
|
/**
|
||||||
|
|
|
@ -404,6 +404,7 @@ void HAL_PWR_DisableWakeUpPin(uint32_t WakeUpPinx)
|
||||||
*/
|
*/
|
||||||
void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry)
|
void HAL_PWR_EnterSLEEPMode(uint32_t Regulator, uint8_t SLEEPEntry)
|
||||||
{
|
{
|
||||||
|
(void)Regulator;
|
||||||
/* Check the parameters */
|
/* Check the parameters */
|
||||||
assert_param(IS_PWR_REGULATOR(Regulator));
|
assert_param(IS_PWR_REGULATOR(Regulator));
|
||||||
assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry));
|
assert_param(IS_PWR_SLEEP_ENTRY(SLEEPEntry));
|
||||||
|
|
|
@ -2118,7 +2118,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start(TIM_HandleTypeDef *htim, uint32_t Outpu
|
||||||
|
|
||||||
No need to enable the counter, it's enabled automatically by hardware
|
No need to enable the counter, it's enabled automatically by hardware
|
||||||
(the counter starts in response to a stimulus and generate a pulse */
|
(the counter starts in response to a stimulus and generate a pulse */
|
||||||
|
(void)OutputChannel;
|
||||||
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
|
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_ENABLE);
|
||||||
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
|
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_ENABLE);
|
||||||
|
|
||||||
|
@ -2150,6 +2150,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Stop(TIM_HandleTypeDef *htim, uint32_t Output
|
||||||
if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
|
if TIM_CHANNEL_1 is used as input, the TIM_CHANNEL_2 will be used as output
|
||||||
in all combinations, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */
|
in all combinations, the TIM_CHANNEL_1 and TIM_CHANNEL_2 should be disabled together */
|
||||||
|
|
||||||
|
(void)OutputChannel;
|
||||||
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
|
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_1, TIM_CCx_DISABLE);
|
||||||
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
|
TIM_CCxChannelCmd(htim->Instance, TIM_CHANNEL_2, TIM_CCx_DISABLE);
|
||||||
|
|
||||||
|
@ -2187,6 +2188,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t Ou
|
||||||
No need to enable the counter, it's enabled automatically by hardware
|
No need to enable the counter, it's enabled automatically by hardware
|
||||||
(the counter starts in response to a stimulus and generate a pulse */
|
(the counter starts in response to a stimulus and generate a pulse */
|
||||||
|
|
||||||
|
(void)OutputChannel;
|
||||||
/* Enable the TIM Capture/Compare 1 interrupt */
|
/* Enable the TIM Capture/Compare 1 interrupt */
|
||||||
__HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
|
__HAL_TIM_ENABLE_IT(htim, TIM_IT_CC1);
|
||||||
|
|
||||||
|
@ -2218,6 +2220,7 @@ HAL_StatusTypeDef HAL_TIM_OnePulse_Start_IT(TIM_HandleTypeDef *htim, uint32_t Ou
|
||||||
*/
|
*/
|
||||||
HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
|
HAL_StatusTypeDef HAL_TIM_OnePulse_Stop_IT(TIM_HandleTypeDef *htim, uint32_t OutputChannel)
|
||||||
{
|
{
|
||||||
|
(void)OutputChannel;
|
||||||
/* Disable the TIM Capture/Compare 1 interrupt */
|
/* Disable the TIM Capture/Compare 1 interrupt */
|
||||||
__HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
|
__HAL_TIM_DISABLE_IT(htim, TIM_IT_CC1);
|
||||||
|
|
||||||
|
|
|
@ -25,36 +25,47 @@ ARM_SDK_URL_BASE := https://launchpad.net/gcc-arm-embedded/5.0/5-2016-q3-update
|
||||||
|
|
||||||
# source: https://launchpad.net/gcc-arm-embedded/5.0/
|
# source: https://launchpad.net/gcc-arm-embedded/5.0/
|
||||||
ifdef LINUX
|
ifdef LINUX
|
||||||
arm_sdk_install: ARM_SDK_URL := $(ARM_SDK_URL_BASE)-linux.tar.bz2
|
ARM_SDK_URL := $(ARM_SDK_URL_BASE)-linux.tar.bz2
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ifdef MACOSX
|
ifdef MACOSX
|
||||||
arm_sdk_install: ARM_SDK_URL := $(ARM_SDK_URL_BASE)-mac.tar.bz2
|
ARM_SDK_URL := $(ARM_SDK_URL_BASE)-mac.tar.bz2
|
||||||
endif
|
endif
|
||||||
|
|
||||||
ifdef WINDOWS
|
ifdef WINDOWS
|
||||||
arm_sdk_install: ARM_SDK_URL := $(ARM_SDK_URL_BASE)-win32.zip
|
ARM_SDK_URL := $(ARM_SDK_URL_BASE)-win32.zip
|
||||||
endif
|
endif
|
||||||
|
|
||||||
arm_sdk_install: ARM_SDK_FILE := $(notdir $(ARM_SDK_URL))
|
ARM_SDK_FILE := $(notdir $(ARM_SDK_URL))
|
||||||
# order-only prereq on directory existance:
|
|
||||||
arm_sdk_install: | $(DL_DIR) $(TOOLS_DIR)
|
|
||||||
arm_sdk_install: arm_sdk_clean
|
|
||||||
ifneq ($(OSFAMILY), windows)
|
|
||||||
# download the source only if it's newer than what we already have
|
|
||||||
$(V1) curl -L -k -o "$(DL_DIR)/$(ARM_SDK_FILE)" "$(ARM_SDK_URL)"
|
|
||||||
|
|
||||||
|
SDK_INSTALL_MARKER := $(ARM_SDK_DIR)/bin/arm-none-eabi-gcc-$(GCC_REQUIRED_VERSION)
|
||||||
|
|
||||||
|
# order-only prereq on directory existance:
|
||||||
|
arm_sdk_install: | $(TOOLS_DIR)
|
||||||
|
|
||||||
|
arm_sdk_install: arm_sdk_download $(SDK_INSTALL_MARKER)
|
||||||
|
|
||||||
|
$(SDK_INSTALL_MARKER):
|
||||||
|
ifneq ($(OSFAMILY), windows)
|
||||||
# binary only release so just extract it
|
# binary only release so just extract it
|
||||||
$(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)"
|
$(V1) tar -C $(TOOLS_DIR) -xjf "$(DL_DIR)/$(ARM_SDK_FILE)"
|
||||||
else
|
else
|
||||||
$(V1) curl -L -k -o "$(DL_DIR)/$(ARM_SDK_FILE)" "$(ARM_SDK_URL)"
|
|
||||||
$(V1) unzip -q -d $(ARM_SDK_DIR) "$(DL_DIR)/$(ARM_SDK_FILE)"
|
$(V1) unzip -q -d $(ARM_SDK_DIR) "$(DL_DIR)/$(ARM_SDK_FILE)"
|
||||||
endif
|
endif
|
||||||
|
|
||||||
|
.PHONY: arm_sdk_download
|
||||||
|
arm_sdk_download: | $(DL_DIR)
|
||||||
|
arm_sdk_download: $(DL_DIR)/$(ARM_SDK_FILE)
|
||||||
|
$(DL_DIR)/$(ARM_SDK_FILE):
|
||||||
|
# download the source only if it's newer than what we already have
|
||||||
|
$(V1) curl -L -k -o "$(DL_DIR)/$(ARM_SDK_FILE)" -z "$(DL_DIR)/$(ARM_SDK_FILE)" "$(ARM_SDK_URL)"
|
||||||
|
|
||||||
|
|
||||||
## arm_sdk_clean : Uninstall Arm SDK
|
## arm_sdk_clean : Uninstall Arm SDK
|
||||||
.PHONY: arm_sdk_clean
|
.PHONY: arm_sdk_clean
|
||||||
arm_sdk_clean:
|
arm_sdk_clean:
|
||||||
$(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR)
|
$(V1) [ ! -d "$(ARM_SDK_DIR)" ] || $(RM) -r $(ARM_SDK_DIR)
|
||||||
|
$(V1) [ ! -d "$(DL_DIR)" ] || $(RM) -r $(DL_DIR)
|
||||||
|
|
||||||
.PHONY: openocd_win_install
|
.PHONY: openocd_win_install
|
||||||
|
|
||||||
|
|
|
@ -1169,7 +1169,7 @@ static bool blackboxWriteSysinfo()
|
||||||
|
|
||||||
switch (xmitState.headerIndex) {
|
switch (xmitState.headerIndex) {
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
BLACKBOX_PRINT_HEADER_LINE("Firmware type:%s", "Cleanflight");
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:Betaflight %s (%s) %s", FC_VERSION_STRING, shortGitRevision, targetName);
|
BLACKBOX_PRINT_HEADER_LINE("Firmware revision:%s %s (%s) %s", FC_FIRMWARE_NAME, FC_VERSION_STRING, shortGitRevision, targetName);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
BLACKBOX_PRINT_HEADER_LINE("Firmware date:%s %s", buildDate, buildTime);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
|
BLACKBOX_PRINT_HEADER_LINE("Craft name:%s", masterConfig.name);
|
||||||
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
BLACKBOX_PRINT_HEADER_LINE("P interval:%d/%d", masterConfig.blackbox_rate_num, masterConfig.blackbox_rate_denom);
|
||||||
|
|
|
@ -15,6 +15,7 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#define FC_FIRMWARE_NAME "Betaflight"
|
||||||
#define FC_VERSION_MAJOR 3 // increment when a major release is made (big new feature, etc)
|
#define FC_VERSION_MAJOR 3 // increment when a major release is made (big new feature, etc)
|
||||||
#define FC_VERSION_MINOR 1 // increment when a minor release is made (small new feature, change etc)
|
#define FC_VERSION_MINOR 1 // 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 FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed
|
||||||
|
|
871
src/main/cms/cms.c
Normal file
871
src/main/cms/cms.c
Normal file
|
@ -0,0 +1,871 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
/*
|
||||||
|
Original OSD code created by Marcin Baliniak
|
||||||
|
OSD-CMS separation by jflyper
|
||||||
|
CMS-displayPort separation by jflyper and martinbudden
|
||||||
|
*/
|
||||||
|
|
||||||
|
//#define CMS_MENU_DEBUG // For external menu content creators
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "build/build_config.h"
|
||||||
|
#include "build/debug.h"
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_menu_builtin.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
|
||||||
|
#include "common/typeconversion.h"
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
// For 'ARM' related
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
// For rcData, stopAllMotors, stopPwmAllMotors
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
// For VISIBLE* (Actually, included by config_master.h)
|
||||||
|
#include "io/osd.h"
|
||||||
|
|
||||||
|
// DisplayPort management
|
||||||
|
|
||||||
|
#ifndef CMS_MAX_DEVICE
|
||||||
|
#define CMS_MAX_DEVICE 4
|
||||||
|
#endif
|
||||||
|
|
||||||
|
static displayPort_t *pCurrentDisplay;
|
||||||
|
|
||||||
|
static displayPort_t *cmsDisplayPorts[CMS_MAX_DEVICE];
|
||||||
|
static int cmsDeviceCount;
|
||||||
|
static int cmsCurrentDevice = -1;
|
||||||
|
|
||||||
|
bool cmsDisplayPortRegister(displayPort_t *pDisplay)
|
||||||
|
{
|
||||||
|
if (cmsDeviceCount == CMS_MAX_DEVICE)
|
||||||
|
return false;
|
||||||
|
|
||||||
|
cmsDisplayPorts[cmsDeviceCount++] = pDisplay;
|
||||||
|
|
||||||
|
return true;
|
||||||
|
}
|
||||||
|
|
||||||
|
static displayPort_t *cmsDisplayPortSelectCurrent(void)
|
||||||
|
{
|
||||||
|
if (cmsDeviceCount == 0)
|
||||||
|
return NULL;
|
||||||
|
|
||||||
|
if (cmsCurrentDevice < 0)
|
||||||
|
cmsCurrentDevice = 0;
|
||||||
|
|
||||||
|
return cmsDisplayPorts[cmsCurrentDevice];
|
||||||
|
}
|
||||||
|
|
||||||
|
static displayPort_t *cmsDisplayPortSelectNext(void)
|
||||||
|
{
|
||||||
|
if (cmsDeviceCount == 0)
|
||||||
|
return NULL;
|
||||||
|
|
||||||
|
cmsCurrentDevice = (cmsCurrentDevice + 1) % cmsDeviceCount; // -1 Okay
|
||||||
|
|
||||||
|
return cmsDisplayPorts[cmsCurrentDevice];
|
||||||
|
}
|
||||||
|
|
||||||
|
#define CMS_UPDATE_INTERVAL_US 50000 // Interval of key scans (microsec)
|
||||||
|
#define CMS_POLL_INTERVAL_US 100000 // Interval of polling dynamic values (microsec)
|
||||||
|
|
||||||
|
// XXX LEFT_MENU_COLUMN and RIGHT_MENU_COLUMN must be adjusted
|
||||||
|
// dynamically depending on size of the active output device,
|
||||||
|
// or statically to accomodate sizes of all supported devices.
|
||||||
|
//
|
||||||
|
// Device characteristics
|
||||||
|
// OLED
|
||||||
|
// 21 cols x 8 rows
|
||||||
|
// 128x64 with 5x7 (6x8) : 21 cols x 8 rows
|
||||||
|
// MAX7456 (PAL)
|
||||||
|
// 30 cols x 16 rows
|
||||||
|
// MAX7456 (NTSC)
|
||||||
|
// 30 cols x 13 rows
|
||||||
|
// HoTT Telemetry Screen
|
||||||
|
// 21 cols x 8 rows
|
||||||
|
//
|
||||||
|
|
||||||
|
#define LEFT_MENU_COLUMN 1
|
||||||
|
#define RIGHT_MENU_COLUMN(p) ((p)->cols - 8)
|
||||||
|
#define MAX_MENU_ITEMS(p) ((p)->rows - 2)
|
||||||
|
|
||||||
|
static bool cmsInMenu = false;
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED const CMS_Menu *currentMenu; // Points to top entry of the current page
|
||||||
|
|
||||||
|
// XXX Does menu backing support backing into second page???
|
||||||
|
|
||||||
|
static const CMS_Menu *menuStack[10]; // Stack to save menu transition
|
||||||
|
static uint8_t menuStackHistory[10];// cursorRow in a stacked menu
|
||||||
|
static uint8_t menuStackIdx = 0;
|
||||||
|
|
||||||
|
static OSD_Entry *pageTop; // Points to top entry of the current page
|
||||||
|
static OSD_Entry *pageTopAlt; // Only 2 pages are allowed (for now)
|
||||||
|
static uint8_t maxRow; // Max row in the current page
|
||||||
|
|
||||||
|
static int8_t cursorRow;
|
||||||
|
|
||||||
|
#ifdef CMS_MENU_DEBUG // For external menu content creators
|
||||||
|
|
||||||
|
static char menuErrLabel[21 + 1] = "RANDOM DATA";
|
||||||
|
|
||||||
|
static OSD_Entry menuErrEntries[] = {
|
||||||
|
{ "BROKEN MENU", OME_Label, NULL, NULL, 0 },
|
||||||
|
{ menuErrLabel, OME_Label, NULL, NULL, 0 },
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu menuErr = {
|
||||||
|
"MENUERR",
|
||||||
|
OME_MENU,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
NULL,
|
||||||
|
menuErrEntries,
|
||||||
|
};
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Stick/key detection
|
||||||
|
|
||||||
|
#define IS_HI(X) (rcData[X] > 1750)
|
||||||
|
#define IS_LO(X) (rcData[X] < 1250)
|
||||||
|
#define IS_MID(X) (rcData[X] > 1250 && rcData[X] < 1750)
|
||||||
|
|
||||||
|
//key definiotion because API provide menu navigation over MSP/GUI app - not used NOW
|
||||||
|
#define KEY_ENTER 0
|
||||||
|
#define KEY_UP 1
|
||||||
|
#define KEY_DOWN 2
|
||||||
|
#define KEY_LEFT 3
|
||||||
|
#define KEY_RIGHT 4
|
||||||
|
#define KEY_ESC 5
|
||||||
|
|
||||||
|
#define BUTTON_TIME 250 // msec
|
||||||
|
#define BUTTON_PAUSE 500 // msec
|
||||||
|
|
||||||
|
static void cmsUpdateMaxRow(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
maxRow = 0;
|
||||||
|
|
||||||
|
for (const OSD_Entry *ptr = pageTop; ptr->type != OME_END; ptr++) {
|
||||||
|
maxRow++;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (maxRow > MAX_MENU_ITEMS(instance)) {
|
||||||
|
maxRow = MAX_MENU_ITEMS(instance);
|
||||||
|
}
|
||||||
|
|
||||||
|
maxRow--;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsFormatFloat(int32_t value, char *floatString)
|
||||||
|
{
|
||||||
|
uint8_t k;
|
||||||
|
// np. 3450
|
||||||
|
|
||||||
|
itoa(100000 + value, floatString, 10); // Create string from abs of integer value
|
||||||
|
|
||||||
|
// 103450
|
||||||
|
|
||||||
|
floatString[0] = floatString[1];
|
||||||
|
floatString[1] = floatString[2];
|
||||||
|
floatString[2] = '.';
|
||||||
|
|
||||||
|
// 03.450
|
||||||
|
// usuwam koncowe zera i kropke
|
||||||
|
// Keep the first decimal place
|
||||||
|
for (k = 5; k > 3; k--)
|
||||||
|
if (floatString[k] == '0' || floatString[k] == '.')
|
||||||
|
floatString[k] = 0;
|
||||||
|
else
|
||||||
|
break;
|
||||||
|
|
||||||
|
// oraz zero wiodonce
|
||||||
|
if (floatString[0] == '0')
|
||||||
|
floatString[0] = ' ';
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsPadToSize(char *buf, int size)
|
||||||
|
{
|
||||||
|
int i;
|
||||||
|
|
||||||
|
for (i = 0 ; i < size ; i++) {
|
||||||
|
if (buf[i] == 0)
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
for ( ; i < size ; i++) {
|
||||||
|
buf[i] = ' ';
|
||||||
|
}
|
||||||
|
|
||||||
|
buf[size] = 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static int cmsDrawMenuEntry(displayPort_t *pDisplay, OSD_Entry *p, uint8_t row)
|
||||||
|
{
|
||||||
|
char buff[10];
|
||||||
|
int cnt = 0;
|
||||||
|
|
||||||
|
switch (p->type) {
|
||||||
|
case OME_String:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, p->data);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_Submenu:
|
||||||
|
case OME_Funcall:
|
||||||
|
if (IS_PRINTVALUE(p)) {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, ">");
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_Bool:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
if (*((uint8_t *)(p->data))) {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "YES");
|
||||||
|
} else {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "NO ");
|
||||||
|
}
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_TAB: {
|
||||||
|
if (IS_PRINTVALUE(p)) {
|
||||||
|
OSD_TAB_t *ptr = p->data;
|
||||||
|
//cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 5, row, (char *)ptr->names[*ptr->val]);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, (char *)ptr->names[*ptr->val]);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
#ifdef OSD
|
||||||
|
case OME_VISIBLE:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
uint32_t address = (uint32_t)p->data;
|
||||||
|
uint16_t *val;
|
||||||
|
|
||||||
|
val = (uint16_t *)address;
|
||||||
|
|
||||||
|
if (VISIBLE(*val)) {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "YES");
|
||||||
|
} else {
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "NO ");
|
||||||
|
}
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
case OME_UINT8:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
OSD_UINT8_t *ptr = p->data;
|
||||||
|
itoa(*ptr->val, buff, 10);
|
||||||
|
cmsPadToSize(buff, 5);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_INT8:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
OSD_INT8_t *ptr = p->data;
|
||||||
|
itoa(*ptr->val, buff, 10);
|
||||||
|
cmsPadToSize(buff, 5);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_UINT16:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
OSD_UINT16_t *ptr = p->data;
|
||||||
|
itoa(*ptr->val, buff, 10);
|
||||||
|
cmsPadToSize(buff, 5);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_INT16:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
OSD_UINT16_t *ptr = p->data;
|
||||||
|
itoa(*ptr->val, buff, 10);
|
||||||
|
cmsPadToSize(buff, 5);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, buff);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_FLOAT:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
OSD_FLOAT_t *ptr = p->data;
|
||||||
|
cmsFormatFloat(*ptr->val * ptr->multipler, buff);
|
||||||
|
cmsPadToSize(buff, 5);
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay) - 1, row, buff); // XXX One char left ???
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_Label:
|
||||||
|
if (IS_PRINTVALUE(p) && p->data) {
|
||||||
|
// A label with optional string, immediately following text
|
||||||
|
cnt = displayWrite(pDisplay, LEFT_MENU_COLUMN + 2 + strlen(p->text), row, p->data);
|
||||||
|
CLR_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_OSD_Exit:
|
||||||
|
case OME_END:
|
||||||
|
case OME_Back:
|
||||||
|
break;
|
||||||
|
case OME_MENU:
|
||||||
|
// Fall through
|
||||||
|
default:
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
// Shouldn't happen. Notify creator of this menu content.
|
||||||
|
cnt = displayWrite(pDisplay, RIGHT_MENU_COLUMN(pDisplay), row, "BADENT");
|
||||||
|
#endif
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
|
||||||
|
return cnt;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs)
|
||||||
|
{
|
||||||
|
if (!pageTop)
|
||||||
|
return;
|
||||||
|
|
||||||
|
uint8_t i;
|
||||||
|
OSD_Entry *p;
|
||||||
|
uint8_t top = (pDisplay->rows - maxRow) / 2 - 1;
|
||||||
|
|
||||||
|
// Polled (dynamic) value display denominator.
|
||||||
|
|
||||||
|
bool drawPolled = false;
|
||||||
|
static uint32_t lastPolledUs = 0;
|
||||||
|
|
||||||
|
if (currentTimeUs > lastPolledUs + CMS_POLL_INTERVAL_US) {
|
||||||
|
drawPolled = true;
|
||||||
|
lastPolledUs = currentTimeUs;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint32_t room = displayTxBytesFree(pDisplay);
|
||||||
|
|
||||||
|
if (pDisplay->cleared) {
|
||||||
|
for (p = pageTop, i= 0; p->type != OME_END; p++, i++) {
|
||||||
|
SET_PRINTLABEL(p);
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
|
||||||
|
if (i > MAX_MENU_ITEMS(pDisplay)) // max per page
|
||||||
|
{
|
||||||
|
pageTopAlt = pageTop + MAX_MENU_ITEMS(pDisplay);
|
||||||
|
if (pageTopAlt->type == OME_END)
|
||||||
|
pageTopAlt = NULL;
|
||||||
|
}
|
||||||
|
|
||||||
|
pDisplay->cleared = false;
|
||||||
|
} else if (drawPolled) {
|
||||||
|
for (p = pageTop ; p <= pageTop + maxRow ; p++) {
|
||||||
|
if (IS_DYNAMIC(p))
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Cursor manipulation
|
||||||
|
|
||||||
|
while ((pageTop + cursorRow)->type == OME_Label) // skip label
|
||||||
|
cursorRow++;
|
||||||
|
|
||||||
|
if (pDisplay->cursorRow >= 0 && cursorRow != pDisplay->cursorRow) {
|
||||||
|
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, pDisplay->cursorRow + top, " ");
|
||||||
|
}
|
||||||
|
|
||||||
|
if (room < 30)
|
||||||
|
return;
|
||||||
|
|
||||||
|
if (pDisplay->cursorRow != cursorRow) {
|
||||||
|
room -= displayWrite(pDisplay, LEFT_MENU_COLUMN, cursorRow + top, " >");
|
||||||
|
pDisplay->cursorRow = cursorRow;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (room < 30)
|
||||||
|
return;
|
||||||
|
|
||||||
|
// Print text labels
|
||||||
|
for (i = 0, p = pageTop; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
|
||||||
|
if (IS_PRINTLABEL(p)) {
|
||||||
|
uint8_t coloff = LEFT_MENU_COLUMN;
|
||||||
|
coloff += (p->type == OME_Label) ? 1 : 2;
|
||||||
|
room -= displayWrite(pDisplay, coloff, i + top, p->text);
|
||||||
|
CLR_PRINTLABEL(p);
|
||||||
|
if (room < 30)
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Print values
|
||||||
|
|
||||||
|
// XXX Polled values at latter positions in the list may not be
|
||||||
|
// XXX printed if not enough room in the middle of the list.
|
||||||
|
|
||||||
|
for (i = 0, p = pageTop; i < MAX_MENU_ITEMS(pDisplay) && p->type != OME_END; i++, p++) {
|
||||||
|
if (IS_PRINTVALUE(p)) {
|
||||||
|
room -= cmsDrawMenuEntry(pDisplay, p, top + i);
|
||||||
|
if (room < 30)
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
long cmsMenuChange(displayPort_t *pDisplay, const void *ptr)
|
||||||
|
{
|
||||||
|
CMS_Menu *pMenu = (CMS_Menu *)ptr;
|
||||||
|
|
||||||
|
if (pMenu) {
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
if (pMenu->GUARD_type != OME_MENU) {
|
||||||
|
// ptr isn't pointing to a CMS_Menu.
|
||||||
|
if (pMenu->GUARD_type <= OME_MAX) {
|
||||||
|
strncpy(menuErrLabel, pMenu->GUARD_text, sizeof(menuErrLabel) - 1);
|
||||||
|
} else {
|
||||||
|
strncpy(menuErrLabel, "LABEL UNKNOWN", sizeof(menuErrLabel) - 1);
|
||||||
|
}
|
||||||
|
pMenu = &menuErr;
|
||||||
|
}
|
||||||
|
#endif
|
||||||
|
|
||||||
|
// Stack the current menu and move to a new menu.
|
||||||
|
// The (pMenu == curretMenu) case occurs when reopening for display sw
|
||||||
|
|
||||||
|
if (pMenu != currentMenu) {
|
||||||
|
menuStack[menuStackIdx] = currentMenu;
|
||||||
|
cursorRow += pageTop - currentMenu->entries; // Convert cursorRow to absolute value
|
||||||
|
menuStackHistory[menuStackIdx] = cursorRow;
|
||||||
|
menuStackIdx++;
|
||||||
|
|
||||||
|
currentMenu = pMenu;
|
||||||
|
cursorRow = 0;
|
||||||
|
|
||||||
|
if (pMenu->onEnter)
|
||||||
|
pMenu->onEnter();
|
||||||
|
}
|
||||||
|
|
||||||
|
pageTop = currentMenu->entries;
|
||||||
|
pageTopAlt = NULL;
|
||||||
|
|
||||||
|
displayClear(pDisplay);
|
||||||
|
cmsUpdateMaxRow(pDisplay);
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED long cmsMenuBack(displayPort_t *pDisplay)
|
||||||
|
{
|
||||||
|
// Let onExit function decide whether to allow exit or not.
|
||||||
|
|
||||||
|
if (currentMenu->onExit && currentMenu->onExit(pageTop + cursorRow) < 0)
|
||||||
|
return -1;
|
||||||
|
|
||||||
|
if (menuStackIdx) {
|
||||||
|
displayClear(pDisplay);
|
||||||
|
menuStackIdx--;
|
||||||
|
currentMenu = menuStack[menuStackIdx];
|
||||||
|
cursorRow = menuStackHistory[menuStackIdx];
|
||||||
|
|
||||||
|
// cursorRow is absolute offset of a focused entry when stacked.
|
||||||
|
// Convert it back to page and relative offset.
|
||||||
|
|
||||||
|
pageTop = currentMenu->entries; // Temporary for cmsUpdateMaxRow()
|
||||||
|
cmsUpdateMaxRow(pDisplay);
|
||||||
|
|
||||||
|
if (cursorRow > maxRow) {
|
||||||
|
// Cursor was in the second page.
|
||||||
|
pageTopAlt = currentMenu->entries;
|
||||||
|
pageTop = pageTopAlt + maxRow + 1;
|
||||||
|
cursorRow -= (maxRow + 1);
|
||||||
|
cmsUpdateMaxRow(pDisplay); // Update maxRow for the second page
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED void cmsMenuOpen(void)
|
||||||
|
{
|
||||||
|
if (!cmsInMenu) {
|
||||||
|
// New open
|
||||||
|
pCurrentDisplay = cmsDisplayPortSelectCurrent();
|
||||||
|
if (!pCurrentDisplay)
|
||||||
|
return;
|
||||||
|
cmsInMenu = true;
|
||||||
|
currentMenu = &menuMain;
|
||||||
|
DISABLE_ARMING_FLAG(OK_TO_ARM);
|
||||||
|
} else {
|
||||||
|
// Switch display
|
||||||
|
displayPort_t *pNextDisplay = cmsDisplayPortSelectNext();
|
||||||
|
if (pNextDisplay != pCurrentDisplay) {
|
||||||
|
displayRelease(pCurrentDisplay);
|
||||||
|
pCurrentDisplay = pNextDisplay;
|
||||||
|
} else {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
displayGrab(pCurrentDisplay); // grab the display for use by the CMS
|
||||||
|
cmsMenuChange(pCurrentDisplay, currentMenu);
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsTraverseGlobalExit(const CMS_Menu *pMenu)
|
||||||
|
{
|
||||||
|
debug[0]++;
|
||||||
|
|
||||||
|
for (const OSD_Entry *p = pMenu->entries; p->type != OME_END ; p++) {
|
||||||
|
if (p->type == OME_Submenu) {
|
||||||
|
cmsTraverseGlobalExit(p->data);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (pMenu->onGlobalExit) {
|
||||||
|
debug[1]++;
|
||||||
|
pMenu->onGlobalExit();
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
long cmsMenuExit(displayPort_t *pDisplay, const void *ptr)
|
||||||
|
{
|
||||||
|
if (ptr) {
|
||||||
|
displayClear(pDisplay);
|
||||||
|
|
||||||
|
displayWrite(pDisplay, 5, 3, "REBOOTING...");
|
||||||
|
displayResync(pDisplay); // Was max7456RefreshAll(); why at this timing?
|
||||||
|
|
||||||
|
stopMotors();
|
||||||
|
stopPwmAllMotors();
|
||||||
|
delay(200);
|
||||||
|
|
||||||
|
cmsTraverseGlobalExit(&menuMain);
|
||||||
|
|
||||||
|
if (currentMenu->onExit)
|
||||||
|
currentMenu->onExit((OSD_Entry *)NULL); // Forced exit
|
||||||
|
|
||||||
|
saveConfigAndNotify();
|
||||||
|
}
|
||||||
|
|
||||||
|
cmsInMenu = false;
|
||||||
|
|
||||||
|
displayRelease(pDisplay);
|
||||||
|
currentMenu = NULL;
|
||||||
|
|
||||||
|
if (ptr)
|
||||||
|
systemReset();
|
||||||
|
|
||||||
|
ENABLE_ARMING_FLAG(OK_TO_ARM);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
STATIC_UNIT_TESTED uint16_t cmsHandleKey(displayPort_t *pDisplay, uint8_t key)
|
||||||
|
{
|
||||||
|
uint16_t res = BUTTON_TIME;
|
||||||
|
OSD_Entry *p;
|
||||||
|
|
||||||
|
if (!currentMenu)
|
||||||
|
return res;
|
||||||
|
|
||||||
|
if (key == KEY_ESC) {
|
||||||
|
cmsMenuBack(pDisplay);
|
||||||
|
return BUTTON_PAUSE;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (key == KEY_DOWN) {
|
||||||
|
if (cursorRow < maxRow) {
|
||||||
|
cursorRow++;
|
||||||
|
} else {
|
||||||
|
if (pageTopAlt) { // we have another page
|
||||||
|
displayClear(pDisplay);
|
||||||
|
p = pageTopAlt;
|
||||||
|
pageTopAlt = pageTop;
|
||||||
|
pageTop = (OSD_Entry *)p;
|
||||||
|
cmsUpdateMaxRow(pDisplay);
|
||||||
|
}
|
||||||
|
cursorRow = 0; // Goto top in any case
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (key == KEY_UP) {
|
||||||
|
cursorRow--;
|
||||||
|
|
||||||
|
if ((pageTop + cursorRow)->type == OME_Label && cursorRow > 0)
|
||||||
|
cursorRow--;
|
||||||
|
|
||||||
|
if (cursorRow == -1 || (pageTop + cursorRow)->type == OME_Label) {
|
||||||
|
if (pageTopAlt) {
|
||||||
|
displayClear(pDisplay);
|
||||||
|
p = pageTopAlt;
|
||||||
|
pageTopAlt = pageTop;
|
||||||
|
pageTop = (OSD_Entry *)p;
|
||||||
|
cmsUpdateMaxRow(pDisplay);
|
||||||
|
}
|
||||||
|
cursorRow = maxRow; // Goto bottom in any case
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
if (key == KEY_DOWN || key == KEY_UP)
|
||||||
|
return res;
|
||||||
|
|
||||||
|
p = pageTop + cursorRow;
|
||||||
|
|
||||||
|
switch (p->type) {
|
||||||
|
case OME_Submenu:
|
||||||
|
case OME_Funcall:
|
||||||
|
case OME_OSD_Exit:
|
||||||
|
if (p->func && key == KEY_RIGHT) {
|
||||||
|
p->func(pDisplay, p->data);
|
||||||
|
res = BUTTON_PAUSE;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_Back:
|
||||||
|
cmsMenuBack(pDisplay);
|
||||||
|
res = BUTTON_PAUSE;
|
||||||
|
break;
|
||||||
|
case OME_Bool:
|
||||||
|
if (p->data) {
|
||||||
|
uint8_t *val = p->data;
|
||||||
|
if (key == KEY_RIGHT)
|
||||||
|
*val = 1;
|
||||||
|
else
|
||||||
|
*val = 0;
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#ifdef OSD
|
||||||
|
case OME_VISIBLE:
|
||||||
|
if (p->data) {
|
||||||
|
uint32_t address = (uint32_t)p->data;
|
||||||
|
uint16_t *val;
|
||||||
|
|
||||||
|
val = (uint16_t *)address;
|
||||||
|
|
||||||
|
if (key == KEY_RIGHT)
|
||||||
|
*val |= VISIBLE_FLAG;
|
||||||
|
else
|
||||||
|
*val %= ~VISIBLE_FLAG;
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
#endif
|
||||||
|
case OME_UINT8:
|
||||||
|
case OME_FLOAT:
|
||||||
|
if (p->data) {
|
||||||
|
OSD_UINT8_t *ptr = p->data;
|
||||||
|
if (key == KEY_RIGHT) {
|
||||||
|
if (*ptr->val < ptr->max)
|
||||||
|
*ptr->val += ptr->step;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (*ptr->val > ptr->min)
|
||||||
|
*ptr->val -= ptr->step;
|
||||||
|
}
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
if (p->func) {
|
||||||
|
p->func(pDisplay, p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_TAB:
|
||||||
|
if (p->type == OME_TAB) {
|
||||||
|
OSD_TAB_t *ptr = p->data;
|
||||||
|
|
||||||
|
if (key == KEY_RIGHT) {
|
||||||
|
if (*ptr->val < ptr->max)
|
||||||
|
*ptr->val += 1;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (*ptr->val > 0)
|
||||||
|
*ptr->val -= 1;
|
||||||
|
}
|
||||||
|
if (p->func)
|
||||||
|
p->func(pDisplay, p->data);
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_INT8:
|
||||||
|
if (p->data) {
|
||||||
|
OSD_INT8_t *ptr = p->data;
|
||||||
|
if (key == KEY_RIGHT) {
|
||||||
|
if (*ptr->val < ptr->max)
|
||||||
|
*ptr->val += ptr->step;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (*ptr->val > ptr->min)
|
||||||
|
*ptr->val -= ptr->step;
|
||||||
|
}
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
if (p->func) {
|
||||||
|
p->func(pDisplay, p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_UINT16:
|
||||||
|
if (p->data) {
|
||||||
|
OSD_UINT16_t *ptr = p->data;
|
||||||
|
if (key == KEY_RIGHT) {
|
||||||
|
if (*ptr->val < ptr->max)
|
||||||
|
*ptr->val += ptr->step;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (*ptr->val > ptr->min)
|
||||||
|
*ptr->val -= ptr->step;
|
||||||
|
}
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
if (p->func) {
|
||||||
|
p->func(pDisplay, p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_INT16:
|
||||||
|
if (p->data) {
|
||||||
|
OSD_INT16_t *ptr = p->data;
|
||||||
|
if (key == KEY_RIGHT) {
|
||||||
|
if (*ptr->val < ptr->max)
|
||||||
|
*ptr->val += ptr->step;
|
||||||
|
}
|
||||||
|
else {
|
||||||
|
if (*ptr->val > ptr->min)
|
||||||
|
*ptr->val -= ptr->step;
|
||||||
|
}
|
||||||
|
SET_PRINTVALUE(p);
|
||||||
|
if (p->func) {
|
||||||
|
p->func(pDisplay, p);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
case OME_String:
|
||||||
|
break;
|
||||||
|
case OME_Label:
|
||||||
|
case OME_END:
|
||||||
|
break;
|
||||||
|
case OME_MENU:
|
||||||
|
// Shouldn't happen
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
return res;
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsUpdate(uint32_t currentTimeUs)
|
||||||
|
{
|
||||||
|
static int16_t rcDelayMs = BUTTON_TIME;
|
||||||
|
static uint32_t lastCalledMs = 0;
|
||||||
|
static uint32_t lastCmsHeartBeatMs = 0;
|
||||||
|
|
||||||
|
const uint32_t currentTimeMs = currentTimeUs / 1000;
|
||||||
|
|
||||||
|
if (!cmsInMenu) {
|
||||||
|
// Detect menu invocation
|
||||||
|
if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
|
||||||
|
cmsMenuOpen();
|
||||||
|
rcDelayMs = BUTTON_PAUSE; // Tends to overshoot if BUTTON_TIME
|
||||||
|
}
|
||||||
|
} else {
|
||||||
|
uint8_t key = 0;
|
||||||
|
if (rcDelayMs > 0) {
|
||||||
|
rcDelayMs -= (currentTimeMs - lastCalledMs);
|
||||||
|
}
|
||||||
|
else if (IS_MID(THROTTLE) && IS_LO(YAW) && IS_HI(PITCH) && !ARMING_FLAG(ARMED)) {
|
||||||
|
// Double enter = display switching
|
||||||
|
cmsMenuOpen();
|
||||||
|
rcDelayMs = BUTTON_PAUSE;
|
||||||
|
}
|
||||||
|
else if (IS_HI(PITCH)) {
|
||||||
|
key = KEY_UP;
|
||||||
|
rcDelayMs = BUTTON_TIME;
|
||||||
|
}
|
||||||
|
else if (IS_LO(PITCH)) {
|
||||||
|
key = KEY_DOWN;
|
||||||
|
rcDelayMs = BUTTON_TIME;
|
||||||
|
}
|
||||||
|
else if (IS_LO(ROLL)) {
|
||||||
|
key = KEY_LEFT;
|
||||||
|
rcDelayMs = BUTTON_TIME;
|
||||||
|
}
|
||||||
|
else if (IS_HI(ROLL)) {
|
||||||
|
key = KEY_RIGHT;
|
||||||
|
rcDelayMs = BUTTON_TIME;
|
||||||
|
}
|
||||||
|
else if (IS_HI(YAW) || IS_LO(YAW))
|
||||||
|
{
|
||||||
|
key = KEY_ESC;
|
||||||
|
rcDelayMs = BUTTON_TIME;
|
||||||
|
}
|
||||||
|
|
||||||
|
//lastCalled = currentTime;
|
||||||
|
|
||||||
|
if (key) {
|
||||||
|
rcDelayMs = cmsHandleKey(pCurrentDisplay, key);
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
cmsDrawMenu(pCurrentDisplay, currentTimeUs);
|
||||||
|
|
||||||
|
if (currentTimeMs > lastCmsHeartBeatMs + 500) {
|
||||||
|
// Heart beat for external CMS display device @ 500msec
|
||||||
|
// (Timeout @ 1000msec)
|
||||||
|
displayHeartbeat(pCurrentDisplay);
|
||||||
|
lastCmsHeartBeatMs = currentTimeMs;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
lastCalledMs = currentTimeMs;
|
||||||
|
}
|
||||||
|
|
||||||
|
void cmsHandler(uint32_t currentTime)
|
||||||
|
{
|
||||||
|
if (cmsDeviceCount < 0)
|
||||||
|
return;
|
||||||
|
|
||||||
|
static uint32_t lastCalled = 0;
|
||||||
|
|
||||||
|
if (currentTime >= lastCalled + CMS_UPDATE_INTERVAL_US) {
|
||||||
|
lastCalled = currentTime;
|
||||||
|
cmsUpdate(currentTime);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
||||||
|
// Is initializing with menuMain better?
|
||||||
|
// Can it be done with the current main()?
|
||||||
|
void cmsInit(void)
|
||||||
|
{
|
||||||
|
cmsDeviceCount = 0;
|
||||||
|
cmsCurrentDevice = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
#endif // CMS
|
17
src/main/cms/cms.h
Normal file
17
src/main/cms/cms.h
Normal file
|
@ -0,0 +1,17 @@
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "drivers/display.h"
|
||||||
|
|
||||||
|
// Device management
|
||||||
|
bool cmsDisplayPortRegister(displayPort_t *pDisplay);
|
||||||
|
|
||||||
|
// For main.c and scheduler
|
||||||
|
void cmsInit(void);
|
||||||
|
void cmsHandler(uint32_t currentTime);
|
||||||
|
|
||||||
|
long cmsMenuChange(displayPort_t *pPort, const void *ptr);
|
||||||
|
long cmsMenuExit(displayPort_t *pPort, const void *ptr);
|
||||||
|
|
||||||
|
#define CMS_STARTUP_HELP_TEXT1 "MENU: THR MID"
|
||||||
|
#define CMS_STARTUP_HELP_TEXT2 "+ YAW LEFT"
|
||||||
|
#define CMS_STARTUP_HELP_TEXT3 "+ PITCH UP"
|
111
src/main/cms/cms_menu_blackbox.c
Normal file
111
src/main/cms/cms_menu_blackbox.c
Normal file
|
@ -0,0 +1,111 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// CMS things for blackbox and flashfs.
|
||||||
|
//
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_blackbox.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "io/flashfs.h"
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
static long cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr)
|
||||||
|
{
|
||||||
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
displayClear(pDisplay);
|
||||||
|
displayWrite(pDisplay, 5, 3, "ERASING FLASH...");
|
||||||
|
displayResync(pDisplay); // Was max7456RefreshAll(); Why at this timing?
|
||||||
|
|
||||||
|
flashfsEraseCompletely();
|
||||||
|
while (!flashfsIsReady()) {
|
||||||
|
delay(100);
|
||||||
|
}
|
||||||
|
|
||||||
|
displayClear(pDisplay);
|
||||||
|
displayResync(pDisplay); // Was max7456RefreshAll(); wedges during heavy SPI?
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
#endif // USE_FLASHFS
|
||||||
|
|
||||||
|
static bool featureRead = false;
|
||||||
|
static uint8_t cmsx_FeatureBlackbox;
|
||||||
|
|
||||||
|
static long cmsx_Blackbox_FeatureRead(void)
|
||||||
|
{
|
||||||
|
if (!featureRead) {
|
||||||
|
cmsx_FeatureBlackbox = feature(FEATURE_BLACKBOX) ? 1 : 0;
|
||||||
|
featureRead = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_Blackbox_FeatureWriteback(void)
|
||||||
|
{
|
||||||
|
if (cmsx_FeatureBlackbox)
|
||||||
|
featureSet(FEATURE_BLACKBOX);
|
||||||
|
else
|
||||||
|
featureClear(FEATURE_BLACKBOX);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuBlackboxEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- BLACKBOX --", OME_Label, NULL, NULL, 0},
|
||||||
|
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureBlackbox, 0 },
|
||||||
|
{ "RATE DENOM", OME_UINT8, NULL, &(OSD_UINT8_t){ &masterConfig.blackbox_rate_denom,1,32,1 }, 0 },
|
||||||
|
|
||||||
|
#ifdef USE_FLASHFS
|
||||||
|
{ "ERASE FLASH", OME_Funcall, cmsx_EraseFlash, NULL, 0 },
|
||||||
|
#endif // USE_FLASHFS
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuBlackbox = {
|
||||||
|
.GUARD_text = "MENUBB",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_Blackbox_FeatureRead,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = cmsx_Blackbox_FeatureWriteback,
|
||||||
|
.entries = cmsx_menuBlackboxEntries
|
||||||
|
};
|
||||||
|
#endif
|
20
src/main/cms/cms_menu_blackbox.h
Normal file
20
src/main/cms/cms_menu_blackbox.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuBlackbox;
|
149
src/main/cms/cms_menu_builtin.c
Normal file
149
src/main/cms/cms_menu_builtin.c
Normal file
|
@ -0,0 +1,149 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
//
|
||||||
|
// Built-in menu contents and support functions
|
||||||
|
//
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_builtin.h"
|
||||||
|
|
||||||
|
// Sub menus
|
||||||
|
|
||||||
|
#include "cms/cms_menu_imu.h"
|
||||||
|
#include "cms/cms_menu_blackbox.h"
|
||||||
|
#include "cms/cms_menu_vtx.h"
|
||||||
|
#include "cms/cms_menu_osd.h"
|
||||||
|
#include "cms/cms_menu_ledstrip.h"
|
||||||
|
#include "cms/cms_menu_misc.h"
|
||||||
|
|
||||||
|
// User supplied menus
|
||||||
|
|
||||||
|
#include "io/vtx_smartaudio_cms.h"
|
||||||
|
|
||||||
|
// Info
|
||||||
|
|
||||||
|
static char infoGitRev[GIT_SHORT_REVISION_LENGTH];
|
||||||
|
static char infoTargetName[] = __TARGET__;
|
||||||
|
|
||||||
|
#include "msp/msp_protocol.h" // XXX for FC identification... not available elsewhere
|
||||||
|
|
||||||
|
static long cmsx_InfoInit(void)
|
||||||
|
{
|
||||||
|
for (int i = 0 ; i < GIT_SHORT_REVISION_LENGTH ; i++) {
|
||||||
|
if (shortGitRevision[i] >= 'a' && shortGitRevision[i] <= 'f')
|
||||||
|
infoGitRev[i] = shortGitRevision[i] - 'a' + 'A';
|
||||||
|
else
|
||||||
|
infoGitRev[i] = shortGitRevision[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry menuInfoEntries[] = {
|
||||||
|
{ "--- INFO ---", OME_Label, NULL, NULL, 0 },
|
||||||
|
{ "FWID", OME_String, NULL, BETAFLIGHT_IDENTIFIER, 0 },
|
||||||
|
{ "FWVER", OME_String, NULL, FC_VERSION_STRING, 0 },
|
||||||
|
{ "GITREV", OME_String, NULL, infoGitRev, 0 },
|
||||||
|
{ "TARGET", OME_String, NULL, infoTargetName, 0 },
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu menuInfo = {
|
||||||
|
.GUARD_text = "MENUINFO",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_InfoInit,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuInfoEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
// Features
|
||||||
|
|
||||||
|
static OSD_Entry menuFeaturesEntries[] =
|
||||||
|
{
|
||||||
|
{"--- FEATURES ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"BLACKBOX", OME_Submenu, cmsMenuChange, &cmsx_menuBlackbox, 0},
|
||||||
|
#if defined(VTX) || defined(USE_RTC6705)
|
||||||
|
{"VTX", OME_Submenu, cmsMenuChange, &cmsx_menuVtx, 0},
|
||||||
|
#endif // VTX || USE_RTC6705
|
||||||
|
#if defined(VTX_SMARTAUDIO)
|
||||||
|
{"VTX SA", OME_Submenu, cmsMenuChange, &cmsx_menuVtxSmartAudio, 0},
|
||||||
|
#endif
|
||||||
|
#ifdef LED_STRIP
|
||||||
|
{"LED STRIP", OME_Submenu, cmsMenuChange, &cmsx_menuLedstrip, 0},
|
||||||
|
#endif // LED_STRIP
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu menuFeatures = {
|
||||||
|
.GUARD_text = "MENUFEATURES",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuFeaturesEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
// Main
|
||||||
|
|
||||||
|
static OSD_Entry menuMainEntries[] =
|
||||||
|
{
|
||||||
|
{"-- MAIN --", OME_Label, NULL, NULL, 0},
|
||||||
|
|
||||||
|
{"PROFILE", OME_Submenu, cmsMenuChange, &cmsx_menuImu, 0},
|
||||||
|
{"FEATURES", OME_Submenu, cmsMenuChange, &menuFeatures, 0},
|
||||||
|
#ifdef OSD
|
||||||
|
{"SCR LAYOUT", OME_Submenu, cmsMenuChange, &cmsx_menuOsdLayout, 0},
|
||||||
|
{"ALARMS", OME_Submenu, cmsMenuChange, &cmsx_menuAlarms, 0},
|
||||||
|
#endif
|
||||||
|
{"FC&FW INFO", OME_Submenu, cmsMenuChange, &menuInfo, 0},
|
||||||
|
{"MISC", OME_Submenu, cmsMenuChange, &cmsx_menuMisc, 0},
|
||||||
|
{"SAVE&REBOOT", OME_OSD_Exit, cmsMenuExit, (void*)1, 0},
|
||||||
|
{"EXIT", OME_OSD_Exit, cmsMenuExit, (void*)0, 0},
|
||||||
|
#ifdef CMS_MENU_DEBUG
|
||||||
|
{"ERR SAMPLE", OME_Submenu, cmsMenuChange, &menuInfoEntries[0], 0},
|
||||||
|
#endif
|
||||||
|
|
||||||
|
{NULL,OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu menuMain = {
|
||||||
|
.GUARD_text = "MENUMAIN",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuMainEntries,
|
||||||
|
};
|
||||||
|
#endif
|
22
src/main/cms/cms_menu_builtin.h
Normal file
22
src/main/cms/cms_menu_builtin.h
Normal file
|
@ -0,0 +1,22 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
|
||||||
|
extern CMS_Menu menuMain;
|
384
src/main/cms/cms_menu_imu.c
Normal file
384
src/main/cms/cms_menu_imu.c
Normal file
|
@ -0,0 +1,384 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
// Menu contents for PID, RATES, RC preview, misc
|
||||||
|
// Should be part of the relevant .c file.
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
//#include "common/typeconversion.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_imu.h"
|
||||||
|
|
||||||
|
#include "fc/config.h"
|
||||||
|
#include "fc/rc_controls.h"
|
||||||
|
#include "fc/runtime_config.h"
|
||||||
|
|
||||||
|
#include "flight/pid.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
//
|
||||||
|
// PID
|
||||||
|
//
|
||||||
|
static uint8_t tmpProfileIndex;
|
||||||
|
static uint8_t profileIndex;
|
||||||
|
static char profileIndexString[] = " p";
|
||||||
|
static uint8_t tempPid[3][3];
|
||||||
|
|
||||||
|
static uint8_t tmpRateProfileIndex;
|
||||||
|
static uint8_t rateProfileIndex;
|
||||||
|
static char rateProfileIndexString[] = " p-r";
|
||||||
|
static controlRateConfig_t rateProfile;
|
||||||
|
|
||||||
|
static long cmsx_menuImu_onEnter(void)
|
||||||
|
{
|
||||||
|
profileIndex = masterConfig.current_profile_index;
|
||||||
|
tmpProfileIndex = profileIndex + 1;
|
||||||
|
|
||||||
|
rateProfileIndex = masterConfig.profile[profileIndex].activeRateProfile;
|
||||||
|
tmpRateProfileIndex = rateProfileIndex + 1;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_menuImu_onExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
masterConfig.current_profile_index = profileIndex;
|
||||||
|
masterConfig.profile[profileIndex].activeRateProfile = rateProfileIndex;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_profileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
||||||
|
{
|
||||||
|
UNUSED(displayPort);
|
||||||
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
profileIndex = tmpProfileIndex - 1;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_rateProfileIndexOnChange(displayPort_t *displayPort, const void *ptr)
|
||||||
|
{
|
||||||
|
UNUSED(displayPort);
|
||||||
|
UNUSED(ptr);
|
||||||
|
|
||||||
|
rateProfileIndex = tmpRateProfileIndex - 1;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_PidRead(void)
|
||||||
|
{
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < 3; i++) {
|
||||||
|
tempPid[i][0] = masterConfig.profile[profileIndex].pidProfile.P8[i];
|
||||||
|
tempPid[i][1] = masterConfig.profile[profileIndex].pidProfile.I8[i];
|
||||||
|
tempPid[i][2] = masterConfig.profile[profileIndex].pidProfile.D8[i];
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_PidOnEnter(void)
|
||||||
|
{
|
||||||
|
profileIndexString[1] = '0' + tmpProfileIndex;
|
||||||
|
cmsx_PidRead();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_PidWriteback(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
for (uint8_t i = 0; i < 3; i++) {
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.P8[i] = tempPid[i][0];
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.I8[i] = tempPid[i][1];
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.D8[i] = tempPid[i][2];
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuPidEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- PID --", OME_Label, NULL, profileIndexString, 0},
|
||||||
|
|
||||||
|
{ "ROLL P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][0], 0, 200, 1 }, 0 },
|
||||||
|
{ "ROLL I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][1], 0, 200, 1 }, 0 },
|
||||||
|
{ "ROLL D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDROLL][2], 0, 200, 1 }, 0 },
|
||||||
|
|
||||||
|
{ "PITCH P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][0], 0, 200, 1 }, 0 },
|
||||||
|
{ "PITCH I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][1], 0, 200, 1 }, 0 },
|
||||||
|
{ "PITCH D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDPITCH][2], 0, 200, 1 }, 0 },
|
||||||
|
|
||||||
|
{ "YAW P", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][0], 0, 200, 1 }, 0 },
|
||||||
|
{ "YAW I", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][1], 0, 200, 1 }, 0 },
|
||||||
|
{ "YAW D", OME_UINT8, NULL, &(OSD_UINT8_t){ &tempPid[PIDYAW][2], 0, 200, 1 }, 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuPid = {
|
||||||
|
.GUARD_text = "XPID",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_PidOnEnter,
|
||||||
|
.onExit = cmsx_PidWriteback,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuPidEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
//
|
||||||
|
// Rate & Expo
|
||||||
|
//
|
||||||
|
|
||||||
|
static long cmsx_RateProfileRead(void)
|
||||||
|
{
|
||||||
|
memcpy(&rateProfile, &masterConfig.profile[profileIndex].controlRateProfile[rateProfileIndex], sizeof(controlRateConfig_t));
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_RateProfileWriteback(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
memcpy(&masterConfig.profile[profileIndex].controlRateProfile[rateProfileIndex], &rateProfile, sizeof(controlRateConfig_t));
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_RateProfileOnEnter(void)
|
||||||
|
{
|
||||||
|
rateProfileIndexString[1] = '0' + tmpProfileIndex;
|
||||||
|
rateProfileIndexString[3] = '0' + tmpRateProfileIndex;
|
||||||
|
cmsx_RateProfileRead();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuRateProfileEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- RATE --", OME_Label, NULL, rateProfileIndexString, 0 },
|
||||||
|
|
||||||
|
{ "RC RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcRate8, 0, 255, 1, 10 }, 0 },
|
||||||
|
{ "RC YAW RATE", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawRate8, 0, 255, 1, 10 }, 0 },
|
||||||
|
|
||||||
|
{ "ROLL SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[0], 0, 100, 1, 10 }, 0 },
|
||||||
|
{ "PITCH SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[1], 0, 100, 1, 10 }, 0 },
|
||||||
|
{ "YAW SUPER", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rates[2], 0, 100, 1, 10 }, 0 },
|
||||||
|
|
||||||
|
{ "RC EXPO", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcExpo8, 0, 100, 1, 10 }, 0 },
|
||||||
|
{ "RC YAW EXP", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.rcYawExpo8, 0, 100, 1, 10 }, 0 },
|
||||||
|
|
||||||
|
{ "THRPID ATT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &rateProfile.dynThrPID, 0, 100, 1, 10}, 0 },
|
||||||
|
{ "TPA BRKPT", OME_UINT16, NULL, &(OSD_UINT16_t){ &rateProfile.tpa_breakpoint, 1000, 2000, 10}, 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuRateProfile = {
|
||||||
|
.GUARD_text = "MENURATE",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_RateProfileOnEnter,
|
||||||
|
.onExit = cmsx_RateProfileWriteback,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuRateProfileEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint8_t cmsx_dtermSetpointWeight;
|
||||||
|
static uint8_t cmsx_setpointRelaxRatio;
|
||||||
|
static uint8_t cmsx_angleStrength;
|
||||||
|
static uint8_t cmsx_horizonStrength;
|
||||||
|
static uint8_t cmsx_horizonTransition;
|
||||||
|
|
||||||
|
static long cmsx_profileOtherOnEnter(void)
|
||||||
|
{
|
||||||
|
profileIndexString[1] = '0' + tmpProfileIndex;
|
||||||
|
|
||||||
|
cmsx_dtermSetpointWeight = masterConfig.profile[profileIndex].pidProfile.dtermSetpointWeight;
|
||||||
|
cmsx_setpointRelaxRatio = masterConfig.profile[profileIndex].pidProfile.setpointRelaxRatio;
|
||||||
|
|
||||||
|
cmsx_angleStrength = masterConfig.profile[profileIndex].pidProfile.P8[PIDLEVEL];
|
||||||
|
cmsx_horizonStrength = masterConfig.profile[profileIndex].pidProfile.I8[PIDLEVEL];
|
||||||
|
cmsx_horizonTransition = masterConfig.profile[profileIndex].pidProfile.D8[PIDLEVEL];
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_profileOtherOnExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.dtermSetpointWeight = cmsx_dtermSetpointWeight;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.setpointRelaxRatio = cmsx_setpointRelaxRatio;
|
||||||
|
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.P8[PIDLEVEL] = cmsx_angleStrength;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.I8[PIDLEVEL] = cmsx_horizonStrength;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.D8[PIDLEVEL] = cmsx_horizonTransition;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuProfileOtherEntries[] = {
|
||||||
|
{ "-- OTHER PP --", OME_Label, NULL, profileIndexString, 0 },
|
||||||
|
|
||||||
|
{ "D SETPT WT", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_dtermSetpointWeight, 0, 255, 1, 10 }, 0 },
|
||||||
|
{ "SETPT TRS", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_setpointRelaxRatio, 0, 100, 1, 10 }, 0 },
|
||||||
|
{ "ANGLE STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_angleStrength, 0, 200, 1 } , 0 },
|
||||||
|
{ "HORZN STR", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonStrength, 0, 200, 1 } , 0 },
|
||||||
|
{ "HORZN TRS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_horizonTransition, 0, 200, 1 } , 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuProfileOther = {
|
||||||
|
.GUARD_text = "XPROFOTHER",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_profileOtherOnEnter,
|
||||||
|
.onExit = cmsx_profileOtherOnExit,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuProfileOtherEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuFilterGlobalEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- FILTER GLB --", OME_Label, NULL, NULL, 0 },
|
||||||
|
|
||||||
|
{ "GYRO LPF", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.gyro_soft_lpf_hz, 0, 255, 1 }, 0 },
|
||||||
|
{ "GYRO NF1", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_hz_1, 0, 500, 1 }, 0 },
|
||||||
|
{ "GYRO NF1C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_cutoff_1, 0, 500, 1 }, 0 },
|
||||||
|
{ "GYRO NF2", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_hz_2, 0, 500, 1 }, 0 },
|
||||||
|
{ "GYRO NF2C", OME_UINT16, NULL, &(OSD_UINT16_t) { &masterConfig.gyro_soft_notch_cutoff_2, 0, 500, 1 }, 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuFilterGlobal = {
|
||||||
|
.GUARD_text = "XFLTGLB",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuFilterGlobalEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
static uint16_t cmsx_dterm_lpf_hz;
|
||||||
|
static uint16_t cmsx_dterm_notch_hz;
|
||||||
|
static uint16_t cmsx_dterm_notch_cutoff;
|
||||||
|
static uint16_t cmsx_yaw_lpf_hz;
|
||||||
|
static uint16_t cmsx_yaw_p_limit;
|
||||||
|
|
||||||
|
static long cmsx_FilterPerProfileRead(void)
|
||||||
|
{
|
||||||
|
cmsx_dterm_lpf_hz = masterConfig.profile[profileIndex].pidProfile.dterm_lpf_hz;
|
||||||
|
cmsx_dterm_notch_hz = masterConfig.profile[profileIndex].pidProfile.dterm_notch_hz;
|
||||||
|
cmsx_dterm_notch_cutoff = masterConfig.profile[profileIndex].pidProfile.dterm_notch_cutoff;
|
||||||
|
cmsx_yaw_lpf_hz = masterConfig.profile[profileIndex].pidProfile.yaw_lpf_hz;
|
||||||
|
cmsx_yaw_p_limit = masterConfig.profile[profileIndex].pidProfile.yaw_p_limit;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_FilterPerProfileWriteback(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.dterm_lpf_hz = cmsx_dterm_lpf_hz;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.dterm_notch_hz = cmsx_dterm_notch_hz;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.dterm_notch_cutoff = cmsx_dterm_notch_cutoff;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.yaw_lpf_hz = cmsx_yaw_lpf_hz;
|
||||||
|
masterConfig.profile[profileIndex].pidProfile.yaw_p_limit = cmsx_yaw_p_limit;
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuFilterPerProfileEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- FILTER PP --", OME_Label, NULL, NULL, 0 },
|
||||||
|
|
||||||
|
{ "DTERM LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_lpf_hz, 0, 500, 1 }, 0 },
|
||||||
|
{ "DTERM NF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_hz, 0, 500, 1 }, 0 },
|
||||||
|
{ "DTERM NFCO", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_dterm_notch_cutoff, 0, 500, 1 }, 0 },
|
||||||
|
{ "YAW LPF", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_lpf_hz, 0, 500, 1 }, 0 },
|
||||||
|
{ "YAW P LIM", OME_UINT16, NULL, &(OSD_UINT16_t){ &cmsx_yaw_p_limit, 100, 500, 1 }, 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
static CMS_Menu cmsx_menuFilterPerProfile = {
|
||||||
|
.GUARD_text = "XFLTPP",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_FilterPerProfileRead,
|
||||||
|
.onExit = cmsx_FilterPerProfileWriteback,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuFilterPerProfileEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuImuEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- IMU --", OME_Label, NULL, NULL, 0},
|
||||||
|
|
||||||
|
{"PID PROF", OME_UINT8, cmsx_profileIndexOnChange, &(OSD_UINT8_t){ &tmpProfileIndex, 1, MAX_PROFILE_COUNT, 1}, 0},
|
||||||
|
{"PID", OME_Submenu, cmsMenuChange, &cmsx_menuPid, 0},
|
||||||
|
{"OTHER PP", OME_Submenu, cmsMenuChange, &cmsx_menuProfileOther, 0},
|
||||||
|
|
||||||
|
{"RATE PROF", OME_UINT8, cmsx_rateProfileIndexOnChange, &(OSD_UINT8_t){ &tmpRateProfileIndex, 1, MAX_RATEPROFILES, 1}, 0},
|
||||||
|
{"RATE", OME_Submenu, cmsMenuChange, &cmsx_menuRateProfile, 0},
|
||||||
|
|
||||||
|
{"FLT PP", OME_Submenu, cmsMenuChange, &cmsx_menuFilterPerProfile, 0},
|
||||||
|
|
||||||
|
{"FLT GLB", OME_Submenu, cmsMenuChange, &cmsx_menuFilterGlobal, 0},
|
||||||
|
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuImu = {
|
||||||
|
.GUARD_text = "XIMU",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_menuImu_onEnter,
|
||||||
|
.onExit = cmsx_menuImu_onExit,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuImuEntries,
|
||||||
|
};
|
||||||
|
#endif // CMS
|
20
src/main/cms/cms_menu_imu.h
Normal file
20
src/main/cms/cms_menu_imu.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuImu;
|
82
src/main/cms/cms_menu_ledstrip.c
Normal file
82
src/main/cms/cms_menu_ledstrip.c
Normal file
|
@ -0,0 +1,82 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_ledstrip.h"
|
||||||
|
|
||||||
|
#ifdef LED_STRIP
|
||||||
|
|
||||||
|
static bool featureRead = false;
|
||||||
|
static uint8_t cmsx_FeatureLedstrip;
|
||||||
|
|
||||||
|
static long cmsx_Ledstrip_FeatureRead(void)
|
||||||
|
{
|
||||||
|
if (!featureRead) {
|
||||||
|
cmsx_FeatureLedstrip = feature(FEATURE_LED_STRIP) ? 1 : 0;
|
||||||
|
featureRead = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_Ledstrip_FeatureWriteback(void)
|
||||||
|
{
|
||||||
|
if (cmsx_FeatureLedstrip)
|
||||||
|
featureSet(FEATURE_LED_STRIP);
|
||||||
|
else
|
||||||
|
featureClear(FEATURE_LED_STRIP);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuLedstripEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- LED STRIP --", OME_Label, NULL, NULL, 0 },
|
||||||
|
{ "ENABLED", OME_Bool, NULL, &cmsx_FeatureLedstrip, 0 },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0 },
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0 }
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuLedstrip = {
|
||||||
|
.GUARD_text = "MENULED",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_Ledstrip_FeatureRead,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = cmsx_Ledstrip_FeatureWriteback,
|
||||||
|
.entries = cmsx_menuLedstripEntries
|
||||||
|
};
|
||||||
|
#endif // LED_STRIP
|
||||||
|
#endif // CMS
|
20
src/main/cms/cms_menu_ledstrip.h
Normal file
20
src/main/cms/cms_menu_ledstrip.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuLedstrip;
|
104
src/main/cms/cms_menu_misc.c
Normal file
104
src/main/cms/cms_menu_misc.c
Normal file
|
@ -0,0 +1,104 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#include "drivers/system.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_ledstrip.h"
|
||||||
|
|
||||||
|
//
|
||||||
|
// Misc
|
||||||
|
//
|
||||||
|
|
||||||
|
static long cmsx_menuRcConfirmBack(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
if (self && self->type == OME_Back)
|
||||||
|
return 0;
|
||||||
|
else
|
||||||
|
return -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
//
|
||||||
|
// RC preview
|
||||||
|
//
|
||||||
|
static OSD_Entry cmsx_menuRcEntries[] =
|
||||||
|
{
|
||||||
|
{ "-- RC PREV --", OME_Label, NULL, NULL, 0},
|
||||||
|
|
||||||
|
{ "ROLL", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[ROLL], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "PITCH", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[PITCH], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "THR", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[THROTTLE], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "YAW", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[YAW], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
|
||||||
|
{ "AUX1", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX1], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "AUX2", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX2], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "AUX3", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX3], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
{ "AUX4", OME_INT16, NULL, &(OSD_INT16_t){ &rcData[AUX4], 1, 2500, 0 }, DYNAMIC },
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuRcPreview = {
|
||||||
|
.GUARD_text = "XRCPREV",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = cmsx_menuRcConfirmBack,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuRcEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
|
||||||
|
static OSD_Entry menuMiscEntries[]=
|
||||||
|
{
|
||||||
|
{ "-- MISC --", OME_Label, NULL, NULL, 0 },
|
||||||
|
|
||||||
|
{ "MIN THR", OME_UINT16, NULL, &(OSD_UINT16_t){ &masterConfig.motorConfig.minthrottle, 1000, 2000, 1 }, 0 },
|
||||||
|
{ "VBAT SCALE", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatscale, 1, 250, 1 }, 0 },
|
||||||
|
{ "VBAT CLMAX", OME_UINT8, NULL, &(OSD_UINT8_t) { &masterConfig.batteryConfig.vbatmaxcellvoltage, 10, 50, 1 }, 0 },
|
||||||
|
{ "RC PREV", OME_Submenu, cmsMenuChange, &cmsx_menuRcPreview, 0},
|
||||||
|
|
||||||
|
{ "BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{ NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuMisc = {
|
||||||
|
.GUARD_text = "XMISC",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuMiscEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // CMS
|
20
src/main/cms/cms_menu_misc.h
Normal file
20
src/main/cms/cms_menu_misc.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuMisc;
|
112
src/main/cms/cms_menu_osd.c
Normal file
112
src/main/cms/cms_menu_osd.c
Normal file
|
@ -0,0 +1,112 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_osd.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#if defined(OSD) && defined(CMS)
|
||||||
|
|
||||||
|
OSD_UINT8_t entryAlarmRssi = {&masterConfig.osdProfile.rssi_alarm, 5, 90, 5};
|
||||||
|
OSD_UINT16_t entryAlarmCapacity = {&masterConfig.osdProfile.cap_alarm, 50, 30000, 50};
|
||||||
|
OSD_UINT16_t enryAlarmFlyTime = {&masterConfig.osdProfile.time_alarm, 1, 200, 1};
|
||||||
|
OSD_UINT16_t entryAlarmAltitude = {&masterConfig.osdProfile.alt_alarm, 1, 200, 1};
|
||||||
|
|
||||||
|
OSD_Entry cmsx_menuAlarmsEntries[] =
|
||||||
|
{
|
||||||
|
{"--- ALARMS ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"RSSI", OME_UINT8, NULL, &entryAlarmRssi, 0},
|
||||||
|
{"MAIN BAT", OME_UINT16, NULL, &entryAlarmCapacity, 0},
|
||||||
|
{"FLY TIME", OME_UINT16, NULL, &enryAlarmFlyTime, 0},
|
||||||
|
{"MAX ALT", OME_UINT16, NULL, &entryAlarmAltitude, 0},
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuAlarms = {
|
||||||
|
.GUARD_text = "MENUALARMS",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuAlarmsEntries,
|
||||||
|
};
|
||||||
|
|
||||||
|
OSD_Entry menuOsdActiveElemsEntries[] =
|
||||||
|
{
|
||||||
|
{"--- ACTIV ELEM ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"RSSI", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], 0},
|
||||||
|
{"MAIN BATTERY", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], 0},
|
||||||
|
{"HORIZON", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ARTIFICIAL_HORIZON], 0},
|
||||||
|
{"HORIZON SIDEBARS", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_HORIZON_SIDEBARS], 0},
|
||||||
|
{"UPTIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ONTIME], 0},
|
||||||
|
{"FLY TIME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYTIME], 0},
|
||||||
|
{"FLY MODE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_FLYMODE], 0},
|
||||||
|
{"NAME", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CRAFT_NAME], 0},
|
||||||
|
{"THROTTLE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], 0},
|
||||||
|
#ifdef VTX
|
||||||
|
{"VTX CHAN", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL]},
|
||||||
|
#endif // VTX
|
||||||
|
{"CURRENT (A)", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_CURRENT_DRAW], 0},
|
||||||
|
{"USED MAH", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_MAH_DRAWN], 0},
|
||||||
|
#ifdef GPS
|
||||||
|
{"GPS SPEED", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SPEED], 0},
|
||||||
|
{"GPS SATS.", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_GPS_SATS], 0},
|
||||||
|
#endif // GPS
|
||||||
|
{"ALTITUDE", OME_VISIBLE, NULL, &masterConfig.osdProfile.item_pos[OSD_ALTITUDE], 0},
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu menuOsdActiveElems = {
|
||||||
|
.GUARD_text = "MENUOSDACT",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = menuOsdActiveElemsEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
OSD_Entry cmsx_menuOsdLayoutEntries[] =
|
||||||
|
{
|
||||||
|
{"---SCREEN LAYOUT---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"ACTIVE ELEM", OME_Submenu, cmsMenuChange, &menuOsdActiveElems, 0},
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuOsdLayout = {
|
||||||
|
.GUARD_text = "MENULAYOUT",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = NULL,
|
||||||
|
.onExit = NULL,
|
||||||
|
.onGlobalExit = NULL,
|
||||||
|
.entries = cmsx_menuOsdLayoutEntries
|
||||||
|
};
|
||||||
|
#endif // CMS
|
21
src/main/cms/cms_menu_osd.h
Normal file
21
src/main/cms/cms_menu_osd.h
Normal file
|
@ -0,0 +1,21 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuAlarms;
|
||||||
|
extern CMS_Menu cmsx_menuOsdLayout;
|
146
src/main/cms/cms_menu_vtx.c
Normal file
146
src/main/cms/cms_menu_vtx.c
Normal file
|
@ -0,0 +1,146 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
#include <ctype.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/version.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
#include "cms/cms_types.h"
|
||||||
|
#include "cms/cms_menu_vtx.h"
|
||||||
|
|
||||||
|
#include "config/config_profile.h"
|
||||||
|
#include "config/config_master.h"
|
||||||
|
#include "config/feature.h"
|
||||||
|
|
||||||
|
#ifdef CMS
|
||||||
|
|
||||||
|
#if defined(VTX) || defined(USE_RTC6705)
|
||||||
|
|
||||||
|
static bool featureRead = false;
|
||||||
|
static uint8_t cmsx_featureVtx = 0, cmsx_vtxBand, cmsx_vtxChannel;
|
||||||
|
|
||||||
|
static long cmsx_Vtx_FeatureRead(void)
|
||||||
|
{
|
||||||
|
if (!featureRead) {
|
||||||
|
cmsx_featureVtx = feature(FEATURE_VTX) ? 1 : 0;
|
||||||
|
featureRead = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_Vtx_FeatureWriteback(void)
|
||||||
|
{
|
||||||
|
if (cmsx_featureVtx)
|
||||||
|
featureSet(FEATURE_VTX);
|
||||||
|
else
|
||||||
|
featureClear(FEATURE_VTX);
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static const char * const vtxBandNames[] = {
|
||||||
|
"BOSCAM A",
|
||||||
|
"BOSCAM B",
|
||||||
|
"BOSCAM E",
|
||||||
|
"FATSHARK",
|
||||||
|
"RACEBAND",
|
||||||
|
};
|
||||||
|
|
||||||
|
static OSD_TAB_t entryVtxBand = {&cmsx_vtxBand,4,&vtxBandNames[0]};
|
||||||
|
static OSD_UINT8_t entryVtxChannel = {&cmsx_vtxChannel, 1, 8, 1};
|
||||||
|
|
||||||
|
static void cmsx_Vtx_ConfigRead(void)
|
||||||
|
{
|
||||||
|
#ifdef VTX
|
||||||
|
cmsx_vtxBand = masterConfig.vtx_band;
|
||||||
|
cmsx_vtxChannel = masterConfig.vtx_channel + 1;
|
||||||
|
#endif // VTX
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
cmsx_vtxBand = masterConfig.vtx_channel / 8;
|
||||||
|
cmsx_vtxChannel = masterConfig.vtx_channel % 8 + 1;
|
||||||
|
#endif // USE_RTC6705
|
||||||
|
}
|
||||||
|
|
||||||
|
static void cmsx_Vtx_ConfigWriteback(void)
|
||||||
|
{
|
||||||
|
#ifdef VTX
|
||||||
|
masterConfig.vtx_band = cmsx_vtxBand;
|
||||||
|
masterConfig.vtx_channel = cmsx_vtxChannel - 1;
|
||||||
|
#endif // VTX
|
||||||
|
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
masterConfig.vtx_channel = cmsx_vtxBand * 8 + cmsx_vtxChannel - 1;
|
||||||
|
#endif // USE_RTC6705
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_Vtx_onEnter(void)
|
||||||
|
{
|
||||||
|
cmsx_Vtx_FeatureRead();
|
||||||
|
cmsx_Vtx_ConfigRead();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
static long cmsx_Vtx_onExit(const OSD_Entry *self)
|
||||||
|
{
|
||||||
|
UNUSED(self);
|
||||||
|
|
||||||
|
cmsx_Vtx_ConfigWriteback();
|
||||||
|
|
||||||
|
return 0;
|
||||||
|
}
|
||||||
|
|
||||||
|
#ifdef VTX
|
||||||
|
static OSD_UINT8_t entryVtxMode = {&masterConfig.vtx_mode, 0, 2, 1};
|
||||||
|
static OSD_UINT16_t entryVtxMhz = {&masterConfig.vtx_mhz, 5600, 5950, 1};
|
||||||
|
#endif // VTX
|
||||||
|
|
||||||
|
static OSD_Entry cmsx_menuVtxEntries[] =
|
||||||
|
{
|
||||||
|
{"--- VTX ---", OME_Label, NULL, NULL, 0},
|
||||||
|
{"ENABLED", OME_Bool, NULL, &cmsx_featureVtx, 0},
|
||||||
|
#ifdef VTX
|
||||||
|
{"VTX MODE", OME_UINT8, NULL, &entryVtxMode, 0},
|
||||||
|
{"VTX MHZ", OME_UINT16, NULL, &entryVtxMhz, 0},
|
||||||
|
#endif // VTX
|
||||||
|
{"BAND", OME_TAB, NULL, &entryVtxBand, 0},
|
||||||
|
{"CHANNEL", OME_UINT8, NULL, &entryVtxChannel, 0},
|
||||||
|
#ifdef USE_RTC6705
|
||||||
|
{"LOW POWER", OME_Bool, NULL, &masterConfig.vtx_power, 0},
|
||||||
|
#endif // USE_RTC6705
|
||||||
|
{"BACK", OME_Back, NULL, NULL, 0},
|
||||||
|
{NULL, OME_END, NULL, NULL, 0}
|
||||||
|
};
|
||||||
|
|
||||||
|
CMS_Menu cmsx_menuVtx = {
|
||||||
|
.GUARD_text = "MENUVTX",
|
||||||
|
.GUARD_type = OME_MENU,
|
||||||
|
.onEnter = cmsx_Vtx_onEnter,
|
||||||
|
.onExit= cmsx_Vtx_onExit,
|
||||||
|
.onGlobalExit = cmsx_Vtx_FeatureWriteback,
|
||||||
|
.entries = cmsx_menuVtxEntries
|
||||||
|
};
|
||||||
|
|
||||||
|
#endif // VTX || USE_RTC6705
|
||||||
|
#endif // CMS
|
20
src/main/cms/cms_menu_vtx.h
Normal file
20
src/main/cms/cms_menu_vtx.h
Normal file
|
@ -0,0 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
extern CMS_Menu cmsx_menuVtx;
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
//
|
//
|
||||||
// Menu element types
|
// Menu element types
|
||||||
// XXX Upon separation, all OME would be renamed to CME_ or similar.
|
// XXX Upon separation, all OME would be renamed to CME_ or similar.
|
||||||
|
@ -5,8 +22,6 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
typedef long (*OSDMenuFuncPtr)(displayPort_t *, void *);
|
|
||||||
|
|
||||||
//type of elements
|
//type of elements
|
||||||
|
|
||||||
typedef enum
|
typedef enum
|
||||||
|
@ -15,12 +30,12 @@ typedef enum
|
||||||
OME_Back,
|
OME_Back,
|
||||||
OME_OSD_Exit,
|
OME_OSD_Exit,
|
||||||
OME_Submenu,
|
OME_Submenu,
|
||||||
|
OME_Funcall,
|
||||||
OME_Bool,
|
OME_Bool,
|
||||||
OME_INT8,
|
OME_INT8,
|
||||||
OME_UINT8,
|
OME_UINT8,
|
||||||
OME_UINT16,
|
OME_UINT16,
|
||||||
OME_INT16,
|
OME_INT16,
|
||||||
OME_Poll_INT16,
|
|
||||||
OME_String,
|
OME_String,
|
||||||
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
|
OME_FLOAT, //only up to 255 value and cant be 2.55 or 25.5, just for PID's
|
||||||
//wlasciwosci elementow
|
//wlasciwosci elementow
|
||||||
|
@ -29,13 +44,20 @@ typedef enum
|
||||||
#endif
|
#endif
|
||||||
OME_TAB,
|
OME_TAB,
|
||||||
OME_END,
|
OME_END,
|
||||||
|
|
||||||
|
// Debug aid
|
||||||
|
OME_MENU,
|
||||||
|
|
||||||
|
OME_MAX = OME_MENU
|
||||||
} OSD_MenuElement;
|
} OSD_MenuElement;
|
||||||
|
|
||||||
|
typedef long (*CMSEntryFuncPtr)(displayPort_t *displayPort, const void *ptr);
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
char *text;
|
const char *text;
|
||||||
OSD_MenuElement type;
|
const OSD_MenuElement type;
|
||||||
OSDMenuFuncPtr func;
|
const CMSEntryFuncPtr func;
|
||||||
void *data;
|
void *data;
|
||||||
uint8_t flags;
|
uint8_t flags;
|
||||||
} OSD_Entry;
|
} OSD_Entry;
|
||||||
|
@ -43,6 +65,7 @@ typedef struct
|
||||||
// Bits in flags
|
// Bits in flags
|
||||||
#define PRINT_VALUE 0x01 // Value has been changed, need to redraw
|
#define PRINT_VALUE 0x01 // Value has been changed, need to redraw
|
||||||
#define PRINT_LABEL 0x02 // Text label should be printed
|
#define PRINT_LABEL 0x02 // Text label should be printed
|
||||||
|
#define DYNAMIC 0x04 // Value should be updated dynamically
|
||||||
|
|
||||||
#define IS_PRINTVALUE(p) ((p)->flags & PRINT_VALUE)
|
#define IS_PRINTVALUE(p) ((p)->flags & PRINT_VALUE)
|
||||||
#define SET_PRINTVALUE(p) { (p)->flags |= PRINT_VALUE; }
|
#define SET_PRINTVALUE(p) { (p)->flags |= PRINT_VALUE; }
|
||||||
|
@ -52,6 +75,32 @@ typedef struct
|
||||||
#define SET_PRINTLABEL(p) { (p)->flags |= PRINT_LABEL; }
|
#define SET_PRINTLABEL(p) { (p)->flags |= PRINT_LABEL; }
|
||||||
#define CLR_PRINTLABEL(p) { (p)->flags &= ~PRINT_LABEL; }
|
#define CLR_PRINTLABEL(p) { (p)->flags &= ~PRINT_LABEL; }
|
||||||
|
|
||||||
|
#define IS_DYNAMIC(p) ((p)->flags & DYNAMIC)
|
||||||
|
|
||||||
|
|
||||||
|
typedef long (*CMSMenuFuncPtr)(void);
|
||||||
|
|
||||||
|
/*
|
||||||
|
onExit function is called with self:
|
||||||
|
(1) Pointer to an OSD_Entry when cmsMenuBack() was called.
|
||||||
|
Point to an OSD_Entry with type == OME_Back if BACK was selected.
|
||||||
|
(2) NULL if called from menu exit (forced exit at top level).
|
||||||
|
*/
|
||||||
|
|
||||||
|
typedef long (*CMSMenuOnExitPtr)(const OSD_Entry *self);
|
||||||
|
|
||||||
|
typedef struct
|
||||||
|
{
|
||||||
|
// These two are debug aids for menu content creators.
|
||||||
|
const char *GUARD_text;
|
||||||
|
const OSD_MenuElement GUARD_type;
|
||||||
|
|
||||||
|
const CMSMenuFuncPtr onEnter;
|
||||||
|
const CMSMenuOnExitPtr onExit;
|
||||||
|
const CMSMenuFuncPtr onGlobalExit;
|
||||||
|
OSD_Entry *entries;
|
||||||
|
} CMS_Menu;
|
||||||
|
|
||||||
typedef struct
|
typedef struct
|
||||||
{
|
{
|
||||||
uint8_t *val;
|
uint8_t *val;
|
|
@ -17,7 +17,7 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define EEPROM_CONF_VERSION 144
|
#define EEPROM_CONF_VERSION 145
|
||||||
|
|
||||||
void initEEPROM(void);
|
void initEEPROM(void);
|
||||||
void writeEEPROM();
|
void writeEEPROM();
|
||||||
|
|
|
@ -21,9 +21,13 @@
|
||||||
|
|
||||||
#include "config/config_profile.h"
|
#include "config/config_profile.h"
|
||||||
|
|
||||||
|
#include "cms/cms.h"
|
||||||
|
|
||||||
|
#include "drivers/adc.h"
|
||||||
#include "drivers/pwm_rx.h"
|
#include "drivers/pwm_rx.h"
|
||||||
#include "drivers/sound_beeper.h"
|
#include "drivers/sound_beeper.h"
|
||||||
#include "drivers/sonar_hcsr04.h"
|
#include "drivers/sonar_hcsr04.h"
|
||||||
|
#include "drivers/sdcard.h"
|
||||||
|
|
||||||
#include "fc/rc_controls.h"
|
#include "fc/rc_controls.h"
|
||||||
|
|
||||||
|
@ -38,7 +42,6 @@
|
||||||
#include "io/motors.h"
|
#include "io/motors.h"
|
||||||
#include "io/servos.h"
|
#include "io/servos.h"
|
||||||
#include "io/gps.h"
|
#include "io/gps.h"
|
||||||
#include "io/cms.h"
|
|
||||||
#include "io/osd.h"
|
#include "io/osd.h"
|
||||||
#include "io/ledstrip.h"
|
#include "io/ledstrip.h"
|
||||||
#include "io/vtx.h"
|
#include "io/vtx.h"
|
||||||
|
@ -153,6 +156,10 @@ typedef struct master_s {
|
||||||
pwmConfig_t pwmConfig;
|
pwmConfig_t pwmConfig;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_ADC
|
||||||
|
adcConfig_t adcConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
#ifdef BEEPER
|
#ifdef BEEPER
|
||||||
beeperConfig_t beeperConfig;
|
beeperConfig_t beeperConfig;
|
||||||
#endif
|
#endif
|
||||||
|
@ -162,11 +169,7 @@ typedef struct master_s {
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef LED_STRIP
|
#ifdef LED_STRIP
|
||||||
ledConfig_t ledConfigs[LED_MAX_STRIP_LENGTH];
|
ledStripConfig_t ledStripConfig;
|
||||||
hsvColor_t colors[LED_CONFIGURABLE_COLOR_COUNT];
|
|
||||||
modeColorIndexes_t modeColors[LED_MODE_COUNT];
|
|
||||||
specialColorIndexes_t specialColors;
|
|
||||||
uint8_t ledstrip_visual_beeper; // suppress LEDLOW mode if beeper is on
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#ifdef TRANSPONDER
|
#ifdef TRANSPONDER
|
||||||
|
@ -182,6 +185,10 @@ typedef struct master_s {
|
||||||
osd_profile_t osdProfile;
|
osd_profile_t osdProfile;
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
#ifdef USE_SDCARD
|
||||||
|
sdcardConfig_t sdcardConfig;
|
||||||
|
#endif
|
||||||
|
|
||||||
profile_t profile[MAX_PROFILE_COUNT];
|
profile_t profile[MAX_PROFILE_COUNT];
|
||||||
uint8_t current_profile_index;
|
uint8_t current_profile_index;
|
||||||
|
|
||||||
|
@ -216,8 +223,8 @@ typedef struct master_s {
|
||||||
uint8_t magic_ef; // magic number, should be 0xEF
|
uint8_t magic_ef; // magic number, should be 0xEF
|
||||||
uint8_t chk; // XOR checksum
|
uint8_t chk; // XOR checksum
|
||||||
/*
|
/*
|
||||||
do not add properties after the CHK
|
do not add properties after the MAGIC_EF and CHK
|
||||||
as it is assumed to exist at length-1
|
as it is assumed to exist at length-2 and length-1
|
||||||
*/
|
*/
|
||||||
} master_t;
|
} master_t;
|
||||||
|
|
||||||
|
|
|
@ -27,19 +27,19 @@
|
||||||
|
|
||||||
static uint32_t activeFeaturesLatch = 0;
|
static uint32_t activeFeaturesLatch = 0;
|
||||||
|
|
||||||
void intFeatureSet(uint32_t mask, master_t *config)
|
void intFeatureSet(uint32_t mask, uint32_t *features)
|
||||||
{
|
{
|
||||||
config->enabledFeatures |= mask;
|
*features |= mask;
|
||||||
}
|
}
|
||||||
|
|
||||||
void intFeatureClear(uint32_t mask, master_t *config)
|
void intFeatureClear(uint32_t mask, uint32_t *features)
|
||||||
{
|
{
|
||||||
config->enabledFeatures &= ~(mask);
|
*features &= ~(mask);
|
||||||
}
|
}
|
||||||
|
|
||||||
void intFeatureClearAll(master_t *config)
|
void intFeatureClearAll(uint32_t *features)
|
||||||
{
|
{
|
||||||
config->enabledFeatures = 0;
|
*features = 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
void latchActiveFeatures()
|
void latchActiveFeatures()
|
||||||
|
@ -59,17 +59,17 @@ bool feature(uint32_t mask)
|
||||||
|
|
||||||
void featureSet(uint32_t mask)
|
void featureSet(uint32_t mask)
|
||||||
{
|
{
|
||||||
intFeatureSet(mask, &masterConfig);
|
intFeatureSet(mask, &masterConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
void featureClear(uint32_t mask)
|
void featureClear(uint32_t mask)
|
||||||
{
|
{
|
||||||
intFeatureClear(mask, &masterConfig);
|
intFeatureClear(mask, &masterConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
void featureClearAll()
|
void featureClearAll()
|
||||||
{
|
{
|
||||||
intFeatureClearAll(&masterConfig);
|
intFeatureClearAll(&masterConfig.enabledFeatures);
|
||||||
}
|
}
|
||||||
|
|
||||||
uint32_t featureMask(void)
|
uint32_t featureMask(void)
|
||||||
|
|
|
@ -24,3 +24,7 @@ void featureSet(uint32_t mask);
|
||||||
void featureClear(uint32_t mask);
|
void featureClear(uint32_t mask);
|
||||||
void featureClearAll(void);
|
void featureClearAll(void);
|
||||||
uint32_t featureMask(void);
|
uint32_t featureMask(void);
|
||||||
|
|
||||||
|
void intFeatureClearAll(uint32_t *features);
|
||||||
|
void intFeatureSet(uint32_t mask, uint32_t *features);
|
||||||
|
void intFeatureClear(uint32_t mask, uint32_t *features);
|
|
@ -76,7 +76,7 @@ static void l3gd20SpiInit(SPI_TypeDef *SPIx)
|
||||||
UNUSED(SPIx); // FIXME
|
UNUSED(SPIx); // FIXME
|
||||||
|
|
||||||
mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN));
|
mpul3gd20CsPin = IOGetByTag(IO_TAG(L3GD20_CS_PIN));
|
||||||
IOInit(mpul3gd20CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
IOInit(mpul3gd20CsPin, OWNER_MPU_CS, 0);
|
||||||
IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(mpul3gd20CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
DISABLE_L3GD20;
|
DISABLE_L3GD20;
|
||||||
|
|
|
@ -105,7 +105,7 @@ static inline void mma8451ConfigureInterrupt(void)
|
||||||
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
|
// PA5 - ACC_INT2 output on NAZE rev3/4 hardware
|
||||||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
||||||
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
// OLIMEXINO - The PA5 pin is wired up to LED1, if you need to use an mma8452 on an Olimexino use a different pin and provide support in code.
|
||||||
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU, RESOURCE_EXTI, 0);
|
IOInit(IOGetByTag(IO_TAG(PA5)), OWNER_MPU_EXTI, 0);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA5)), IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
|
|
@ -257,12 +257,12 @@ void mpuIntExtiInit(void)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
#if defined (STM32F7)
|
#if defined (STM32F7)
|
||||||
IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0);
|
IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
|
||||||
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
||||||
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
|
EXTIConfig(mpuIntIO, &mpuIntCallbackRec, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ?
|
||||||
#else
|
#else
|
||||||
|
|
||||||
IOInit(mpuIntIO, OWNER_MPU, RESOURCE_EXTI, 0);
|
IOInit(mpuIntIO, OWNER_MPU_EXTI, 0);
|
||||||
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ?
|
||||||
|
|
||||||
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
EXTIHandlerInit(&mpuIntCallbackRec, mpuIntExtiHandler);
|
||||||
|
|
|
@ -15,9 +15,12 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
#define MPU6500_WHO_AM_I_CONST (0x70)
|
#define MPU6500_WHO_AM_I_CONST (0x70)
|
||||||
#define MPU9250_WHO_AM_I_CONST (0x71)
|
#define MPU9250_WHO_AM_I_CONST (0x71)
|
||||||
#define ICM20608G_WHO_AM_I_CONST (0xAF)
|
#define ICM20608G_WHO_AM_I_CONST (0xAF)
|
||||||
|
#define ICM20602_WHO_AM_I_CONST (0x12)
|
||||||
|
|
||||||
#define MPU6500_BIT_RESET (0x80)
|
#define MPU6500_BIT_RESET (0x80)
|
||||||
#define MPU6500_BIT_INT_ANYRD_2CLEAR (1 << 4)
|
#define MPU6500_BIT_INT_ANYRD_2CLEAR (1 << 4)
|
||||||
|
@ -25,8 +28,6 @@
|
||||||
#define MPU6500_BIT_I2C_IF_DIS (1 << 4)
|
#define MPU6500_BIT_I2C_IF_DIS (1 << 4)
|
||||||
#define MPU6500_BIT_RAW_RDY_EN (0x01)
|
#define MPU6500_BIT_RAW_RDY_EN (0x01)
|
||||||
|
|
||||||
#pragma once
|
|
||||||
|
|
||||||
bool mpu6500AccDetect(acc_t *acc);
|
bool mpu6500AccDetect(acc_t *acc);
|
||||||
bool mpu6500GyroDetect(gyro_t *gyro);
|
bool mpu6500GyroDetect(gyro_t *gyro);
|
||||||
|
|
||||||
|
|
|
@ -70,7 +70,7 @@ static void icm20689SpiInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
icmSpi20689CsPin = IOGetByTag(IO_TAG(ICM20689_CS_PIN));
|
icmSpi20689CsPin = IOGetByTag(IO_TAG(ICM20689_CS_PIN));
|
||||||
IOInit(icmSpi20689CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
IOInit(icmSpi20689CsPin, OWNER_MPU_CS, 0);
|
||||||
IOConfigGPIO(icmSpi20689CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(icmSpi20689CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
spiSetDivisor(ICM20689_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||||
|
|
|
@ -161,7 +161,7 @@ bool mpu6000SpiDetect(void)
|
||||||
#ifdef MPU6000_CS_PIN
|
#ifdef MPU6000_CS_PIN
|
||||||
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
|
mpuSpi6000CsPin = IOGetByTag(IO_TAG(MPU6000_CS_PIN));
|
||||||
#endif
|
#endif
|
||||||
IOInit(mpuSpi6000CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
IOInit(mpuSpi6000CsPin, OWNER_MPU_CS, 0);
|
||||||
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(mpuSpi6000CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
spiSetDivisor(MPU6000_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON);
|
||||||
|
|
|
@ -68,7 +68,7 @@ static void mpu6500SpiInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN));
|
mpuSpi6500CsPin = IOGetByTag(IO_TAG(MPU6500_CS_PIN));
|
||||||
IOInit(mpuSpi6500CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
IOInit(mpuSpi6500CsPin, OWNER_MPU_CS, 0);
|
||||||
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
|
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_CLOCK_FAST);
|
||||||
|
@ -84,7 +84,10 @@ bool mpu6500SpiDetect(void)
|
||||||
|
|
||||||
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);
|
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);
|
||||||
|
|
||||||
if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST || tmp == ICM20608G_WHO_AM_I_CONST) {
|
if (tmp == MPU6500_WHO_AM_I_CONST ||
|
||||||
|
tmp == MPU9250_WHO_AM_I_CONST ||
|
||||||
|
tmp == ICM20608G_WHO_AM_I_CONST ||
|
||||||
|
tmp == ICM20602_WHO_AM_I_CONST) {
|
||||||
return true;
|
return true;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -191,7 +191,7 @@ bool mpu9250SpiDetect(void)
|
||||||
#ifdef MPU9250_CS_PIN
|
#ifdef MPU9250_CS_PIN
|
||||||
mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
|
mpuSpi9250CsPin = IOGetByTag(IO_TAG(MPU9250_CS_PIN));
|
||||||
#endif
|
#endif
|
||||||
IOInit(mpuSpi9250CsPin, OWNER_MPU, RESOURCE_SPI_CS, 0);
|
IOInit(mpuSpi9250CsPin, OWNER_MPU_CS, 0);
|
||||||
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(mpuSpi9250CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
|
spiSetDivisor(MPU9250_SPI_INSTANCE, SPI_CLOCK_INITIALIZATON); //low speed
|
||||||
|
|
|
@ -33,7 +33,7 @@
|
||||||
//#define DEBUG_ADC_CHANNELS
|
//#define DEBUG_ADC_CHANNELS
|
||||||
|
|
||||||
#ifdef USE_ADC
|
#ifdef USE_ADC
|
||||||
adc_config_t adcConfig[ADC_CHANNEL_COUNT];
|
adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
|
||||||
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||||
|
|
||||||
uint8_t adcChannelByTag(ioTag_t ioTag)
|
uint8_t adcChannelByTag(ioTag_t ioTag)
|
||||||
|
@ -61,7 +61,7 @@ uint16_t adcGetChannel(uint8_t channel)
|
||||||
debug[3] = adcValues[adcConfig[3].dmaIndex];
|
debug[3] = adcValues[adcConfig[3].dmaIndex];
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
return adcValues[adcConfig[channel].dmaIndex];
|
return adcValues[adcOperatingConfig[channel].dmaIndex];
|
||||||
}
|
}
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
|
@ -35,14 +35,19 @@ typedef struct adc_config_s {
|
||||||
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
|
uint8_t dmaIndex; // index into DMA buffer in case of sparse channels
|
||||||
bool enabled;
|
bool enabled;
|
||||||
uint8_t sampleTime;
|
uint8_t sampleTime;
|
||||||
} adc_config_t;
|
} adcOperatingConfig_t;
|
||||||
|
|
||||||
typedef struct drv_adc_config_s {
|
typedef struct adcChannelConfig_t {
|
||||||
bool enableVBat;
|
bool enabled;
|
||||||
bool enableRSSI;
|
ioTag_t ioTag;
|
||||||
bool enableCurrentMeter;
|
} adcChannelConfig_t;
|
||||||
bool enableExternal1;
|
|
||||||
} drv_adc_config_t;
|
|
||||||
|
|
||||||
void adcInit(drv_adc_config_t *init);
|
typedef struct adcConfig_s {
|
||||||
|
adcChannelConfig_t vbat;
|
||||||
|
adcChannelConfig_t rssi;
|
||||||
|
adcChannelConfig_t currentMeter;
|
||||||
|
adcChannelConfig_t external1;
|
||||||
|
} adcConfig_t;
|
||||||
|
|
||||||
|
void adcInit(adcConfig_t *config);
|
||||||
uint16_t adcGetChannel(uint8_t channel);
|
uint16_t adcGetChannel(uint8_t channel);
|
||||||
|
|
|
@ -51,7 +51,6 @@ typedef struct adcTagMap_s {
|
||||||
typedef struct adcDevice_s {
|
typedef struct adcDevice_s {
|
||||||
ADC_TypeDef* ADCx;
|
ADC_TypeDef* ADCx;
|
||||||
rccPeriphTag_t rccADC;
|
rccPeriphTag_t rccADC;
|
||||||
rccPeriphTag_t rccDMA;
|
|
||||||
#if defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F4) || defined(STM32F7)
|
||||||
DMA_Stream_TypeDef* DMAy_Streamx;
|
DMA_Stream_TypeDef* DMAy_Streamx;
|
||||||
uint32_t channel;
|
uint32_t channel;
|
||||||
|
@ -62,7 +61,7 @@ typedef struct adcDevice_s {
|
||||||
|
|
||||||
extern const adcDevice_t adcHardware[];
|
extern const adcDevice_t adcHardware[];
|
||||||
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
|
extern const adcTagMap_t adcTagMap[ADC_TAG_MAP_COUNT];
|
||||||
extern adc_config_t adcConfig[ADC_CHANNEL_COUNT];
|
extern adcOperatingConfig_t adcOperatingConfig[ADC_CHANNEL_COUNT];
|
||||||
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
extern volatile uint16_t adcValues[ADC_CHANNEL_COUNT];
|
||||||
|
|
||||||
uint8_t adcChannelByTag(ioTag_t ioTag);
|
uint8_t adcChannelByTag(ioTag_t ioTag);
|
||||||
|
|
|
@ -32,13 +32,14 @@
|
||||||
#include "adc_impl.h"
|
#include "adc_impl.h"
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
|
#include "dma.h"
|
||||||
|
|
||||||
#ifndef ADC_INSTANCE
|
#ifndef ADC_INSTANCE
|
||||||
#define ADC_INSTANCE ADC1
|
#define ADC_INSTANCE ADC1
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const adcDevice_t adcHardware[] = {
|
const adcDevice_t adcHardware[] = {
|
||||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 }
|
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Channelx = DMA1_Channel1 }
|
||||||
};
|
};
|
||||||
|
|
||||||
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||||
|
@ -76,40 +77,28 @@ const adcTagMap_t adcTagMap[] = {
|
||||||
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
// NAZE rev.5 hardware has PA5 (ADC1_IN5) on breakout pad on bottom of board
|
||||||
//
|
//
|
||||||
|
|
||||||
void adcInit(drv_adc_config_t *init)
|
void adcInit(adcConfig_t *config)
|
||||||
{
|
{
|
||||||
|
|
||||||
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
|
|
||||||
UNUSED(init);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
uint8_t configuredAdcChannels = 0;
|
uint8_t configuredAdcChannels = 0;
|
||||||
|
|
||||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig));
|
||||||
|
|
||||||
#ifdef VBAT_ADC_PIN
|
if (config->vbat.enabled) {
|
||||||
if (init->enableVBat) {
|
adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag;
|
||||||
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef RSSI_ADC_PIN
|
if (config->rssi.enabled) {
|
||||||
if (init->enableRSSI) {
|
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
|
||||||
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EXTERNAL1_ADC_PIN
|
if (config->external1.enabled) {
|
||||||
if (init->enableExternal1) {
|
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||||
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CURRENT_METER_ADC_PIN
|
if (config->currentMeter.enabled) {
|
||||||
if (init->enableCurrentMeter) {
|
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||||
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||||
if (device == ADCINVALID)
|
if (device == ADCINVALID)
|
||||||
|
@ -117,21 +106,28 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
const adcDevice_t adc = adcHardware[device];
|
const adcDevice_t adc = adcHardware[device];
|
||||||
|
|
||||||
|
bool adcActive = false;
|
||||||
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].tag)
|
if (!adcOperatingConfig[i].tag)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i, 0);
|
adcActive = true;
|
||||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0));
|
IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0);
|
||||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AIN, 0));
|
||||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag);
|
||||||
adcConfig[i].sampleTime = ADC_SampleTime_239Cycles5;
|
adcOperatingConfig[i].dmaIndex = configuredAdcChannels++;
|
||||||
adcConfig[i].enabled = true;
|
adcOperatingConfig[i].sampleTime = ADC_SampleTime_239Cycles5;
|
||||||
|
adcOperatingConfig[i].enabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!adcActive) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
|
RCC_ADCCLKConfig(RCC_PCLK2_Div8); // 9MHz from 72MHz APB2 clock(HSE), 8MHz from 64MHz (HSI)
|
||||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
|
||||||
|
dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0);
|
||||||
|
|
||||||
DMA_DeInit(adc.DMAy_Channelx);
|
DMA_DeInit(adc.DMAy_Channelx);
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
@ -162,10 +158,10 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
uint8_t rank = 1;
|
uint8_t rank = 1;
|
||||||
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].enabled) {
|
if (!adcOperatingConfig[i].enabled) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
ADC_DMACmd(adc.ADCx, ENABLE);
|
ADC_DMACmd(adc.ADCx, ENABLE);
|
||||||
|
|
|
@ -30,6 +30,7 @@
|
||||||
#include "adc_impl.h"
|
#include "adc_impl.h"
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
|
#include "dma.h"
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
@ -38,8 +39,12 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const adcDevice_t adcHardware[] = {
|
const adcDevice_t adcHardware[] = {
|
||||||
{ .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA1), .DMAy_Channelx = DMA1_Channel1 },
|
{ .ADCx = ADC1, .rccADC = RCC_AHB(ADC12), .DMAy_Channelx = DMA1_Channel1 },
|
||||||
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .rccDMA = RCC_AHB(DMA2), .DMAy_Channelx = DMA2_Channel1 }
|
#ifdef ADC24_DMA_REMAP
|
||||||
|
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .DMAy_Channelx = DMA2_Channel3 }
|
||||||
|
#else
|
||||||
|
{ .ADCx = ADC2, .rccADC = RCC_AHB(ADC12), .DMAy_Channelx = DMA2_Channel1 }
|
||||||
|
#endif
|
||||||
};
|
};
|
||||||
|
|
||||||
const adcTagMap_t adcTagMap[] = {
|
const adcTagMap_t adcTagMap[] = {
|
||||||
|
@ -95,61 +100,62 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||||
return ADCINVALID;
|
return ADCINVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
void adcInit(drv_adc_config_t *init)
|
void adcInit(adcConfig_t *config)
|
||||||
{
|
{
|
||||||
UNUSED(init);
|
|
||||||
ADC_InitTypeDef ADC_InitStructure;
|
ADC_InitTypeDef ADC_InitStructure;
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
uint8_t adcChannelCount = 0;
|
uint8_t adcChannelCount = 0;
|
||||||
|
|
||||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig));
|
||||||
|
|
||||||
#ifdef VBAT_ADC_PIN
|
if (config->vbat.enabled) {
|
||||||
if (init->enableVBat) {
|
adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag;
|
||||||
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef RSSI_ADC_PIN
|
if (config->rssi.enabled) {
|
||||||
if (init->enableRSSI) {
|
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
|
||||||
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CURRENT_METER_ADC_PIN
|
if (config->external1.enabled) {
|
||||||
if (init->enableCurrentMeter) {
|
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||||
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EXTERNAL1_ADC_PIN
|
if (config->currentMeter.enabled) {
|
||||||
if (init->enableExternal1) {
|
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||||
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN);
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||||
if (device == ADCINVALID)
|
if (device == ADCINVALID)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
|
#ifdef ADC24_DMA_REMAP
|
||||||
|
SYSCFG_DMAChannelRemapConfig(SYSCFG_DMARemap_ADC2ADC4, ENABLE);
|
||||||
|
#endif
|
||||||
adcDevice_t adc = adcHardware[device];
|
adcDevice_t adc = adcHardware[device];
|
||||||
|
|
||||||
|
bool adcActive = false;
|
||||||
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].tag)
|
if (!adcOperatingConfig[i].tag)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY+i,0);
|
adcActive = true;
|
||||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0);
|
||||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||||
adcConfig[i].dmaIndex = adcChannelCount++;
|
adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag);
|
||||||
adcConfig[i].sampleTime = ADC_SampleTime_601Cycles5;
|
adcOperatingConfig[i].dmaIndex = adcChannelCount++;
|
||||||
adcConfig[i].enabled = true;
|
adcOperatingConfig[i].sampleTime = ADC_SampleTime_601Cycles5;
|
||||||
|
adcOperatingConfig[i].enabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!adcActive) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
||||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
|
||||||
|
dmaInit(dmaGetIdentifier(adc.DMAy_Channelx), OWNER_ADC, 0);
|
||||||
|
|
||||||
DMA_DeInit(adc.DMAy_Channelx);
|
DMA_DeInit(adc.DMAy_Channelx);
|
||||||
|
|
||||||
|
@ -204,10 +210,10 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
uint8_t rank = 1;
|
uint8_t rank = 1;
|
||||||
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].enabled) {
|
if (!adcOperatingConfig[i].enabled) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime);
|
||||||
}
|
}
|
||||||
|
|
||||||
ADC_Cmd(adc.ADCx, ENABLE);
|
ADC_Cmd(adc.ADCx, ENABLE);
|
||||||
|
|
|
@ -25,6 +25,7 @@
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "io_impl.h"
|
#include "io_impl.h"
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
|
#include "dma.h"
|
||||||
|
|
||||||
#include "sensor.h"
|
#include "sensor.h"
|
||||||
#include "accgyro.h"
|
#include "accgyro.h"
|
||||||
|
@ -37,8 +38,8 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const adcDevice_t adcHardware[] = {
|
const adcDevice_t adcHardware[] = {
|
||||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 },
|
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_Channel_0 },
|
||||||
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
||||||
};
|
};
|
||||||
|
|
||||||
/* note these could be packed up for saving space */
|
/* note these could be packed up for saving space */
|
||||||
|
@ -82,7 +83,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||||
return ADCINVALID;
|
return ADCINVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
void adcInit(drv_adc_config_t *init)
|
void adcInit(adcConfig_t *config)
|
||||||
{
|
{
|
||||||
ADC_InitTypeDef ADC_InitStructure;
|
ADC_InitTypeDef ADC_InitStructure;
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
@ -90,37 +91,23 @@ void adcInit(drv_adc_config_t *init)
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
uint8_t configuredAdcChannels = 0;
|
uint8_t configuredAdcChannels = 0;
|
||||||
|
|
||||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig));
|
||||||
|
|
||||||
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
|
if (config->vbat.enabled) {
|
||||||
UNUSED(init);
|
adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag;
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef VBAT_ADC_PIN
|
|
||||||
if (init->enableVBat) {
|
|
||||||
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); //VBAT_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef RSSI_ADC_PIN
|
if (config->rssi.enabled) {
|
||||||
if (init->enableRSSI) {
|
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
|
||||||
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EXTERNAL1_ADC_PIN
|
if (config->external1.enabled) {
|
||||||
if (init->enableExternal1) {
|
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||||
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CURRENT_METER_ADC_PIN
|
if (config->currentMeter.enabled) {
|
||||||
if (init->enableCurrentMeter) {
|
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||||
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); //CURRENT_METER_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
//RCC_ADCCLKConfig(RCC_ADC12PLLCLK_Div256); // 72 MHz divided by 256 = 281.25 kHz
|
|
||||||
|
|
||||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||||
if (device == ADCINVALID)
|
if (device == ADCINVALID)
|
||||||
|
@ -128,21 +115,28 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
adcDevice_t adc = adcHardware[device];
|
adcDevice_t adc = adcHardware[device];
|
||||||
|
|
||||||
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
bool adcActive = false;
|
||||||
if (!adcConfig[i].tag)
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
|
if (!adcOperatingConfig[i].tag)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
|
adcActive = true;
|
||||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0);
|
||||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_Mode_AN, 0, GPIO_OType_OD, GPIO_PuPd_NOPULL));
|
||||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag);
|
||||||
adcConfig[i].sampleTime = ADC_SampleTime_480Cycles;
|
adcOperatingConfig[i].dmaIndex = configuredAdcChannels++;
|
||||||
adcConfig[i].enabled = true;
|
adcOperatingConfig[i].sampleTime = ADC_SampleTime_480Cycles;
|
||||||
|
adcOperatingConfig[i].enabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!adcActive) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
|
||||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||||
|
|
||||||
|
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
|
||||||
|
|
||||||
DMA_DeInit(adc.DMAy_Streamx);
|
DMA_DeInit(adc.DMAy_Streamx);
|
||||||
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
|
@ -184,10 +178,10 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
uint8_t rank = 1;
|
uint8_t rank = 1;
|
||||||
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].enabled) {
|
if (!adcOperatingConfig[i].enabled) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
ADC_RegularChannelConfig(adc.ADCx, adcConfig[i].adcChannel, rank++, adcConfig[i].sampleTime);
|
ADC_RegularChannelConfig(adc.ADCx, adcOperatingConfig[i].adcChannel, rank++, adcOperatingConfig[i].sampleTime);
|
||||||
}
|
}
|
||||||
ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE);
|
ADC_DMARequestAfterLastTransferCmd(adc.ADCx, ENABLE);
|
||||||
|
|
||||||
|
|
|
@ -25,6 +25,7 @@
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "io_impl.h"
|
#include "io_impl.h"
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
|
#include "dma.h"
|
||||||
|
|
||||||
#include "sensor.h"
|
#include "sensor.h"
|
||||||
#include "accgyro.h"
|
#include "accgyro.h"
|
||||||
|
@ -37,8 +38,8 @@
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const adcDevice_t adcHardware[] = {
|
const adcDevice_t adcHardware[] = {
|
||||||
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_CHANNEL_0 },
|
{ .ADCx = ADC1, .rccADC = RCC_APB2(ADC1), .DMAy_Streamx = DMA2_Stream4, .channel = DMA_CHANNEL_0 },
|
||||||
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .rccDMA = RCC_AHB1(DMA2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
//{ .ADCx = ADC2, .rccADC = RCC_APB2(ADC2), .DMAy_Streamx = DMA2_Stream1, .channel = DMA_Channel_0 }
|
||||||
};
|
};
|
||||||
|
|
||||||
/* note these could be packed up for saving space */
|
/* note these could be packed up for saving space */
|
||||||
|
@ -82,7 +83,7 @@ ADCDevice adcDeviceByInstance(ADC_TypeDef *instance)
|
||||||
return ADCINVALID;
|
return ADCINVALID;
|
||||||
}
|
}
|
||||||
|
|
||||||
void adcInit(drv_adc_config_t *init)
|
void adcInit(adcConfig_t *config)
|
||||||
{
|
{
|
||||||
DMA_HandleTypeDef DmaHandle;
|
DMA_HandleTypeDef DmaHandle;
|
||||||
ADC_HandleTypeDef ADCHandle;
|
ADC_HandleTypeDef ADCHandle;
|
||||||
|
@ -90,35 +91,23 @@ void adcInit(drv_adc_config_t *init)
|
||||||
uint8_t i;
|
uint8_t i;
|
||||||
uint8_t configuredAdcChannels = 0;
|
uint8_t configuredAdcChannels = 0;
|
||||||
|
|
||||||
memset(&adcConfig, 0, sizeof(adcConfig));
|
memset(&adcOperatingConfig, 0, sizeof(adcOperatingConfig));
|
||||||
|
|
||||||
#if !defined(VBAT_ADC_PIN) && !defined(EXTERNAL1_ADC_PIN) && !defined(RSSI_ADC_PIN) && !defined(CURRENT_METER_ADC_PIN)
|
if (config->vbat.enabled) {
|
||||||
UNUSED(init);
|
adcOperatingConfig[ADC_BATTERY].tag = config->vbat.ioTag;
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef VBAT_ADC_PIN
|
|
||||||
if (init->enableVBat) {
|
|
||||||
adcConfig[ADC_BATTERY].tag = IO_TAG(VBAT_ADC_PIN); //VBAT_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef RSSI_ADC_PIN
|
if (config->rssi.enabled) {
|
||||||
if (init->enableRSSI) {
|
adcOperatingConfig[ADC_RSSI].tag = config->rssi.ioTag; //RSSI_ADC_CHANNEL;
|
||||||
adcConfig[ADC_RSSI].tag = IO_TAG(RSSI_ADC_PIN); //RSSI_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef EXTERNAL1_ADC_PIN
|
if (config->external1.enabled) {
|
||||||
if (init->enableExternal1) {
|
adcOperatingConfig[ADC_EXTERNAL1].tag = config->external1.ioTag; //EXTERNAL1_ADC_CHANNEL;
|
||||||
adcConfig[ADC_EXTERNAL1].tag = IO_TAG(EXTERNAL1_ADC_PIN); //EXTERNAL1_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
#ifdef CURRENT_METER_ADC_PIN
|
if (config->currentMeter.enabled) {
|
||||||
if (init->enableCurrentMeter) {
|
adcOperatingConfig[ADC_CURRENT].tag = config->currentMeter.ioTag; //CURRENT_METER_ADC_CHANNEL;
|
||||||
adcConfig[ADC_CURRENT].tag = IO_TAG(CURRENT_METER_ADC_PIN); //CURRENT_METER_ADC_CHANNEL;
|
|
||||||
}
|
}
|
||||||
#endif
|
|
||||||
|
|
||||||
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
ADCDevice device = adcDeviceByInstance(ADC_INSTANCE);
|
||||||
if (device == ADCINVALID)
|
if (device == ADCINVALID)
|
||||||
|
@ -126,20 +115,26 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
adcDevice_t adc = adcHardware[device];
|
adcDevice_t adc = adcHardware[device];
|
||||||
|
|
||||||
for (uint8_t i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
bool adcActive = false;
|
||||||
if (!adcConfig[i].tag)
|
for (int i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
|
if (!adcOperatingConfig[i].tag)
|
||||||
continue;
|
continue;
|
||||||
|
|
||||||
IOInit(IOGetByTag(adcConfig[i].tag), OWNER_ADC, RESOURCE_ADC_BATTERY + i, 0);
|
adcActive = true;
|
||||||
IOConfigGPIO(IOGetByTag(adcConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL));
|
IOInit(IOGetByTag(adcOperatingConfig[i].tag), OWNER_ADC_BATT + i, 0);
|
||||||
adcConfig[i].adcChannel = adcChannelByTag(adcConfig[i].tag);
|
IOConfigGPIO(IOGetByTag(adcOperatingConfig[i].tag), IO_CONFIG(GPIO_MODE_ANALOG, 0, GPIO_NOPULL));
|
||||||
adcConfig[i].dmaIndex = configuredAdcChannels++;
|
adcOperatingConfig[i].adcChannel = adcChannelByTag(adcOperatingConfig[i].tag);
|
||||||
adcConfig[i].sampleTime = ADC_SAMPLETIME_480CYCLES;
|
adcOperatingConfig[i].dmaIndex = configuredAdcChannels++;
|
||||||
adcConfig[i].enabled = true;
|
adcOperatingConfig[i].sampleTime = ADC_SAMPLETIME_480CYCLES;
|
||||||
|
adcOperatingConfig[i].enabled = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (!adcActive) {
|
||||||
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
RCC_ClockCmd(adc.rccDMA, ENABLE);
|
|
||||||
RCC_ClockCmd(adc.rccADC, ENABLE);
|
RCC_ClockCmd(adc.rccADC, ENABLE);
|
||||||
|
dmaInit(dmaGetIdentifier(adc.DMAy_Streamx), OWNER_ADC, 0);
|
||||||
|
|
||||||
ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8;
|
ADCHandle.Init.ClockPrescaler = ADC_CLOCK_SYNC_PCLK_DIV8;
|
||||||
ADCHandle.Init.ContinuousConvMode = ENABLE;
|
ADCHandle.Init.ContinuousConvMode = ENABLE;
|
||||||
|
@ -185,13 +180,13 @@ void adcInit(drv_adc_config_t *init)
|
||||||
|
|
||||||
uint8_t rank = 1;
|
uint8_t rank = 1;
|
||||||
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
for (i = 0; i < ADC_CHANNEL_COUNT; i++) {
|
||||||
if (!adcConfig[i].enabled) {
|
if (!adcOperatingConfig[i].enabled) {
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
ADC_ChannelConfTypeDef sConfig;
|
ADC_ChannelConfTypeDef sConfig;
|
||||||
sConfig.Channel = adcConfig[i].adcChannel;
|
sConfig.Channel = adcOperatingConfig[i].adcChannel;
|
||||||
sConfig.Rank = rank++;
|
sConfig.Rank = rank++;
|
||||||
sConfig.SamplingTime = adcConfig[i].sampleTime;
|
sConfig.SamplingTime = adcOperatingConfig[i].sampleTime;
|
||||||
sConfig.Offset = 0;
|
sConfig.Offset = 0;
|
||||||
|
|
||||||
/*##-3- Configure ADC regular channel ######################################*/
|
/*##-3- Configure ADC regular channel ######################################*/
|
||||||
|
|
|
@ -143,7 +143,7 @@ void bmp085InitXclrIO(const bmp085Config_t *config)
|
||||||
{
|
{
|
||||||
if (!xclrIO && config && config->xclrIO) {
|
if (!xclrIO && config && config->xclrIO) {
|
||||||
xclrIO = IOGetByTag(config->xclrIO);
|
xclrIO = IOGetByTag(config->xclrIO);
|
||||||
IOInit(xclrIO, OWNER_BARO, RESOURCE_OUTPUT, 0);
|
IOInit(xclrIO, OWNER_BARO_CS, 0);
|
||||||
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
|
IOConfigGPIO(xclrIO, IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -172,7 +172,7 @@ bool bmp085Detect(const bmp085Config_t *config, baro_t *baro)
|
||||||
if (config && config->eocIO) {
|
if (config && config->eocIO) {
|
||||||
eocIO = IOGetByTag(config->eocIO);
|
eocIO = IOGetByTag(config->eocIO);
|
||||||
// EXTI interrupt for barometer EOC
|
// EXTI interrupt for barometer EOC
|
||||||
IOInit(eocIO, OWNER_SYSTEM, RESOURCE_INPUT | RESOURCE_EXTI);
|
IOInit(eocIO, OWNER_BARO_EXTI, 0);
|
||||||
IOConfigGPIO(eocIO, Mode_IN_FLOATING);
|
IOConfigGPIO(eocIO, Mode_IN_FLOATING);
|
||||||
EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler);
|
EXTIHandlerInit(&bmp085_extiCallbackRec, bmp085_extiHandler);
|
||||||
EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, EXTI_Trigger_Rising);
|
EXTIConfig(eocIO, &bmp085_extiCallbackRec, NVIC_PRIO_BARO_EXTI, EXTI_Trigger_Rising);
|
||||||
|
|
|
@ -65,7 +65,7 @@ void bmp280SpiInit(void)
|
||||||
}
|
}
|
||||||
|
|
||||||
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
|
bmp280CsPin = IOGetByTag(IO_TAG(BMP280_CS_PIN));
|
||||||
IOInit(bmp280CsPin, OWNER_BARO, RESOURCE_SPI_CS, 0);
|
IOInit(bmp280CsPin, OWNER_BARO_CS, 0);
|
||||||
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
|
IOConfigGPIO(bmp280CsPin, IOCFG_OUT_PP);
|
||||||
|
|
||||||
DISABLE_BMP280;
|
DISABLE_BMP280;
|
||||||
|
|
|
@ -209,8 +209,8 @@ void i2cInit(I2CDevice device)
|
||||||
IO_t scl = IOGetByTag(i2c->scl);
|
IO_t scl = IOGetByTag(i2c->scl);
|
||||||
IO_t sda = IOGetByTag(i2c->sda);
|
IO_t sda = IOGetByTag(i2c->sda);
|
||||||
|
|
||||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
// Enable RCC
|
// Enable RCC
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
|
|
|
@ -387,8 +387,8 @@ void i2cInit(I2CDevice device)
|
||||||
IO_t scl = IOGetByTag(i2c->scl);
|
IO_t scl = IOGetByTag(i2c->scl);
|
||||||
IO_t sda = IOGetByTag(i2c->sda);
|
IO_t sda = IOGetByTag(i2c->sda);
|
||||||
|
|
||||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
// Enable RCC
|
// Enable RCC
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
|
|
|
@ -90,10 +90,10 @@ void i2cInit(I2CDevice device)
|
||||||
RCC_ClockCmd(i2c->rcc, ENABLE);
|
RCC_ClockCmd(i2c->rcc, ENABLE);
|
||||||
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
RCC_I2CCLKConfig(I2Cx == I2C2 ? RCC_I2C2CLK_SYSCLK : RCC_I2C1CLK_SYSCLK);
|
||||||
|
|
||||||
IOInit(scl, OWNER_I2C, RESOURCE_I2C_SCL, RESOURCE_INDEX(device));
|
IOInit(scl, OWNER_I2C_SCL, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
IOConfigGPIOAF(scl, IOCFG_I2C, GPIO_AF_4);
|
||||||
|
|
||||||
IOInit(sda, OWNER_I2C, RESOURCE_I2C_SDA, RESOURCE_INDEX(device));
|
IOInit(sda, OWNER_I2C_SDA, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
IOConfigGPIOAF(sda, IOCFG_I2C, GPIO_AF_4);
|
||||||
|
|
||||||
I2C_InitTypeDef i2cInit = {
|
I2C_InitTypeDef i2cInit = {
|
||||||
|
|
|
@ -116,9 +116,9 @@ void spiInitDevice(SPIDevice device)
|
||||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||||
|
|
||||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
|
IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device));
|
||||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
|
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
||||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
#if defined(STM32F3) || defined(STM32F4)
|
#if defined(STM32F3) || defined(STM32F4)
|
||||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||||
|
|
|
@ -79,6 +79,11 @@ typedef struct SPIDevice_s {
|
||||||
uint8_t af;
|
uint8_t af;
|
||||||
volatile uint16_t errorCount;
|
volatile uint16_t errorCount;
|
||||||
bool leadingEdge;
|
bool leadingEdge;
|
||||||
|
#if defined(STM32F7)
|
||||||
|
SPI_HandleTypeDef hspi;
|
||||||
|
DMA_HandleTypeDef hdma;
|
||||||
|
uint8_t dmaIrqHandler;
|
||||||
|
#endif
|
||||||
} spiDevice_t;
|
} spiDevice_t;
|
||||||
|
|
||||||
bool spiInit(SPIDevice device);
|
bool spiInit(SPIDevice device);
|
||||||
|
|
|
@ -70,22 +70,12 @@
|
||||||
|
|
||||||
|
|
||||||
static spiDevice_t spiHardwareMap[] = {
|
static spiDevice_t spiHardwareMap[] = {
|
||||||
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF5_SPI1, false },
|
{ .dev = SPI1, .nss = IO_TAG(SPI1_NSS_PIN), .sck = IO_TAG(SPI1_SCK_PIN), .miso = IO_TAG(SPI1_MISO_PIN), .mosi = IO_TAG(SPI1_MOSI_PIN), .rcc = RCC_APB2(SPI1), .af = GPIO_AF5_SPI1, .leadingEdge = false, .dmaIrqHandler = DMA2_ST3_HANDLER },
|
||||||
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF5_SPI2, false },
|
{ .dev = SPI2, .nss = IO_TAG(SPI2_NSS_PIN), .sck = IO_TAG(SPI2_SCK_PIN), .miso = IO_TAG(SPI2_MISO_PIN), .mosi = IO_TAG(SPI2_MOSI_PIN), .rcc = RCC_APB1(SPI2), .af = GPIO_AF5_SPI2, .leadingEdge = false, .dmaIrqHandler = DMA1_ST4_HANDLER },
|
||||||
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF5_SPI3, false },
|
{ .dev = SPI3, .nss = IO_TAG(SPI3_NSS_PIN), .sck = IO_TAG(SPI3_SCK_PIN), .miso = IO_TAG(SPI3_MISO_PIN), .mosi = IO_TAG(SPI3_MOSI_PIN), .rcc = RCC_APB1(SPI3), .af = GPIO_AF5_SPI3, .leadingEdge = false, .dmaIrqHandler = DMA1_ST7_HANDLER },
|
||||||
{ .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .af = GPIO_AF5_SPI4, false }
|
{ .dev = SPI4, .nss = IO_TAG(SPI4_NSS_PIN), .sck = IO_TAG(SPI4_SCK_PIN), .miso = IO_TAG(SPI4_MISO_PIN), .mosi = IO_TAG(SPI4_MOSI_PIN), .rcc = RCC_APB2(SPI4), .af = GPIO_AF5_SPI4, .leadingEdge = false, .dmaIrqHandler = DMA2_ST1_HANDLER }
|
||||||
};
|
};
|
||||||
|
|
||||||
typedef struct{
|
|
||||||
SPI_HandleTypeDef Handle;
|
|
||||||
}spiHandle_t;
|
|
||||||
static spiHandle_t spiHandle[SPIDEV_MAX+1];
|
|
||||||
|
|
||||||
typedef struct{
|
|
||||||
DMA_HandleTypeDef Handle;
|
|
||||||
}dmaHandle_t;
|
|
||||||
static dmaHandle_t dmaHandle[SPIDEV_MAX+1];
|
|
||||||
|
|
||||||
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
if (instance == SPI1)
|
if (instance == SPI1)
|
||||||
|
@ -105,32 +95,32 @@ SPIDevice spiDeviceByInstance(SPI_TypeDef *instance)
|
||||||
|
|
||||||
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
|
SPI_HandleTypeDef* spiHandleByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
return &spiHandle[spiDeviceByInstance(instance)].Handle;
|
return &spiHardwareMap[spiDeviceByInstance(instance)].hspi;
|
||||||
}
|
}
|
||||||
|
|
||||||
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
|
DMA_HandleTypeDef* dmaHandleByInstance(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
return &dmaHandle[spiDeviceByInstance(instance)].Handle;
|
return &spiHardwareMap[spiDeviceByInstance(instance)].hdma;
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI1_IRQHandler(void)
|
void SPI1_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHandle[SPIDEV_1].Handle);
|
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_1].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI2_IRQHandler(void)
|
void SPI2_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHandle[SPIDEV_2].Handle);
|
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_2].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI3_IRQHandler(void)
|
void SPI3_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHandle[SPIDEV_3].Handle);
|
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_3].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
void SPI4_IRQHandler(void)
|
void SPI4_IRQHandler(void)
|
||||||
{
|
{
|
||||||
HAL_SPI_IRQHandler(&spiHandle[SPIDEV_4].Handle);
|
HAL_SPI_IRQHandler(&spiHardwareMap[SPIDEV_4].hspi);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -155,9 +145,9 @@ void spiInitDevice(SPIDevice device)
|
||||||
RCC_ClockCmd(spi->rcc, ENABLE);
|
RCC_ClockCmd(spi->rcc, ENABLE);
|
||||||
RCC_ResetCmd(spi->rcc, ENABLE);
|
RCC_ResetCmd(spi->rcc, ENABLE);
|
||||||
|
|
||||||
IOInit(IOGetByTag(spi->sck), OWNER_SPI, RESOURCE_SPI_SCK, device + 1);
|
IOInit(IOGetByTag(spi->sck), OWNER_SPI_SCK, RESOURCE_INDEX(device));
|
||||||
IOInit(IOGetByTag(spi->miso), OWNER_SPI, RESOURCE_SPI_MISO, device + 1);
|
IOInit(IOGetByTag(spi->miso), OWNER_SPI_MISO, RESOURCE_INDEX(device));
|
||||||
IOInit(IOGetByTag(spi->mosi), OWNER_SPI, RESOURCE_SPI_MOSI, device + 1);
|
IOInit(IOGetByTag(spi->mosi), OWNER_SPI_MOSI, RESOURCE_INDEX(device));
|
||||||
|
|
||||||
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F3) || defined(STM32F4) || defined(STM32F7)
|
||||||
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
IOConfigGPIOAF(IOGetByTag(spi->sck), SPI_IO_AF_CFG, spi->af);
|
||||||
|
@ -177,10 +167,9 @@ void spiInitDevice(SPIDevice device)
|
||||||
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
|
IOConfigGPIO(IOGetByTag(spi->nss), SPI_IO_CS_CFG);
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
SPI_HandleTypeDef Handle;
|
spiHardwareMap[device].hspi.Instance = spi->dev;
|
||||||
Handle.Instance = spi->dev;
|
|
||||||
// Init SPI hardware
|
// Init SPI hardware
|
||||||
HAL_SPI_DeInit(&Handle);
|
HAL_SPI_DeInit(&spiHardwareMap[device].hspi);
|
||||||
|
|
||||||
spiInit.Mode = SPI_MODE_MASTER;
|
spiInit.Mode = SPI_MODE_MASTER;
|
||||||
spiInit.Direction = SPI_DIRECTION_2LINES;
|
spiInit.Direction = SPI_DIRECTION_2LINES;
|
||||||
|
@ -201,15 +190,10 @@ void spiInitDevice(SPIDevice device)
|
||||||
spiInit.CLKPhase = SPI_PHASE_2EDGE;
|
spiInit.CLKPhase = SPI_PHASE_2EDGE;
|
||||||
}
|
}
|
||||||
|
|
||||||
Handle.Init = spiInit;
|
spiHardwareMap[device].hspi.Init = spiInit;
|
||||||
#ifdef STM32F303xC
|
|
||||||
// Configure for 8-bit reads.
|
|
||||||
SPI_RxFIFOThresholdConfig(spi->dev, SPI_RxFIFOThreshold_QF);
|
|
||||||
#endif
|
|
||||||
|
|
||||||
if (HAL_SPI_Init(&Handle) == HAL_OK)
|
if (HAL_SPI_Init(&spiHardwareMap[device].hspi) == HAL_OK)
|
||||||
{
|
{
|
||||||
spiHandle[device].Handle = Handle;
|
|
||||||
if (spi->nss) {
|
if (spi->nss) {
|
||||||
IOHi(IOGetByTag(spi->nss));
|
IOHi(IOGetByTag(spi->nss));
|
||||||
}
|
}
|
||||||
|
@ -275,7 +259,8 @@ uint8_t spiTransferByte(SPI_TypeDef *instance, uint8_t in)
|
||||||
*/
|
*/
|
||||||
bool spiIsBusBusy(SPI_TypeDef *instance)
|
bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||||
{
|
{
|
||||||
if(spiHandle[spiDeviceByInstance(instance)].Handle.State == HAL_SPI_STATE_BUSY)
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
|
if(spiHardwareMap[device].hspi.State == HAL_SPI_STATE_BUSY)
|
||||||
return true;
|
return true;
|
||||||
else
|
else
|
||||||
return false;
|
return false;
|
||||||
|
@ -283,21 +268,22 @@ bool spiIsBusBusy(SPI_TypeDef *instance)
|
||||||
|
|
||||||
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
|
bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len)
|
||||||
{
|
{
|
||||||
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
HAL_StatusTypeDef status;
|
HAL_StatusTypeDef status;
|
||||||
|
|
||||||
#define SPI_DEFAULT_TIMEOUT 10
|
#define SPI_DEFAULT_TIMEOUT 10
|
||||||
|
|
||||||
if(!out) // Tx only
|
if(!out) // Tx only
|
||||||
{
|
{
|
||||||
status = HAL_SPI_Transmit(&spiHandle[spiDeviceByInstance(instance)].Handle, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_Transmit(&spiHardwareMap[device].hspi, (uint8_t *)in, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
else if(!in) // Rx only
|
else if(!in) // Rx only
|
||||||
{
|
{
|
||||||
status = HAL_SPI_Receive(&spiHandle[spiDeviceByInstance(instance)].Handle, out, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_Receive(&spiHardwareMap[device].hspi, out, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
else // Tx and Rx
|
else // Tx and Rx
|
||||||
{
|
{
|
||||||
status = HAL_SPI_TransmitReceive(&spiHandle[spiDeviceByInstance(instance)].Handle, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
status = HAL_SPI_TransmitReceive(&spiHardwareMap[device].hspi, (uint8_t *)in, out, len, SPI_DEFAULT_TIMEOUT);
|
||||||
}
|
}
|
||||||
|
|
||||||
if( status != HAL_OK)
|
if( status != HAL_OK)
|
||||||
|
@ -309,46 +295,46 @@ bool spiTransfer(SPI_TypeDef *instance, uint8_t *out, const uint8_t *in, int len
|
||||||
|
|
||||||
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
void spiSetDivisor(SPI_TypeDef *instance, uint16_t divisor)
|
||||||
{
|
{
|
||||||
SPI_HandleTypeDef *Handle = &spiHandle[spiDeviceByInstance(instance)].Handle;
|
SPIDevice device = spiDeviceByInstance(instance);
|
||||||
if (HAL_SPI_DeInit(Handle) == HAL_OK)
|
if (HAL_SPI_DeInit(&spiHardwareMap[device].hspi) == HAL_OK)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
|
|
||||||
switch (divisor) {
|
switch (divisor) {
|
||||||
case 2:
|
case 2:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_2;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 4:
|
case 4:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_4;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 8:
|
case 8:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_8;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 16:
|
case 16:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_16;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 32:
|
case 32:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_32;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 64:
|
case 64:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_64;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 128:
|
case 128:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_128;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_128;
|
||||||
break;
|
break;
|
||||||
|
|
||||||
case 256:
|
case 256:
|
||||||
Handle->Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
spiHardwareMap[device].hspi.Init.BaudRatePrescaler = SPI_BAUDRATEPRESCALER_256;
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
if (HAL_SPI_Init(Handle) == HAL_OK)
|
if (HAL_SPI_Init(&spiHardwareMap[device].hspi) == HAL_OK)
|
||||||
{
|
{
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -370,68 +356,44 @@ void spiResetErrorCounter(SPI_TypeDef *instance)
|
||||||
|
|
||||||
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
void dmaSPIIRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
{
|
{
|
||||||
DMA_HandleTypeDef * hdma = &dmaHandle[(descriptor->userParam)].Handle;
|
SPIDevice device = descriptor->userParam;
|
||||||
|
if (device != SPIINVALID)
|
||||||
HAL_DMA_IRQHandler(hdma);
|
HAL_DMA_IRQHandler(&spiHardwareMap[device].hdma);
|
||||||
|
|
||||||
//SCB_InvalidateDCache_by_Addr();
|
|
||||||
|
|
||||||
/*if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF))
|
|
||||||
{
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_HTIF);
|
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_FEIF))
|
|
||||||
{
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_FEIF);
|
|
||||||
}
|
|
||||||
}
|
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TEIF))
|
|
||||||
{
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TEIF);
|
|
||||||
}
|
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_DMEIF))
|
|
||||||
{
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_DMEIF);
|
|
||||||
}*/
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size)
|
DMA_HandleTypeDef* spiSetDMATransmit(DMA_Stream_TypeDef *Stream, uint32_t Channel, SPI_TypeDef *Instance, uint8_t *pData, uint16_t Size)
|
||||||
{
|
{
|
||||||
SPI_HandleTypeDef* hspi = &spiHandle[spiDeviceByInstance(Instance)].Handle;
|
SPIDevice device = spiDeviceByInstance(Instance);
|
||||||
DMA_HandleTypeDef* hdma = &dmaHandle[spiDeviceByInstance(Instance)].Handle;
|
|
||||||
|
|
||||||
hdma->Instance = Stream;
|
spiHardwareMap[device].hdma.Instance = Stream;
|
||||||
hdma->Init.Channel = Channel;
|
spiHardwareMap[device].hdma.Init.Channel = Channel;
|
||||||
hdma->Init.Direction = DMA_MEMORY_TO_PERIPH;
|
spiHardwareMap[device].hdma.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
||||||
hdma->Init.PeriphInc = DMA_PINC_DISABLE;
|
spiHardwareMap[device].hdma.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||||
hdma->Init.MemInc = DMA_MINC_ENABLE;
|
spiHardwareMap[device].hdma.Init.MemInc = DMA_MINC_ENABLE;
|
||||||
hdma->Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
|
spiHardwareMap[device].hdma.Init.PeriphDataAlignment = DMA_PDATAALIGN_BYTE;
|
||||||
hdma->Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
|
spiHardwareMap[device].hdma.Init.MemDataAlignment = DMA_MDATAALIGN_BYTE;
|
||||||
hdma->Init.Mode = DMA_NORMAL;
|
spiHardwareMap[device].hdma.Init.Mode = DMA_NORMAL;
|
||||||
hdma->Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
spiHardwareMap[device].hdma.Init.FIFOMode = DMA_FIFOMODE_DISABLE;
|
||||||
hdma->Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
|
spiHardwareMap[device].hdma.Init.FIFOThreshold = DMA_FIFO_THRESHOLD_1QUARTERFULL;
|
||||||
hdma->Init.PeriphBurst = DMA_PBURST_SINGLE;
|
spiHardwareMap[device].hdma.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||||
hdma->Init.MemBurst = DMA_MBURST_SINGLE;
|
spiHardwareMap[device].hdma.Init.MemBurst = DMA_MBURST_SINGLE;
|
||||||
hdma->Init.Priority = DMA_PRIORITY_LOW;
|
spiHardwareMap[device].hdma.Init.Priority = DMA_PRIORITY_LOW;
|
||||||
|
|
||||||
|
HAL_DMA_DeInit(&spiHardwareMap[device].hdma);
|
||||||
|
HAL_DMA_Init(&spiHardwareMap[device].hdma);
|
||||||
|
|
||||||
HAL_DMA_DeInit(hdma);
|
__HAL_DMA_ENABLE(&spiHardwareMap[device].hdma);
|
||||||
HAL_DMA_Init(hdma);
|
__HAL_SPI_ENABLE(&spiHardwareMap[device].hspi);
|
||||||
|
|
||||||
__HAL_DMA_ENABLE(hdma);
|
|
||||||
__HAL_SPI_ENABLE(hspi);
|
|
||||||
/* Associate the initialized DMA handle to the spi handle */
|
/* Associate the initialized DMA handle to the spi handle */
|
||||||
__HAL_LINKDMA(hspi, hdmatx, (*hdma));
|
__HAL_LINKDMA(&spiHardwareMap[device].hspi, hdmatx, spiHardwareMap[device].hdma);
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
dmaSetHandler(DMA2_ST1_HANDLER, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)spiDeviceByInstance(Instance));
|
dmaSetHandler(spiHardwareMap[device].dmaIrqHandler, dmaSPIIRQHandler, NVIC_BUILD_PRIORITY(3, 0), (uint32_t)device);
|
||||||
|
|
||||||
// SCB_CleanDCache_by_Addr((uint32_t) pData, Size);
|
// And Transmit
|
||||||
|
HAL_SPI_Transmit_DMA(&spiHardwareMap[device].hspi, pData, Size);
|
||||||
|
|
||||||
HAL_SPI_Transmit_DMA(hspi, pData, Size);
|
return &spiHardwareMap[device].hdma;
|
||||||
|
|
||||||
//HAL_DMA_Start(&hdma, (uint32_t) pData, (uint32_t) &(Instance->DR), Size);
|
|
||||||
|
|
||||||
return hdma;
|
|
||||||
}
|
}
|
||||||
|
|
|
@ -34,7 +34,7 @@
|
||||||
void softSpiInit(const softSPIDevice_t *dev)
|
void softSpiInit(const softSPIDevice_t *dev)
|
||||||
{
|
{
|
||||||
// SCK as output
|
// SCK as output
|
||||||
IOInit(IOGetByTag(dev->sckTag), OWNER_SOFTSPI, RESOURCE_SPI_SCK, SOFT_SPIDEV_1 + 1);
|
IOInit(IOGetByTag(dev->sckTag), OWNER_SPI_SCK, RESOURCE_INDEX(SOFT_SPIDEV_1) + 10);
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
IOConfigGPIO(IOGetByTag(dev->sckTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
IOConfigGPIO(IOGetByTag(dev->sckTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
@ -42,7 +42,7 @@ void softSpiInit(const softSPIDevice_t *dev)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// MOSI as output
|
// MOSI as output
|
||||||
IOInit(IOGetByTag(dev->mosiTag), OWNER_SOFTSPI, RESOURCE_SPI_MOSI, SOFT_SPIDEV_1 + 1);
|
IOInit(IOGetByTag(dev->mosiTag), OWNER_SPI_MOSI, RESOURCE_INDEX(SOFT_SPIDEV_1) + 10);
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
IOConfigGPIO(IOGetByTag(dev->mosiTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
IOConfigGPIO(IOGetByTag(dev->mosiTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
@ -50,7 +50,7 @@ void softSpiInit(const softSPIDevice_t *dev)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
// MISO as input
|
// MISO as input
|
||||||
IOInit(IOGetByTag(dev->misoTag), OWNER_SOFTSPI, RESOURCE_SPI_MISO, SOFT_SPIDEV_1 + 1);
|
IOInit(IOGetByTag(dev->misoTag), OWNER_SPI_MISO, RESOURCE_INDEX(SOFT_SPIDEV_1) + 10);
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
IOConfigGPIO(IOGetByTag(dev->misoTag), IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz));
|
IOConfigGPIO(IOGetByTag(dev->misoTag), IO_CONFIG(GPIO_Mode_IN_FLOATING, GPIO_Speed_50MHz));
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
@ -59,7 +59,7 @@ void softSpiInit(const softSPIDevice_t *dev)
|
||||||
|
|
||||||
// NSS as output
|
// NSS as output
|
||||||
if (dev->nssTag != IOTAG_NONE) {
|
if (dev->nssTag != IOTAG_NONE) {
|
||||||
IOInit(IOGetByTag(dev->nssTag), OWNER_SOFTSPI, RESOURCE_SPI_CS, SOFT_SPIDEV_1 + 1);
|
IOInit(IOGetByTag(dev->nssTag), OWNER_SPI_CS, RESOURCE_INDEX(SOFT_SPIDEV_1) + 10);
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
IOConfigGPIO(IOGetByTag(dev->nssTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
IOConfigGPIO(IOGetByTag(dev->nssTag), IO_CONFIG(GPIO_Mode_Out_PP, GPIO_Speed_50MHz));
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
|
72
src/main/drivers/display.c
Normal file
72
src/main/drivers/display.c
Normal file
|
@ -0,0 +1,72 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include <stdbool.h>
|
||||||
|
#include <stdint.h>
|
||||||
|
|
||||||
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "common/utils.h"
|
||||||
|
|
||||||
|
#include "display.h"
|
||||||
|
|
||||||
|
void displayClear(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
instance->vTable->clear(instance);
|
||||||
|
instance->cleared = true;
|
||||||
|
instance->cursorRow = -1;
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayGrab(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
instance->vTable->grab(instance);
|
||||||
|
instance->vTable->clear(instance);
|
||||||
|
instance->isGrabbed = true;
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayRelease(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
instance->vTable->release(instance);
|
||||||
|
instance->isGrabbed = false;
|
||||||
|
}
|
||||||
|
|
||||||
|
bool displayIsGrabbed(const displayPort_t *instance)
|
||||||
|
{
|
||||||
|
// can be called before initialised
|
||||||
|
return (instance && instance->isGrabbed);
|
||||||
|
}
|
||||||
|
|
||||||
|
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, const char *s)
|
||||||
|
{
|
||||||
|
return instance->vTable->write(instance, x, y, s);
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayHeartbeat(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
instance->vTable->heartbeat(instance);
|
||||||
|
}
|
||||||
|
|
||||||
|
void displayResync(displayPort_t *instance)
|
||||||
|
{
|
||||||
|
instance->vTable->resync(instance);
|
||||||
|
}
|
||||||
|
|
||||||
|
uint16_t displayTxBytesFree(const displayPort_t *instance)
|
||||||
|
{
|
||||||
|
return instance->vTable->txBytesFree(instance);
|
||||||
|
}
|
||||||
|
|
49
src/main/drivers/display.h
Normal file
49
src/main/drivers/display.h
Normal file
|
@ -0,0 +1,49 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
struct displayPortVTable_s;
|
||||||
|
typedef struct displayPort_s {
|
||||||
|
const struct displayPortVTable_s *vTable;
|
||||||
|
uint8_t rows;
|
||||||
|
uint8_t cols;
|
||||||
|
|
||||||
|
// CMS state
|
||||||
|
bool cleared;
|
||||||
|
int8_t cursorRow;
|
||||||
|
bool isGrabbed;
|
||||||
|
} displayPort_t;
|
||||||
|
|
||||||
|
typedef struct displayPortVTable_s {
|
||||||
|
int (*grab)(displayPort_t *displayPort);
|
||||||
|
int (*release)(displayPort_t *displayPort);
|
||||||
|
int (*clear)(displayPort_t *displayPort);
|
||||||
|
int (*write)(displayPort_t *displayPort, uint8_t x, uint8_t y, const char *text);
|
||||||
|
int (*heartbeat)(displayPort_t *displayPort);
|
||||||
|
void (*resync)(displayPort_t *displayPort);
|
||||||
|
uint32_t (*txBytesFree)(const displayPort_t *displayPort);
|
||||||
|
} displayPortVTable_t;
|
||||||
|
|
||||||
|
void displayGrab(displayPort_t *instance);
|
||||||
|
void displayRelease(displayPort_t *instance);
|
||||||
|
bool displayIsGrabbed(const displayPort_t *instance);
|
||||||
|
void displayClear(displayPort_t *instance);
|
||||||
|
int displayWrite(displayPort_t *instance, uint8_t x, uint8_t y, const char *s);
|
||||||
|
void displayHeartbeat(displayPort_t *instance);
|
||||||
|
void displayResync(displayPort_t *instance);
|
||||||
|
uint16_t displayTxBytesFree(const displayPort_t *instance);
|
|
@ -63,16 +63,18 @@ DEFINE_DMA_IRQ_HANDLER(2, 4, DMA2_CH4_HANDLER)
|
||||||
DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER)
|
DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_CH5_HANDLER)
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex)
|
||||||
void dmaInit(void)
|
|
||||||
{
|
{
|
||||||
// TODO: Do we need this?
|
RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
||||||
|
dmaDescriptors[identifier].owner = owner;
|
||||||
|
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||||
{
|
{
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
/* TODO: remove this - enforce the init */
|
||||||
RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
RCC_AHBPeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
||||||
dmaDescriptors[identifier].irqHandlerCallback = callback;
|
dmaDescriptors[identifier].irqHandlerCallback = callback;
|
||||||
dmaDescriptors[identifier].userParam = userParam;
|
dmaDescriptors[identifier].userParam = userParam;
|
||||||
|
@ -84,3 +86,22 @@ void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr
|
||||||
NVIC_Init(&NVIC_InitStructure);
|
NVIC_Init(&NVIC_InitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].owner;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].resourceIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
|
||||||
|
if (dmaDescriptors[i].channel == channel) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -15,10 +15,29 @@
|
||||||
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
*/
|
*/
|
||||||
|
|
||||||
|
#pragma once
|
||||||
|
|
||||||
|
#include "resource.h"
|
||||||
|
|
||||||
struct dmaChannelDescriptor_s;
|
struct dmaChannelDescriptor_s;
|
||||||
typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor);
|
typedef void (*dmaCallbackHandlerFuncPtr)(struct dmaChannelDescriptor_s *channelDescriptor);
|
||||||
|
|
||||||
|
typedef struct dmaChannelDescriptor_s {
|
||||||
|
DMA_TypeDef* dma;
|
||||||
|
#if defined(STM32F4) || defined(STM32F7)
|
||||||
|
DMA_Stream_TypeDef* stream;
|
||||||
|
#else
|
||||||
|
DMA_Channel_TypeDef* channel;
|
||||||
|
#endif
|
||||||
|
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
||||||
|
uint8_t flagsShift;
|
||||||
|
IRQn_Type irqN;
|
||||||
|
uint32_t rcc;
|
||||||
|
uint32_t userParam;
|
||||||
|
resourceOwner_e owner;
|
||||||
|
uint8_t resourceIndex;
|
||||||
|
} dmaChannelDescriptor_t;
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F4) || defined(STM32F7)
|
||||||
|
|
||||||
uint32_t dmaFlag_IT_TCIF(const DMA_Stream_TypeDef *stream);
|
uint32_t dmaFlag_IT_TCIF(const DMA_Stream_TypeDef *stream);
|
||||||
|
@ -40,19 +59,15 @@ typedef enum {
|
||||||
DMA2_ST5_HANDLER,
|
DMA2_ST5_HANDLER,
|
||||||
DMA2_ST6_HANDLER,
|
DMA2_ST6_HANDLER,
|
||||||
DMA2_ST7_HANDLER,
|
DMA2_ST7_HANDLER,
|
||||||
} dmaHandlerIdentifier_e;
|
DMA_MAX_DESCRIPTORS
|
||||||
|
} dmaIdentifier_e;
|
||||||
|
|
||||||
typedef struct dmaChannelDescriptor_s {
|
#define DMA_MOD_VALUE 8
|
||||||
DMA_TypeDef* dma;
|
#define DMA_MOD_OFFSET 0
|
||||||
DMA_Stream_TypeDef* stream;
|
#define DMA_OUTPUT_INDEX 0
|
||||||
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
#define DMA_OUTPUT_STRING "DMA%d Stream %d:"
|
||||||
uint8_t flagsShift;
|
|
||||||
IRQn_Type irqN;
|
|
||||||
uint32_t rcc;
|
|
||||||
uint32_t userParam;
|
|
||||||
} dmaChannelDescriptor_t;
|
|
||||||
|
|
||||||
#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
#define DEFINE_DMA_CHANNEL(d, s, f, i, r) {.dma = d, .stream = s, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0, .owner = 0, .resourceIndex = 0 }
|
||||||
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
#define DEFINE_DMA_IRQ_HANDLER(d, s, i) void DMA ## d ## _Stream ## s ## _IRQHandler(void) {\
|
||||||
if (dmaDescriptors[i].irqHandlerCallback)\
|
if (dmaDescriptors[i].irqHandlerCallback)\
|
||||||
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
||||||
|
@ -68,6 +83,8 @@ typedef struct dmaChannelDescriptor_s {
|
||||||
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
|
#define DMA_IT_DMEIF ((uint32_t)0x00000004)
|
||||||
#define DMA_IT_FEIF ((uint32_t)0x00000001)
|
#define DMA_IT_FEIF ((uint32_t)0x00000001)
|
||||||
|
|
||||||
|
dmaIdentifier_e dmaGetIdentifier(const DMA_Stream_TypeDef* stream);
|
||||||
|
|
||||||
#else
|
#else
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
|
@ -78,24 +95,22 @@ typedef enum {
|
||||||
DMA1_CH5_HANDLER,
|
DMA1_CH5_HANDLER,
|
||||||
DMA1_CH6_HANDLER,
|
DMA1_CH6_HANDLER,
|
||||||
DMA1_CH7_HANDLER,
|
DMA1_CH7_HANDLER,
|
||||||
|
#if defined(STM32F3) || defined(STM32F10X_CL)
|
||||||
DMA2_CH1_HANDLER,
|
DMA2_CH1_HANDLER,
|
||||||
DMA2_CH2_HANDLER,
|
DMA2_CH2_HANDLER,
|
||||||
DMA2_CH3_HANDLER,
|
DMA2_CH3_HANDLER,
|
||||||
DMA2_CH4_HANDLER,
|
DMA2_CH4_HANDLER,
|
||||||
DMA2_CH5_HANDLER,
|
DMA2_CH5_HANDLER,
|
||||||
} dmaHandlerIdentifier_e;
|
#endif
|
||||||
|
DMA_MAX_DESCRIPTORS
|
||||||
|
} dmaIdentifier_e;
|
||||||
|
|
||||||
typedef struct dmaChannelDescriptor_s {
|
#define DMA_MOD_VALUE 7
|
||||||
DMA_TypeDef* dma;
|
#define DMA_MOD_OFFSET 1
|
||||||
DMA_Channel_TypeDef* channel;
|
#define DMA_OUTPUT_INDEX 0
|
||||||
dmaCallbackHandlerFuncPtr irqHandlerCallback;
|
#define DMA_OUTPUT_STRING "DMA%d Channel %d:"
|
||||||
uint8_t flagsShift;
|
|
||||||
IRQn_Type irqN;
|
|
||||||
uint32_t rcc;
|
|
||||||
uint32_t userParam;
|
|
||||||
} dmaChannelDescriptor_t;
|
|
||||||
|
|
||||||
#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0}
|
#define DEFINE_DMA_CHANNEL(d, c, f, i, r) {.dma = d, .channel = c, .irqHandlerCallback = NULL, .flagsShift = f, .irqN = i, .rcc = r, .userParam = 0, .owner = 0, .resourceIndex = 0 }
|
||||||
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
#define DEFINE_DMA_IRQ_HANDLER(d, c, i) void DMA ## d ## _Channel ## c ## _IRQHandler(void) {\
|
||||||
if (dmaDescriptors[i].irqHandlerCallback)\
|
if (dmaDescriptors[i].irqHandlerCallback)\
|
||||||
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
dmaDescriptors[i].irqHandlerCallback(&dmaDescriptors[i]);\
|
||||||
|
@ -108,8 +123,12 @@ typedef struct dmaChannelDescriptor_s {
|
||||||
#define DMA_IT_HTIF ((uint32_t)0x00000004)
|
#define DMA_IT_HTIF ((uint32_t)0x00000004)
|
||||||
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
#define DMA_IT_TEIF ((uint32_t)0x00000008)
|
||||||
|
|
||||||
|
dmaIdentifier_e dmaGetIdentifier(const DMA_Channel_TypeDef* channel);
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void dmaInit(void);
|
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex);
|
||||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam);
|
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam);
|
||||||
|
|
||||||
|
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier);
|
||||||
|
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier);
|
||||||
|
|
|
@ -23,11 +23,12 @@
|
||||||
|
|
||||||
#include "nvic.h"
|
#include "nvic.h"
|
||||||
#include "dma.h"
|
#include "dma.h"
|
||||||
|
#include "resource.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* DMA descriptors.
|
* DMA descriptors.
|
||||||
*/
|
*/
|
||||||
static dmaChannelDescriptor_t dmaDescriptors[] = {
|
static dmaChannelDescriptor_t dmaDescriptors[DMA_MAX_DESCRIPTORS] = {
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream0, 0, DMA1_Stream0_IRQn, RCC_AHB1Periph_DMA1),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream0, 0, DMA1_Stream0_IRQn, RCC_AHB1Periph_DMA1),
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream1, 6, DMA1_Stream1_IRQn, RCC_AHB1Periph_DMA1),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream1, 6, DMA1_Stream1_IRQn, RCC_AHB1Periph_DMA1),
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream2, 16, DMA1_Stream2_IRQn, RCC_AHB1Periph_DMA1),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream2, 16, DMA1_Stream2_IRQn, RCC_AHB1Periph_DMA1),
|
||||||
|
@ -67,12 +68,14 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
|
||||||
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
||||||
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
||||||
|
|
||||||
void dmaInit(void)
|
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex)
|
||||||
{
|
{
|
||||||
// TODO: Do we need this?
|
RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
||||||
|
dmaDescriptors[identifier].owner = owner;
|
||||||
|
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||||
}
|
}
|
||||||
|
|
||||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||||
{
|
{
|
||||||
NVIC_InitTypeDef NVIC_InitStructure;
|
NVIC_InitTypeDef NVIC_InitStructure;
|
||||||
|
|
||||||
|
@ -101,3 +104,23 @@ uint32_t dmaFlag_IT_TCIF(const DMA_Stream_TypeDef *stream)
|
||||||
RETURN_TCIF_FLAG(stream, 7);
|
RETURN_TCIF_FLAG(stream, 7);
|
||||||
return 0;
|
return 0;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].owner;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].resourceIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
dmaIdentifier_e dmaGetIdentifier(const DMA_Stream_TypeDef* stream)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
|
||||||
|
if (dmaDescriptors[i].stream == stream) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -23,11 +23,12 @@
|
||||||
|
|
||||||
#include "drivers/nvic.h"
|
#include "drivers/nvic.h"
|
||||||
#include "drivers/dma.h"
|
#include "drivers/dma.h"
|
||||||
|
#include "resource.h"
|
||||||
|
|
||||||
/*
|
/*
|
||||||
* DMA descriptors.
|
* DMA descriptors.
|
||||||
*/
|
*/
|
||||||
static dmaChannelDescriptor_t dmaDescriptors[] = {
|
static dmaChannelDescriptor_t dmaDescriptors[DMA_MAX_DESCRIPTORS] = {
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream0, 0, DMA1_Stream0_IRQn, RCC_AHB1ENR_DMA1EN),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream0, 0, DMA1_Stream0_IRQn, RCC_AHB1ENR_DMA1EN),
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream1, 6, DMA1_Stream1_IRQn, RCC_AHB1ENR_DMA1EN),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream1, 6, DMA1_Stream1_IRQn, RCC_AHB1ENR_DMA1EN),
|
||||||
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream2, 16, DMA1_Stream2_IRQn, RCC_AHB1ENR_DMA1EN),
|
DEFINE_DMA_CHANNEL(DMA1, DMA1_Stream2, 16, DMA1_Stream2_IRQn, RCC_AHB1ENR_DMA1EN),
|
||||||
|
@ -68,30 +69,50 @@ DEFINE_DMA_IRQ_HANDLER(2, 5, DMA2_ST5_HANDLER)
|
||||||
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
DEFINE_DMA_IRQ_HANDLER(2, 6, DMA2_ST6_HANDLER)
|
||||||
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
DEFINE_DMA_IRQ_HANDLER(2, 7, DMA2_ST7_HANDLER)
|
||||||
|
|
||||||
|
static void enableDmaClock(uint32_t rcc)
|
||||||
void dmaInit(void)
|
|
||||||
{
|
{
|
||||||
// TODO: Do we need this?
|
|
||||||
}
|
|
||||||
|
|
||||||
void dmaSetHandler(dmaHandlerIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
|
||||||
{
|
|
||||||
//clock
|
|
||||||
//RCC_AHB1PeriphClockCmd(dmaDescriptors[identifier].rcc, ENABLE);
|
|
||||||
|
|
||||||
do {
|
do {
|
||||||
__IO uint32_t tmpreg;
|
__IO uint32_t tmpreg;
|
||||||
SET_BIT(RCC->AHB1ENR, dmaDescriptors[identifier].rcc);
|
SET_BIT(RCC->AHB1ENR, rcc);
|
||||||
/* Delay after an RCC peripheral clock enabling */
|
/* Delay after an RCC peripheral clock enabling */
|
||||||
tmpreg = READ_BIT(RCC->AHB1ENR, dmaDescriptors[identifier].rcc);
|
tmpreg = READ_BIT(RCC->AHB1ENR, rcc);
|
||||||
UNUSED(tmpreg);
|
UNUSED(tmpreg);
|
||||||
} while(0);
|
} while(0);
|
||||||
|
}
|
||||||
|
|
||||||
|
void dmaInit(dmaIdentifier_e identifier, resourceOwner_e owner, uint8_t resourceIndex)
|
||||||
|
{
|
||||||
|
enableDmaClock(dmaDescriptors[identifier].rcc);
|
||||||
|
dmaDescriptors[identifier].owner = owner;
|
||||||
|
dmaDescriptors[identifier].resourceIndex = resourceIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
void dmaSetHandler(dmaIdentifier_e identifier, dmaCallbackHandlerFuncPtr callback, uint32_t priority, uint32_t userParam)
|
||||||
|
{
|
||||||
|
enableDmaClock(dmaDescriptors[identifier].rcc);
|
||||||
dmaDescriptors[identifier].irqHandlerCallback = callback;
|
dmaDescriptors[identifier].irqHandlerCallback = callback;
|
||||||
dmaDescriptors[identifier].userParam = userParam;
|
dmaDescriptors[identifier].userParam = userParam;
|
||||||
|
|
||||||
|
|
||||||
HAL_NVIC_SetPriority(dmaDescriptors[identifier].irqN, NVIC_PRIORITY_BASE(priority), NVIC_PRIORITY_SUB(priority));
|
HAL_NVIC_SetPriority(dmaDescriptors[identifier].irqN, NVIC_PRIORITY_BASE(priority), NVIC_PRIORITY_SUB(priority));
|
||||||
HAL_NVIC_EnableIRQ(dmaDescriptors[identifier].irqN);
|
HAL_NVIC_EnableIRQ(dmaDescriptors[identifier].irqN);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
resourceOwner_e dmaGetOwner(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].owner;
|
||||||
|
}
|
||||||
|
|
||||||
|
uint8_t dmaGetResourceIndex(dmaIdentifier_e identifier)
|
||||||
|
{
|
||||||
|
return dmaDescriptors[identifier].resourceIndex;
|
||||||
|
}
|
||||||
|
|
||||||
|
dmaIdentifier_e dmaGetIdentifier(const DMA_Stream_TypeDef* stream)
|
||||||
|
{
|
||||||
|
for (int i = 0; i < DMA_MAX_DESCRIPTORS; i++) {
|
||||||
|
if (dmaDescriptors[i].stream == stream) {
|
||||||
|
return i;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
return 0;
|
||||||
|
}
|
|
@ -49,6 +49,7 @@
|
||||||
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
|
#define JEDEC_ID_MACRONIX_MX25L6406E 0xC22017
|
||||||
#define JEDEC_ID_MICRON_N25Q128 0x20ba18
|
#define JEDEC_ID_MICRON_N25Q128 0x20ba18
|
||||||
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
|
#define JEDEC_ID_WINBOND_W25Q128 0xEF4018
|
||||||
|
#define JEDEC_ID_MACRONIX_MX25L25635E 0xC22019
|
||||||
|
|
||||||
#define DISABLE_M25P16 IOHi(m25p16CsPin)
|
#define DISABLE_M25P16 IOHi(m25p16CsPin)
|
||||||
#define ENABLE_M25P16 IOLo(m25p16CsPin)
|
#define ENABLE_M25P16 IOLo(m25p16CsPin)
|
||||||
|
@ -179,6 +180,10 @@ static bool m25p16_readIdentification()
|
||||||
geometry.sectors = 256;
|
geometry.sectors = 256;
|
||||||
geometry.pagesPerSector = 256;
|
geometry.pagesPerSector = 256;
|
||||||
break;
|
break;
|
||||||
|
case JEDEC_ID_MACRONIX_MX25L25635E:
|
||||||
|
geometry.sectors = 512;
|
||||||
|
geometry.pagesPerSector = 256;
|
||||||
|
break;
|
||||||
default:
|
default:
|
||||||
// Unsupported chip or not an SPI NOR flash
|
// Unsupported chip or not an SPI NOR flash
|
||||||
geometry.sectors = 0;
|
geometry.sectors = 0;
|
||||||
|
@ -224,7 +229,7 @@ bool m25p16_init(ioTag_t csTag)
|
||||||
return false;
|
return false;
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
IOInit(m25p16CsPin, OWNER_FLASH, RESOURCE_SPI_CS, 0);
|
IOInit(m25p16CsPin, OWNER_FLASH_CS, 0);
|
||||||
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(m25p16CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
DISABLE_M25P16;
|
DISABLE_M25P16;
|
||||||
|
|
|
@ -36,7 +36,7 @@ static IO_t pin = IO_NONE;
|
||||||
void initInverter(void)
|
void initInverter(void)
|
||||||
{
|
{
|
||||||
pin = IOGetByTag(IO_TAG(INVERTER));
|
pin = IOGetByTag(IO_TAG(INVERTER));
|
||||||
IOInit(pin, OWNER_INVERTER, RESOURCE_OUTPUT, 1);
|
IOInit(pin, OWNER_INVERTER, 1);
|
||||||
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
IOConfigGPIO(pin, IOCFG_OUT_PP);
|
||||||
|
|
||||||
inverterSet(false);
|
inverterSet(false);
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
|
@ -62,18 +79,6 @@ const struct ioPortDef_s ioPortDefs[] = {
|
||||||
};
|
};
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
|
||||||
"FREE", "PWM", "PPM", "MOTOR", "SERVO", "SOFTSERIAL", "ADC", "SERIAL", "DEBUG", "TIMER",
|
|
||||||
"SONAR_TRIGGER", "SONAR_ECHO", "SYSTEM", "SPI", "I2C", "SDCARD", "FLASH", "USB", "BEEPER", "OSD",
|
|
||||||
"BARO", "MPU", "INVERTER", "LED_STRIP", "LED", "RX", "TX", "SOFT_SPI", "RX_SPI"
|
|
||||||
};
|
|
||||||
|
|
||||||
const char * const resourceNames[RESOURCE_TOTAL_COUNT] = {
|
|
||||||
"", // NONE
|
|
||||||
"IN", "OUT", "IN / OUT", "TIMER","UART TX","UART RX","UART TX/RX","EXTI","SCL",
|
|
||||||
"SDA", "SCK","MOSI","MISO","CS","BATTERY","RSSI","EXT","CURRENT"
|
|
||||||
};
|
|
||||||
|
|
||||||
ioRec_t* IO_Rec(IO_t io)
|
ioRec_t* IO_Rec(IO_t io)
|
||||||
{
|
{
|
||||||
return io;
|
return io;
|
||||||
|
@ -231,11 +236,10 @@ void IOToggle(IO_t io)
|
||||||
}
|
}
|
||||||
|
|
||||||
// claim IO pin, set owner and resources
|
// claim IO pin, set owner and resources
|
||||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index)
|
void IOInit(IO_t io, resourceOwner_e owner, uint8_t index)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
ioRec->owner = owner;
|
ioRec->owner = owner;
|
||||||
ioRec->resource = resource;
|
|
||||||
ioRec->index = index;
|
ioRec->index = index;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -245,18 +249,12 @@ void IORelease(IO_t io)
|
||||||
ioRec->owner = OWNER_FREE;
|
ioRec->owner = OWNER_FREE;
|
||||||
}
|
}
|
||||||
|
|
||||||
resourceOwner_t IOGetOwner(IO_t io)
|
resourceOwner_e IOGetOwner(IO_t io)
|
||||||
{
|
{
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
ioRec_t *ioRec = IO_Rec(io);
|
||||||
return ioRec->owner;
|
return ioRec->owner;
|
||||||
}
|
}
|
||||||
|
|
||||||
resourceType_t IOGetResource(IO_t io)
|
|
||||||
{
|
|
||||||
ioRec_t *ioRec = IO_Rec(io);
|
|
||||||
return ioRec->resource;
|
|
||||||
}
|
|
||||||
|
|
||||||
#if defined(STM32F1)
|
#if defined(STM32F1)
|
||||||
|
|
||||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
void IOConfigGPIO(IO_t io, ioConfig_t cfg)
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
@ -84,10 +101,9 @@ void IOHi(IO_t io);
|
||||||
void IOLo(IO_t io);
|
void IOLo(IO_t io);
|
||||||
void IOToggle(IO_t io);
|
void IOToggle(IO_t io);
|
||||||
|
|
||||||
void IOInit(IO_t io, resourceOwner_t owner, resourceType_t resource, uint8_t index);
|
void IOInit(IO_t io, resourceOwner_e owner, uint8_t index);
|
||||||
void IORelease(IO_t io); // unimplemented
|
void IORelease(IO_t io); // unimplemented
|
||||||
resourceOwner_t IOGetOwner(IO_t io);
|
resourceOwner_e IOGetOwner(IO_t io);
|
||||||
resourceType_t IOGetResources(IO_t io);
|
|
||||||
IO_t IOGetByTag(ioTag_t tag);
|
IO_t IOGetByTag(ioTag_t tag);
|
||||||
|
|
||||||
void IOConfigGPIO(IO_t io, ioConfig_t cfg);
|
void IOConfigGPIO(IO_t io, ioConfig_t cfg);
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include "common/utils.h"
|
#include "common/utils.h"
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
// this file is automatically generated by def_generated.pl script
|
// this file is automatically generated by def_generated.pl script
|
||||||
// do not modify this file directly, your changes will be lost
|
// do not modify this file directly, your changes will be lost
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
// TODO - GPIO_TypeDef include
|
// TODO - GPIO_TypeDef include
|
||||||
|
@ -11,8 +28,7 @@ typedef struct ioDef_s {
|
||||||
typedef struct ioRec_s {
|
typedef struct ioRec_s {
|
||||||
GPIO_TypeDef *gpio;
|
GPIO_TypeDef *gpio;
|
||||||
uint16_t pin;
|
uint16_t pin;
|
||||||
resourceOwner_t owner;
|
resourceOwner_e owner;
|
||||||
resourceType_t resource;
|
|
||||||
uint8_t index;
|
uint8_t index;
|
||||||
} ioRec_t;
|
} ioRec_t;
|
||||||
|
|
||||||
|
|
|
@ -1,3 +1,20 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
@ -8,7 +25,7 @@ typedef uint8_t ioTag_t; // packet tag to specify IO pin
|
||||||
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
|
typedef void* IO_t; // type specifying IO pin. Currently ioRec_t pointer, but this may change
|
||||||
|
|
||||||
// NONE initializer for ioTag_t variables
|
// NONE initializer for ioTag_t variables
|
||||||
#define IO_TAG_NONE ((ioTag_t)0)
|
#define IO_TAG_NONE IO_TAG(NONE)
|
||||||
|
|
||||||
// NONE initializer for IO_t variable
|
// NONE initializer for IO_t variable
|
||||||
#define IO_NONE ((IO_t)0)
|
#define IO_NONE ((IO_t)0)
|
||||||
|
|
|
@ -96,7 +96,7 @@ void ledInit(bool alternative_led)
|
||||||
|
|
||||||
for (int i = 0; i < LED_NUMBER; i++) {
|
for (int i = 0; i < LED_NUMBER; i++) {
|
||||||
if (leds[i + ledOffset]) {
|
if (leds[i + ledOffset]) {
|
||||||
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_OUTPUT, RESOURCE_INDEX(i));
|
IOInit(leds[i + ledOffset], OWNER_LED, RESOURCE_INDEX(i));
|
||||||
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
IOConfigGPIO(leds[i + ledOffset], IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -37,12 +37,13 @@
|
||||||
#include "common/color.h"
|
#include "common/color.h"
|
||||||
#include "common/colorconversion.h"
|
#include "common/colorconversion.h"
|
||||||
#include "dma.h"
|
#include "dma.h"
|
||||||
|
#include "io.h"
|
||||||
#include "light_ws2811strip.h"
|
#include "light_ws2811strip.h"
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F1) || defined(STM32F3)
|
||||||
uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
|
||||||
#else
|
|
||||||
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||||
|
#else
|
||||||
|
uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||||
#endif
|
#endif
|
||||||
volatile uint8_t ws2811LedDataTransferInProgress = 0;
|
volatile uint8_t ws2811LedDataTransferInProgress = 0;
|
||||||
|
|
||||||
|
@ -84,10 +85,13 @@ void setStripColors(const hsvColor_t *colors)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripInit(void)
|
void ws2811LedStripInit(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
memset(&ledStripDMABuffer, 0, WS2811_DMA_BUFFER_SIZE);
|
memset(&ledStripDMABuffer, 0, WS2811_DMA_BUFFER_SIZE);
|
||||||
ws2811LedStripHardwareInit();
|
ws2811LedStripHardwareInit(ioTag);
|
||||||
|
|
||||||
|
const hsvColor_t hsv_white = { 0, 255, 255};
|
||||||
|
setStripColor(&hsv_white);
|
||||||
ws2811UpdateStrip();
|
ws2811UpdateStrip();
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -17,28 +17,41 @@
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
|
#include "io_types.h"
|
||||||
|
|
||||||
#define WS2811_LED_STRIP_LENGTH 32
|
#define WS2811_LED_STRIP_LENGTH 32
|
||||||
#define WS2811_BITS_PER_LED 24
|
#define WS2811_BITS_PER_LED 24
|
||||||
#define WS2811_DELAY_BUFFER_LENGTH 42 // for 50us delay
|
// for 50us delay
|
||||||
|
#define WS2811_DELAY_BUFFER_LENGTH 42
|
||||||
|
|
||||||
#define WS2811_DATA_BUFFER_SIZE (WS2811_BITS_PER_LED * WS2811_LED_STRIP_LENGTH)
|
#define WS2811_DATA_BUFFER_SIZE (WS2811_BITS_PER_LED * WS2811_LED_STRIP_LENGTH)
|
||||||
|
// number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes)
|
||||||
#define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH) // number of bytes needed is #LEDs * 24 bytes + 42 trailing bytes)
|
#define WS2811_DMA_BUFFER_SIZE (WS2811_DATA_BUFFER_SIZE + WS2811_DELAY_BUFFER_LENGTH)
|
||||||
|
|
||||||
#if defined(STM32F40_41xxx)
|
#if defined(STM32F40_41xxx)
|
||||||
#define BIT_COMPARE_1 67 // timer compare value for logical 1
|
#define WS2811_TIMER_HZ 84000000
|
||||||
#define BIT_COMPARE_0 33 // timer compare value for logical 0
|
#define WS2811_TIMER_PERIOD 104
|
||||||
|
// timer compare value for logical 1
|
||||||
|
#define BIT_COMPARE_1 67
|
||||||
|
// timer compare value for logical 0
|
||||||
|
#define BIT_COMPARE_0 33
|
||||||
#elif defined(STM32F7)
|
#elif defined(STM32F7)
|
||||||
#define BIT_COMPARE_1 76 // timer compare value for logical 1
|
// timer compare value for logical 1
|
||||||
#define BIT_COMPARE_0 38 // timer compare value for logical 0
|
#define BIT_COMPARE_1 76
|
||||||
|
// timer compare value for logical 0
|
||||||
|
#define BIT_COMPARE_0 38
|
||||||
#else
|
#else
|
||||||
#define BIT_COMPARE_1 17 // timer compare value for logical 1
|
#define WS2811_TIMER_HZ 24000000
|
||||||
#define BIT_COMPARE_0 9 // timer compare value for logical 0
|
#define WS2811_TIMER_PERIOD 29
|
||||||
|
// timer compare value for logical 1
|
||||||
|
#define BIT_COMPARE_1 17
|
||||||
|
// timer compare value for logical 0
|
||||||
|
#define BIT_COMPARE_0 9
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
void ws2811LedStripInit(void);
|
void ws2811LedStripInit(ioTag_t ioTag);
|
||||||
|
|
||||||
void ws2811LedStripHardwareInit(void);
|
void ws2811LedStripHardwareInit(ioTag_t ioTag);
|
||||||
void ws2811LedStripDMAEnable(void);
|
void ws2811LedStripDMAEnable(void);
|
||||||
|
|
||||||
void ws2811UpdateStrip(void);
|
void ws2811UpdateStrip(void);
|
||||||
|
@ -54,9 +67,9 @@ void setStripColors(const hsvColor_t *colors);
|
||||||
|
|
||||||
bool isWS2811LedStripReady(void);
|
bool isWS2811LedStripReady(void);
|
||||||
|
|
||||||
#if defined(STM32F4) || defined(STM32F7)
|
#if defined(STM32F1) || defined(STM32F3)
|
||||||
extern uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
|
||||||
#else
|
|
||||||
extern uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
extern uint8_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||||
|
#else
|
||||||
|
extern uint32_t ledStripDMABuffer[WS2811_DMA_BUFFER_SIZE];
|
||||||
#endif
|
#endif
|
||||||
extern volatile uint8_t ws2811LedDataTransferInProgress;
|
extern volatile uint8_t ws2811LedDataTransferInProgress;
|
||||||
|
|
|
@ -31,26 +31,15 @@
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
#if !defined(WS2811_PIN)
|
|
||||||
#define WS2811_PIN PA0
|
|
||||||
#define WS2811_TIMER TIM5
|
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
|
|
||||||
#define WS2811_DMA_STREAM DMA1_Stream2
|
|
||||||
#define WS2811_DMA_IT DMA_IT_TCIF2
|
|
||||||
#define WS2811_DMA_CHANNEL DMA_Channel_6
|
|
||||||
#define WS2811_TIMER_CHANNEL TIM_Channel_1
|
|
||||||
#define WS2811_TIMER_GPIO_AF GPIO_AF2_TIM5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static IO_t ws2811IO = IO_NONE;
|
static IO_t ws2811IO = IO_NONE;
|
||||||
static uint16_t timDMASource = 0;
|
|
||||||
bool ws2811Initialised = false;
|
bool ws2811Initialised = false;
|
||||||
|
|
||||||
static TIM_HandleTypeDef TimHandle;
|
static TIM_HandleTypeDef TimHandle;
|
||||||
|
static uint16_t timerChannel = 0;
|
||||||
|
|
||||||
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
|
void HAL_TIM_PWM_PulseFinishedCallback(TIM_HandleTypeDef *htim)
|
||||||
{
|
{
|
||||||
if(htim->Instance==WS2811_TIMER)
|
if(htim->Instance == TimHandle.Instance)
|
||||||
{
|
{
|
||||||
//HAL_TIM_PWM_Stop_DMA(&TimHandle,WS2811_TIMER_CHANNEL);
|
//HAL_TIM_PWM_Stop_DMA(&TimHandle,WS2811_TIMER_CHANNEL);
|
||||||
ws2811LedDataTransferInProgress = 0;
|
ws2811LedDataTransferInProgress = 0;
|
||||||
|
@ -62,9 +51,20 @@ void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t* descriptor)
|
||||||
HAL_DMA_IRQHandler(TimHandle.hdma[descriptor->userParam]);
|
HAL_DMA_IRQHandler(TimHandle.hdma[descriptor->userParam]);
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripHardwareInit(void)
|
void ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
TimHandle.Instance = WS2811_TIMER;
|
if (!ioTag) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
||||||
|
TIM_TypeDef *timer = timerHardware->tim;
|
||||||
|
timerChannel = timerHardware->channel;
|
||||||
|
|
||||||
|
if (timerHardware->dmaStream == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
TimHandle.Instance = timer;
|
||||||
|
|
||||||
TimHandle.Init.Prescaler = 1;
|
TimHandle.Init.Prescaler = 1;
|
||||||
TimHandle.Init.Period = 135; // 800kHz
|
TimHandle.Init.Period = 135; // 800kHz
|
||||||
|
@ -78,16 +78,14 @@ void ws2811LedStripHardwareInit(void)
|
||||||
|
|
||||||
static DMA_HandleTypeDef hdma_tim;
|
static DMA_HandleTypeDef hdma_tim;
|
||||||
|
|
||||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
ws2811IO = IOGetByTag(ioTag);
|
||||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
|
||||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
|
||||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), WS2811_TIMER_GPIO_AF);
|
|
||||||
|
|
||||||
__DMA1_CLK_ENABLE();
|
__DMA1_CLK_ENABLE();
|
||||||
|
|
||||||
|
|
||||||
/* Set the parameters to be configured */
|
/* Set the parameters to be configured */
|
||||||
hdma_tim.Init.Channel = WS2811_DMA_CHANNEL;
|
hdma_tim.Init.Channel = timerHardware->dmaChannel;
|
||||||
hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
hdma_tim.Init.Direction = DMA_MEMORY_TO_PERIPH;
|
||||||
hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
|
hdma_tim.Init.PeriphInc = DMA_PINC_DISABLE;
|
||||||
hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
|
hdma_tim.Init.MemInc = DMA_MINC_ENABLE;
|
||||||
|
@ -101,30 +99,18 @@ void ws2811LedStripHardwareInit(void)
|
||||||
hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
hdma_tim.Init.PeriphBurst = DMA_PBURST_SINGLE;
|
||||||
|
|
||||||
/* Set hdma_tim instance */
|
/* Set hdma_tim instance */
|
||||||
hdma_tim.Instance = WS2811_DMA_STREAM;
|
hdma_tim.Instance = timerHardware->dmaStream;
|
||||||
|
|
||||||
switch (WS2811_TIMER_CHANNEL) {
|
uint16_t dmaSource = timerDmaSource(timerChannel);
|
||||||
case TIM_CHANNEL_1:
|
|
||||||
timDMASource = TIM_DMA_ID_CC1;
|
|
||||||
break;
|
|
||||||
case TIM_CHANNEL_2:
|
|
||||||
timDMASource = TIM_DMA_ID_CC2;
|
|
||||||
break;
|
|
||||||
case TIM_CHANNEL_3:
|
|
||||||
timDMASource = TIM_DMA_ID_CC3;
|
|
||||||
break;
|
|
||||||
case TIM_CHANNEL_4:
|
|
||||||
timDMASource = TIM_DMA_ID_CC4;
|
|
||||||
break;
|
|
||||||
}
|
|
||||||
|
|
||||||
/* Link hdma_tim to hdma[x] (channelx) */
|
/* Link hdma_tim to hdma[x] (channelx) */
|
||||||
__HAL_LINKDMA(&TimHandle, hdma[timDMASource], hdma_tim);
|
__HAL_LINKDMA(&TimHandle, hdma[dmaSource], hdma_tim);
|
||||||
|
|
||||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, timDMASource);
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, dmaSource);
|
||||||
|
|
||||||
/* Initialize TIMx DMA handle */
|
/* Initialize TIMx DMA handle */
|
||||||
if(HAL_DMA_Init(TimHandle.hdma[timDMASource]) != HAL_OK)
|
if(HAL_DMA_Init(TimHandle.hdma[dmaSource]) != HAL_OK)
|
||||||
{
|
{
|
||||||
/* Initialization Error */
|
/* Initialization Error */
|
||||||
return;
|
return;
|
||||||
|
@ -140,15 +126,13 @@ void ws2811LedStripHardwareInit(void)
|
||||||
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
|
TIM_OCInitStructure.OCNIdleState = TIM_OCNIDLESTATE_RESET;
|
||||||
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
|
TIM_OCInitStructure.OCFastMode = TIM_OCFAST_DISABLE;
|
||||||
|
|
||||||
if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, WS2811_TIMER_CHANNEL) != HAL_OK)
|
if(HAL_TIM_PWM_ConfigChannel(&TimHandle, &TIM_OCInitStructure, timerChannel) != HAL_OK)
|
||||||
{
|
{
|
||||||
/* Configuration Error */
|
/* Configuration Error */
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
|
||||||
ws2811Initialised = true;
|
ws2811Initialised = true;
|
||||||
setStripColor(&hsv_white);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
|
@ -160,7 +144,7 @@ void ws2811LedStripDMAEnable(void)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
if( HAL_TIM_PWM_Start_DMA(&TimHandle, WS2811_TIMER_CHANNEL, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK)
|
if (HAL_TIM_PWM_Start_DMA(&TimHandle, timerChannel, ledStripDMABuffer, WS2811_DMA_BUFFER_SIZE) != HAL_OK)
|
||||||
{
|
{
|
||||||
/* Starting PWM generation Error */
|
/* Starting PWM generation Error */
|
||||||
ws2811LedDataTransferInProgress = 0;
|
ws2811LedDataTransferInProgress = 0;
|
||||||
|
|
|
@ -32,8 +32,11 @@
|
||||||
|
|
||||||
static IO_t ws2811IO = IO_NONE;
|
static IO_t ws2811IO = IO_NONE;
|
||||||
bool ws2811Initialised = false;
|
bool ws2811Initialised = false;
|
||||||
|
static DMA_Channel_TypeDef *dmaChannel = NULL;
|
||||||
|
static TIM_TypeDef *timer = NULL;
|
||||||
|
|
||||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
|
{
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||||
ws2811LedDataTransferInProgress = 0;
|
ws2811LedDataTransferInProgress = 0;
|
||||||
DMA_Cmd(descriptor->channel, DISABLE);
|
DMA_Cmd(descriptor->channel, DISABLE);
|
||||||
|
@ -41,32 +44,38 @@ static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripHardwareInit(void)
|
void ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
|
if (!ioTag) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
uint16_t prescalerValue;
|
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
||||||
|
timer = timerHardware->tim;
|
||||||
|
|
||||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
if (timerHardware->dmaChannel == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
ws2811IO = IOGetByTag(ioTag);
|
||||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
|
||||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
|
||||||
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
|
IOConfigGPIO(ws2811IO, IO_CONFIG(GPIO_Speed_50MHz, GPIO_Mode_AF_PP));
|
||||||
|
|
||||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
|
|
||||||
/* Compute the prescaler value */
|
/* Compute the prescaler value */
|
||||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
uint16_t prescalerValue = (uint16_t) (SystemCoreClock / WS2811_TIMER_HZ) - 1;
|
||||||
/* Time base configuration */
|
/* Time base configuration */
|
||||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
TIM_TimeBaseStructure.TIM_Period = WS2811_TIMER_PERIOD; // 800kHz
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
TIM_TimeBaseInit(TIM3, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
/* PWM1 Mode configuration: Channel1 */
|
/* PWM1 Mode configuration: Channel1 */
|
||||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
|
@ -74,20 +83,20 @@ void ws2811LedStripHardwareInit(void)
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
||||||
TIM_OC1Init(TIM3, &TIM_OCInitStructure);
|
TIM_OC1Init(timer, &TIM_OCInitStructure);
|
||||||
TIM_OC1PreloadConfig(TIM3, TIM_OCPreload_Enable);
|
TIM_OC1PreloadConfig(timer, TIM_OCPreload_Enable);
|
||||||
|
|
||||||
TIM_CtrlPWMOutputs(TIM3, ENABLE);
|
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||||
|
|
||||||
/* configure DMA */
|
/* configure DMA */
|
||||||
/* DMA clock enable */
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
|
||||||
RCC_AHBPeriphClockCmd(RCC_AHBPeriph_DMA1, ENABLE);
|
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||||
|
|
||||||
/* DMA1 Channel6 Config */
|
dmaChannel = timerHardware->dmaChannel;
|
||||||
DMA_DeInit(DMA1_Channel6);
|
DMA_DeInit(dmaChannel);
|
||||||
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&TIM3->CCR1;
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||||
|
@ -99,17 +108,14 @@ void ws2811LedStripHardwareInit(void)
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
|
||||||
DMA_Init(DMA1_Channel6, &DMA_InitStructure);
|
DMA_Init(dmaChannel, &DMA_InitStructure);
|
||||||
|
|
||||||
/* TIM3 CC1 DMA Request enable */
|
/* TIM3 CC1 DMA Request enable */
|
||||||
TIM_DMACmd(TIM3, TIM_DMA_CC1, ENABLE);
|
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
||||||
|
|
||||||
DMA_ITConfig(DMA1_Channel6, DMA_IT_TC, ENABLE);
|
DMA_ITConfig(dmaChannel, DMA_IT_TC, ENABLE);
|
||||||
|
|
||||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
|
||||||
ws2811Initialised = true;
|
ws2811Initialised = true;
|
||||||
setStripColor(&hsv_white);
|
|
||||||
ws2811UpdateStrip();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripDMAEnable(void)
|
void ws2811LedStripDMAEnable(void)
|
||||||
|
@ -117,10 +123,10 @@ void ws2811LedStripDMAEnable(void)
|
||||||
if (!ws2811Initialised)
|
if (!ws2811Initialised)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
DMA_SetCurrDataCounter(DMA1_Channel6, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
DMA_SetCurrDataCounter(dmaChannel, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||||
TIM_SetCounter(TIM3, 0);
|
TIM_SetCounter(timer, 0);
|
||||||
TIM_Cmd(TIM3, ENABLE);
|
TIM_Cmd(timer, ENABLE);
|
||||||
DMA_Cmd(DMA1_Channel6, ENABLE);
|
DMA_Cmd(dmaChannel, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -31,18 +31,13 @@
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
|
|
||||||
#ifndef WS2811_PIN
|
|
||||||
#define WS2811_PIN PB8 // TIM16_CH1
|
|
||||||
#define WS2811_TIMER TIM16
|
|
||||||
#define WS2811_DMA_CHANNEL DMA1_Channel3
|
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH3_HANDLER
|
|
||||||
#define WS2811_TIMER_GPIO_AF GPIO_AF_1
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static IO_t ws2811IO = IO_NONE;
|
static IO_t ws2811IO = IO_NONE;
|
||||||
bool ws2811Initialised = false;
|
bool ws2811Initialised = false;
|
||||||
|
static DMA_Channel_TypeDef *dmaChannel = NULL;
|
||||||
|
static TIM_TypeDef *timer = NULL;
|
||||||
|
|
||||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
|
{
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||||
ws2811LedDataTransferInProgress = 0;
|
ws2811LedDataTransferInProgress = 0;
|
||||||
DMA_Cmd(descriptor->channel, DISABLE);
|
DMA_Cmd(descriptor->channel, DISABLE);
|
||||||
|
@ -50,72 +45,84 @@ static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor) {
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripHardwareInit(void)
|
void ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
|
if (!ioTag) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
uint16_t prescalerValue;
|
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
||||||
|
timer = timerHardware->tim;
|
||||||
|
|
||||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
if (timerHardware->dmaChannel == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
ws2811IO = IOGetByTag(ioTag);
|
||||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
|
||||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
||||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), WS2811_TIMER_GPIO_AF);
|
|
||||||
|
|
||||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||||
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
|
|
||||||
/* Compute the prescaler value */
|
/* Compute the prescaler value */
|
||||||
prescalerValue = (uint16_t) (SystemCoreClock / 24000000) - 1;
|
uint16_t prescalerValue = (uint16_t) (SystemCoreClock / WS2811_TIMER_HZ) - 1;
|
||||||
|
|
||||||
/* Time base configuration */
|
/* Time base configuration */
|
||||||
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
TIM_TimeBaseStructure.TIM_Period = 29; // 800kHz
|
TIM_TimeBaseStructure.TIM_Period = WS2811_TIMER_PERIOD; // 800kHz
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
TIM_TimeBaseStructure.TIM_ClockDivision = 0;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
/* PWM1 Mode configuration */
|
/* PWM1 Mode configuration */
|
||||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||||
|
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||||
|
} else {
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
|
}
|
||||||
|
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCPolarity_High;
|
TIM_OC1Init(timer, &TIM_OCInitStructure);
|
||||||
TIM_OC1Init(WS2811_TIMER, &TIM_OCInitStructure);
|
TIM_OC1PreloadConfig(timer, TIM_OCPreload_Enable);
|
||||||
TIM_OC1PreloadConfig(WS2811_TIMER, TIM_OCPreload_Enable);
|
|
||||||
|
|
||||||
|
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||||
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
|
|
||||||
|
|
||||||
/* configure DMA */
|
/* configure DMA */
|
||||||
/* DMA1 Channel Config */
|
/* DMA1 Channel Config */
|
||||||
DMA_DeInit(WS2811_DMA_CHANNEL);
|
dmaChannel = timerHardware->dmaChannel;
|
||||||
|
DMA_DeInit(dmaChannel);
|
||||||
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)&WS2811_TIMER->CCR1;
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||||
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
DMA_InitStructure.DMA_MemoryBaseAddr = (uint32_t)ledStripDMABuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_PeripheralDST;
|
||||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||||
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
DMA_InitStructure.DMA_PeripheralInc = DMA_PeripheralInc_Disable;
|
||||||
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
DMA_InitStructure.DMA_MemoryInc = DMA_MemoryInc_Enable;
|
||||||
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_HalfWord;
|
DMA_InitStructure.DMA_PeripheralDataSize = DMA_PeripheralDataSize_Word;
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Byte;
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
DMA_InitStructure.DMA_Priority = DMA_Priority_High;
|
||||||
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
DMA_InitStructure.DMA_M2M = DMA_M2M_Disable;
|
||||||
|
|
||||||
DMA_Init(WS2811_DMA_CHANNEL, &DMA_InitStructure);
|
DMA_Init(dmaChannel, &DMA_InitStructure);
|
||||||
|
|
||||||
TIM_DMACmd(WS2811_TIMER, TIM_DMA_CC1, ENABLE);
|
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
||||||
|
|
||||||
DMA_ITConfig(WS2811_DMA_CHANNEL, DMA_IT_TC, ENABLE);
|
DMA_ITConfig(dmaChannel, DMA_IT_TC, ENABLE);
|
||||||
|
|
||||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
|
||||||
ws2811Initialised = true;
|
ws2811Initialised = true;
|
||||||
setStripColor(&hsv_white);
|
|
||||||
ws2811UpdateStrip();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripDMAEnable(void)
|
void ws2811LedStripDMAEnable(void)
|
||||||
|
@ -123,10 +130,10 @@ void ws2811LedStripDMAEnable(void)
|
||||||
if (!ws2811Initialised)
|
if (!ws2811Initialised)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
DMA_SetCurrDataCounter(WS2811_DMA_CHANNEL, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
DMA_SetCurrDataCounter(dmaChannel, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||||
TIM_SetCounter(WS2811_TIMER, 0);
|
TIM_SetCounter(timer, 0);
|
||||||
TIM_Cmd(WS2811_TIMER, ENABLE);
|
TIM_Cmd(timer, ENABLE);
|
||||||
DMA_Cmd(WS2811_DMA_CHANNEL, ENABLE);
|
DMA_Cmd(dmaChannel, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -31,85 +31,92 @@
|
||||||
#include "rcc.h"
|
#include "rcc.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
#include "timer_stm32f4xx.h"
|
#include "timer_stm32f4xx.h"
|
||||||
|
#include "io.h"
|
||||||
#if !defined(WS2811_PIN)
|
|
||||||
#define WS2811_PIN PA0
|
|
||||||
#define WS2811_TIMER TIM5
|
|
||||||
#define WS2811_DMA_HANDLER_IDENTIFER DMA1_ST2_HANDLER
|
|
||||||
#define WS2811_DMA_STREAM DMA1_Stream2
|
|
||||||
#define WS2811_DMA_CHANNEL DMA_Channel_6
|
|
||||||
#define WS2811_TIMER_CHANNEL TIM_Channel_1
|
|
||||||
#define WS2811_TIMER_GPIO_AF GPIO_AF_TIM5
|
|
||||||
#endif
|
|
||||||
|
|
||||||
static IO_t ws2811IO = IO_NONE;
|
static IO_t ws2811IO = IO_NONE;
|
||||||
static uint16_t timDMASource = 0;
|
|
||||||
bool ws2811Initialised = false;
|
bool ws2811Initialised = false;
|
||||||
|
static DMA_Stream_TypeDef *stream = NULL;
|
||||||
|
static TIM_TypeDef *timer = NULL;
|
||||||
|
|
||||||
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
static void WS2811_DMA_IRQHandler(dmaChannelDescriptor_t *descriptor)
|
||||||
{
|
{
|
||||||
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
if (DMA_GET_FLAG_STATUS(descriptor, DMA_IT_TCIF)) {
|
||||||
ws2811LedDataTransferInProgress = 0;
|
ws2811LedDataTransferInProgress = 0;
|
||||||
DMA_Cmd(descriptor->stream, DISABLE);
|
DMA_Cmd(descriptor->stream, DISABLE);
|
||||||
TIM_DMACmd(WS2811_TIMER, timDMASource, DISABLE);
|
|
||||||
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
DMA_CLEAR_FLAG(descriptor, DMA_IT_TCIF);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripHardwareInit(void)
|
void ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||||
{
|
{
|
||||||
|
if (!ioTag) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
DMA_InitTypeDef DMA_InitStructure;
|
DMA_InitTypeDef DMA_InitStructure;
|
||||||
|
|
||||||
uint16_t prescalerValue;
|
const timerHardware_t *timerHardware = timerGetByTag(ioTag, TIM_USE_ANY);
|
||||||
|
timer = timerHardware->tim;
|
||||||
|
|
||||||
RCC_ClockCmd(timerRCC(WS2811_TIMER), ENABLE);
|
if (timerHardware->dmaStream == NULL) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
ws2811IO = IOGetByTag(IO_TAG(WS2811_PIN));
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
|
|
||||||
|
ws2811IO = IOGetByTag(ioTag);
|
||||||
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
/* GPIOA Configuration: TIM5 Channel 1 as alternate function push-pull */
|
||||||
IOInit(ws2811IO, OWNER_LED_STRIP, RESOURCE_OUTPUT, 0);
|
IOInit(ws2811IO, OWNER_LED_STRIP, 0);
|
||||||
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), WS2811_TIMER_GPIO_AF);
|
IOConfigGPIOAF(ws2811IO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
||||||
|
|
||||||
// Stop timer
|
// Stop timer
|
||||||
TIM_Cmd(WS2811_TIMER, DISABLE);
|
TIM_Cmd(timer, DISABLE);
|
||||||
|
|
||||||
/* Compute the prescaler value */
|
/* Compute the prescaler value */
|
||||||
prescalerValue = (uint16_t)(SystemCoreClock / 2 / 84000000) - 1;
|
uint16_t prescalerValue = (uint16_t)(SystemCoreClock / timerClockDivisor(timer) / WS2811_TIMER_HZ) - 1;
|
||||||
|
|
||||||
/* Time base configuration */
|
/* Time base configuration */
|
||||||
TIM_TimeBaseStructure.TIM_Period = 104; // 800kHz
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
TIM_TimeBaseStructure.TIM_Period = WS2811_TIMER_PERIOD; // 800kHz
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
TIM_TimeBaseStructure.TIM_Prescaler = prescalerValue;
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
TIM_TimeBaseInit(WS2811_TIMER, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
|
|
||||||
/* PWM1 Mode configuration: Channel1 */
|
/* PWM1 Mode configuration: Channel1 */
|
||||||
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Reset;
|
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Set;
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = TIM_OCNPolarity_High;
|
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||||
TIM_OCInitStructure.TIM_OCNPolarity = TIM_OCNPolarity_High;
|
} else {
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
|
}
|
||||||
|
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||||
|
|
||||||
timerOCInit(WS2811_TIMER, WS2811_TIMER_CHANNEL, &TIM_OCInitStructure);
|
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
|
||||||
timerOCPreloadConfig(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_OCPreload_Enable);
|
timerOCPreloadConfig(timer, timerHardware->channel, TIM_OCPreload_Enable);
|
||||||
timDMASource = timerDmaSource(WS2811_TIMER_CHANNEL);
|
|
||||||
|
|
||||||
TIM_CtrlPWMOutputs(WS2811_TIMER, ENABLE);
|
TIM_CtrlPWMOutputs(timer, ENABLE);
|
||||||
TIM_ARRPreloadConfig(WS2811_TIMER, ENABLE);
|
TIM_ARRPreloadConfig(timer, ENABLE);
|
||||||
|
|
||||||
TIM_CCxCmd(WS2811_TIMER, WS2811_TIMER_CHANNEL, TIM_CCx_Enable);
|
TIM_CCxCmd(timer, timerHardware->channel, TIM_CCx_Enable);
|
||||||
TIM_Cmd(WS2811_TIMER, ENABLE);
|
TIM_Cmd(timer, ENABLE);
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_LED_STRIP, 0);
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
||||||
|
|
||||||
|
stream = timerHardware->dmaStream;
|
||||||
/* configure DMA */
|
/* configure DMA */
|
||||||
DMA_Cmd(WS2811_DMA_STREAM, DISABLE);
|
DMA_Cmd(stream, DISABLE);
|
||||||
DMA_DeInit(WS2811_DMA_STREAM);
|
DMA_DeInit(stream);
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
DMA_InitStructure.DMA_Channel = WS2811_DMA_CHANNEL;
|
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(WS2811_TIMER, WS2811_TIMER_CHANNEL);
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerCCR(timer, timerHardware->channel);
|
||||||
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
|
DMA_InitStructure.DMA_Memory0BaseAddr = (uint32_t)ledStripDMABuffer;
|
||||||
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
DMA_InitStructure.DMA_DIR = DMA_DIR_MemoryToPeripheral;
|
||||||
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
DMA_InitStructure.DMA_BufferSize = WS2811_DMA_BUFFER_SIZE;
|
||||||
|
@ -119,22 +126,14 @@ void ws2811LedStripHardwareInit(void)
|
||||||
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
DMA_InitStructure.DMA_MemoryDataSize = DMA_MemoryDataSize_Word;
|
||||||
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
DMA_InitStructure.DMA_Mode = DMA_Mode_Normal;
|
||||||
DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
|
DMA_InitStructure.DMA_Priority = DMA_Priority_VeryHigh;
|
||||||
DMA_InitStructure.DMA_FIFOMode = DMA_FIFOMode_Enable;
|
|
||||||
DMA_InitStructure.DMA_FIFOThreshold = DMA_FIFOThreshold_1QuarterFull;
|
|
||||||
DMA_InitStructure.DMA_MemoryBurst = DMA_MemoryBurst_Single;
|
|
||||||
DMA_InitStructure.DMA_PeripheralBurst = DMA_PeripheralBurst_Single;
|
|
||||||
|
|
||||||
DMA_Init(WS2811_DMA_STREAM, &DMA_InitStructure);
|
DMA_Init(stream, &DMA_InitStructure);
|
||||||
|
TIM_DMACmd(timer, timerDmaSource(timerHardware->channel), ENABLE);
|
||||||
|
|
||||||
DMA_ITConfig(WS2811_DMA_STREAM, DMA_IT_TC, ENABLE);
|
DMA_ITConfig(stream, DMA_IT_TC, ENABLE);
|
||||||
DMA_ClearITPendingBit(WS2811_DMA_STREAM, dmaFlag_IT_TCIF(WS2811_DMA_STREAM));
|
DMA_ClearITPendingBit(stream, dmaFlag_IT_TCIF(stream));
|
||||||
|
|
||||||
dmaSetHandler(WS2811_DMA_HANDLER_IDENTIFER, WS2811_DMA_IRQHandler, NVIC_PRIO_WS2811_DMA, 0);
|
|
||||||
|
|
||||||
const hsvColor_t hsv_white = { 0, 255, 255};
|
|
||||||
ws2811Initialised = true;
|
ws2811Initialised = true;
|
||||||
setStripColor(&hsv_white);
|
|
||||||
ws2811UpdateStrip();
|
|
||||||
}
|
}
|
||||||
|
|
||||||
void ws2811LedStripDMAEnable(void)
|
void ws2811LedStripDMAEnable(void)
|
||||||
|
@ -142,10 +141,10 @@ void ws2811LedStripDMAEnable(void)
|
||||||
if (!ws2811Initialised)
|
if (!ws2811Initialised)
|
||||||
return;
|
return;
|
||||||
|
|
||||||
DMA_SetCurrDataCounter(WS2811_DMA_STREAM, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
DMA_SetCurrDataCounter(stream, WS2811_DMA_BUFFER_SIZE); // load number of bytes to be transferred
|
||||||
TIM_SetCounter(WS2811_TIMER, 0);
|
TIM_SetCounter(timer, 0);
|
||||||
DMA_Cmd(WS2811_DMA_STREAM, ENABLE);
|
TIM_Cmd(timer, ENABLE);
|
||||||
TIM_DMACmd(WS2811_TIMER, timDMASource, ENABLE);
|
DMA_Cmd(stream, ENABLE);
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -260,7 +260,7 @@ void max7456Init(uint8_t video_system)
|
||||||
#ifdef MAX7456_SPI_CS_PIN
|
#ifdef MAX7456_SPI_CS_PIN
|
||||||
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
|
max7456CsPin = IOGetByTag(IO_TAG(MAX7456_SPI_CS_PIN));
|
||||||
#endif
|
#endif
|
||||||
IOInit(max7456CsPin, OWNER_OSD, RESOURCE_SPI_CS, 0);
|
IOInit(max7456CsPin, OWNER_OSD_CS, 0);
|
||||||
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(max7456CsPin, SPI_IO_CS_CFG);
|
||||||
|
|
||||||
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_CLOCK_STANDARD);
|
||||||
|
@ -294,7 +294,7 @@ void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c)
|
||||||
screenBuffer[y*30+x] = c;
|
screenBuffer[y*30+x] = c;
|
||||||
}
|
}
|
||||||
|
|
||||||
void max7456Write(uint8_t x, uint8_t y, char *buff)
|
void max7456Write(uint8_t x, uint8_t y, const char *buff)
|
||||||
{
|
{
|
||||||
uint8_t i = 0;
|
uint8_t i = 0;
|
||||||
for (i = 0; *(buff+i); i++)
|
for (i = 0; *(buff+i); i++)
|
||||||
|
@ -387,7 +387,7 @@ void max7456RefreshAll(void)
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
void max7456WriteNvm(uint8_t char_address, uint8_t *font_data)
|
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data)
|
||||||
{
|
{
|
||||||
uint8_t x;
|
uint8_t x;
|
||||||
|
|
||||||
|
|
|
@ -146,9 +146,9 @@ extern uint16_t maxScreenSize;
|
||||||
|
|
||||||
void max7456Init(uint8_t system);
|
void max7456Init(uint8_t system);
|
||||||
void max7456DrawScreen(void);
|
void max7456DrawScreen(void);
|
||||||
void max7456WriteNvm(uint8_t char_address, uint8_t *font_data);
|
void max7456WriteNvm(uint8_t char_address, const uint8_t *font_data);
|
||||||
uint8_t max7456GetRowsCount(void);
|
uint8_t max7456GetRowsCount(void);
|
||||||
void max7456Write(uint8_t x, uint8_t y, char *buff);
|
void max7456Write(uint8_t x, uint8_t y, const char *buff);
|
||||||
void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c);
|
void max7456WriteChar(uint8_t x, uint8_t y, uint8_t c);
|
||||||
void max7456ClearScreen(void);
|
void max7456ClearScreen(void);
|
||||||
void max7456RefreshAll(void);
|
void max7456RefreshAll(void);
|
||||||
|
|
|
@ -35,24 +35,25 @@ static pwmCompleteWriteFuncPtr pwmCompleteWritePtr = NULL;
|
||||||
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static bool pwmMotorsEnabled = true;
|
bool pwmMotorsEnabled = true;
|
||||||
|
|
||||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
{
|
{
|
||||||
TIM_OCInitTypeDef TIM_OCInitStructure;
|
TIM_OCInitTypeDef TIM_OCInitStructure;
|
||||||
|
|
||||||
TIM_OCStructInit(&TIM_OCInitStructure);
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM2;
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||||
|
|
||||||
if (output & TIMER_OUTPUT_N_CHANNEL) {
|
if (output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Disable;
|
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
|
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||||
|
TIM_OCInitStructure.TIM_OCNPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low;
|
||||||
} else {
|
} else {
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Disable;
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
|
TIM_OCInitStructure.TIM_OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||||
}
|
}
|
||||||
TIM_OCInitStructure.TIM_Pulse = value;
|
TIM_OCInitStructure.TIM_Pulse = value;
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = (output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_High : TIM_OCPolarity_Low;
|
|
||||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
|
||||||
|
|
||||||
timerOCInit(tim, channel, &TIM_OCInitStructure);
|
timerOCInit(tim, channel, &TIM_OCInitStructure);
|
||||||
timerOCPreloadConfig(tim, channel, TIM_OCPreload_Enable);
|
timerOCPreloadConfig(tim, channel, TIM_OCPreload_Enable);
|
||||||
|
@ -119,6 +120,7 @@ void pwmShutdownPulsesForAllMotors(uint8_t motorCount)
|
||||||
|
|
||||||
void pwmDisableMotors(void)
|
void pwmDisableMotors(void)
|
||||||
{
|
{
|
||||||
|
pwmShutdownPulsesForAllMotors(MAX_SUPPORTED_MOTORS);
|
||||||
pwmMotorsEnabled = false;
|
pwmMotorsEnabled = false;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -208,13 +210,15 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_MOTOR);
|
const timerHardware_t *timerHardware = timerGetByTag(tag, TIM_USE_ANY);
|
||||||
|
|
||||||
if (timerHardware == NULL) {
|
if (timerHardware == NULL) {
|
||||||
/* flag failure and disable ability to arm */
|
/* flag failure and disable ability to arm */
|
||||||
break;
|
break;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
motors[motorIndex].io = IOGetByTag(tag);
|
||||||
|
|
||||||
#ifdef USE_DSHOT
|
#ifdef USE_DSHOT
|
||||||
if (isDigital) {
|
if (isDigital) {
|
||||||
pwmDigitalMotorHardwareConfig(timerHardware, motorIndex, motorConfig->motorPwmProtocol);
|
pwmDigitalMotorHardwareConfig(timerHardware, motorIndex, motorConfig->motorPwmProtocol);
|
||||||
|
@ -223,9 +227,8 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot
|
||||||
continue;
|
continue;
|
||||||
}
|
}
|
||||||
#endif
|
#endif
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
|
||||||
|
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_OUTPUT, RESOURCE_INDEX(motorIndex));
|
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
||||||
|
|
||||||
motors[motorIndex].pwmWritePtr = pwmWritePtr;
|
motors[motorIndex].pwmWritePtr = pwmWritePtr;
|
||||||
|
@ -268,10 +271,10 @@ void servoInit(const servoConfig_t *servoConfig)
|
||||||
|
|
||||||
servos[servoIndex].io = IOGetByTag(tag);
|
servos[servoIndex].io = IOGetByTag(tag);
|
||||||
|
|
||||||
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_OUTPUT, RESOURCE_INDEX(servoIndex));
|
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
|
||||||
IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
|
IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
|
||||||
|
|
||||||
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_SERVO);
|
const timerHardware_t *timer = timerGetByTag(tag, TIM_USE_ANY);
|
||||||
|
|
||||||
if (timer == NULL) {
|
if (timer == NULL) {
|
||||||
/* flag failure and disable ability to arm */
|
/* flag failure and disable ability to arm */
|
||||||
|
|
|
@ -75,6 +75,8 @@ typedef struct {
|
||||||
#endif
|
#endif
|
||||||
} motorDmaOutput_t;
|
} motorDmaOutput_t;
|
||||||
|
|
||||||
|
extern bool pwmMotorsEnabled;
|
||||||
|
|
||||||
struct timerHardware_s;
|
struct timerHardware_s;
|
||||||
typedef void(*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
|
typedef void(*pwmWriteFuncPtr)(uint8_t index, uint16_t value); // function pointer used to write motors
|
||||||
typedef void(*pwmCompleteWriteFuncPtr)(uint8_t motorCount); // function pointer used after motors are written
|
typedef void(*pwmCompleteWriteFuncPtr)(uint8_t motorCount); // function pointer used after motors are written
|
||||||
|
|
|
@ -35,7 +35,7 @@ static pwmCompleteWriteFuncPtr pwmCompleteWritePtr = NULL;
|
||||||
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
static pwmOutputPort_t servos[MAX_SUPPORTED_SERVOS];
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
static bool pwmMotorsEnabled = true;
|
bool pwmMotorsEnabled = true;
|
||||||
|
|
||||||
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
static void pwmOCConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t value, uint8_t output)
|
||||||
{
|
{
|
||||||
|
@ -238,7 +238,7 @@ void motorInit(const motorConfig_t *motorConfig, uint16_t idlePulse, uint8_t mot
|
||||||
#endif
|
#endif
|
||||||
motors[motorIndex].io = IOGetByTag(tag);
|
motors[motorIndex].io = IOGetByTag(tag);
|
||||||
|
|
||||||
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_OUTPUT, RESOURCE_INDEX(motorIndex));
|
IOInit(motors[motorIndex].io, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
//IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
//IOConfigGPIO(motors[motorIndex].io, IOCFG_AF_PP);
|
||||||
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
IOConfigGPIOAF(motors[motorIndex].io, IOCFG_AF_PP, timerHardware->alternateFunction);
|
||||||
|
|
||||||
|
@ -282,7 +282,7 @@ void servoInit(const servoConfig_t *servoConfig)
|
||||||
|
|
||||||
servos[servoIndex].io = IOGetByTag(tag);
|
servos[servoIndex].io = IOGetByTag(tag);
|
||||||
|
|
||||||
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_OUTPUT, RESOURCE_INDEX(servoIndex));
|
IOInit(servos[servoIndex].io, OWNER_SERVO, RESOURCE_INDEX(servoIndex));
|
||||||
//IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
|
//IOConfigGPIO(servos[servoIndex].io, IOCFG_AF_PP);
|
||||||
|
|
||||||
const timerHardware_t *timer = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
|
const timerHardware_t *timer = timerGetByTag(tag, TIMER_OUTPUT_ENABLED);
|
||||||
|
|
|
@ -20,6 +20,8 @@
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
#include "build/debug.h"
|
||||||
|
|
||||||
#include "io.h"
|
#include "io.h"
|
||||||
#include "timer.h"
|
#include "timer.h"
|
||||||
#include "pwm_output.h"
|
#include "pwm_output.h"
|
||||||
|
@ -57,6 +59,11 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
||||||
|
|
||||||
void pwmWriteDigital(uint8_t index, uint16_t value)
|
void pwmWriteDigital(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[index];
|
motorDmaOutput_t * const motor = &dmaMotors[index];
|
||||||
|
|
||||||
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
||||||
|
@ -84,6 +91,10 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
UNUSED(motorCount);
|
UNUSED(motorCount);
|
||||||
|
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||||
|
@ -114,11 +125,12 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
const uint8_t timerIndex = getTimerIndex(timer);
|
const uint8_t timerIndex = getTimerIndex(timer);
|
||||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
||||||
|
|
||||||
IOInit(motorIO, OWNER_MOTOR, RESOURCE_OUTPUT, 0);
|
IOInit(motorIO, OWNER_MOTOR, 0);
|
||||||
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
||||||
|
|
||||||
if (configureTimer) {
|
if (configureTimer) {
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
|
||||||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
TIM_Cmd(timer, DISABLE);
|
TIM_Cmd(timer, DISABLE);
|
||||||
|
@ -139,6 +151,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1);
|
TIM_TimeBaseStructure.TIM_Prescaler = (uint16_t)((SystemCoreClock / timerClockDivisor(timer) / hz) - 1);
|
||||||
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
|
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||||
|
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
}
|
}
|
||||||
|
@ -148,13 +161,12 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
TIM_OCInitStructure.TIM_OCNIdleState = TIM_OCNIdleState_Reset;
|
||||||
TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_High : TIM_OCNPolarity_Low;
|
TIM_OCInitStructure.TIM_OCNPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCNPolarity_Low : TIM_OCNPolarity_High;
|
||||||
} else {
|
} else {
|
||||||
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
TIM_OCInitStructure.TIM_OutputState = TIM_OutputState_Enable;
|
||||||
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
TIM_OCInitStructure.TIM_OCIdleState = TIM_OCIdleState_Set;
|
||||||
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
TIM_OCInitStructure.TIM_OCPolarity = (timerHardware->output & TIMER_OUTPUT_INVERTED) ? TIM_OCPolarity_Low : TIM_OCPolarity_High;
|
||||||
}
|
}
|
||||||
|
|
||||||
TIM_OCInitStructure.TIM_Pulse = 0;
|
TIM_OCInitStructure.TIM_Pulse = 0;
|
||||||
|
|
||||||
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
|
timerOCInit(timer, timerHardware->channel, &TIM_OCInitStructure);
|
||||||
|
@ -172,6 +184,12 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
|
|
||||||
DMA_Channel_TypeDef *channel = timerHardware->dmaChannel;
|
DMA_Channel_TypeDef *channel = timerHardware->dmaChannel;
|
||||||
|
|
||||||
|
if (channel == NULL) {
|
||||||
|
/* trying to use a non valid channel */
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
|
||||||
DMA_Cmd(channel, DISABLE);
|
DMA_Cmd(channel, DISABLE);
|
||||||
|
|
|
@ -58,6 +58,10 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
||||||
|
|
||||||
void pwmWriteDigital(uint8_t index, uint16_t value)
|
void pwmWriteDigital(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[index];
|
motorDmaOutput_t * const motor = &dmaMotors[index];
|
||||||
|
|
||||||
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
||||||
|
@ -85,6 +89,10 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
UNUSED(motorCount);
|
UNUSED(motorCount);
|
||||||
|
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
for (int i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||||
|
@ -115,11 +123,12 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
const uint8_t timerIndex = getTimerIndex(timer);
|
const uint8_t timerIndex = getTimerIndex(timer);
|
||||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
||||||
|
|
||||||
IOInit(motorIO, OWNER_MOTOR, RESOURCE_OUTPUT, 0);
|
IOInit(motorIO, OWNER_MOTOR, 0);
|
||||||
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, GPIO_PuPd_UP), timerHardware->alternateFunction);
|
||||||
|
|
||||||
if (configureTimer) {
|
if (configureTimer) {
|
||||||
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
TIM_TimeBaseInitTypeDef TIM_TimeBaseStructure;
|
||||||
|
TIM_TimeBaseStructInit(&TIM_TimeBaseStructure);
|
||||||
|
|
||||||
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
RCC_ClockCmd(timerRCC(timer), ENABLE);
|
||||||
TIM_Cmd(timer, DISABLE);
|
TIM_Cmd(timer, DISABLE);
|
||||||
|
@ -140,10 +149,12 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;
|
TIM_TimeBaseStructure.TIM_Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;
|
||||||
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
|
TIM_TimeBaseStructure.TIM_Period = MOTOR_BITLENGTH;
|
||||||
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
TIM_TimeBaseStructure.TIM_ClockDivision = TIM_CKD_DIV1;
|
||||||
|
TIM_TimeBaseStructure.TIM_RepetitionCounter = 0;
|
||||||
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
TIM_TimeBaseStructure.TIM_CounterMode = TIM_CounterMode_Up;
|
||||||
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
TIM_TimeBaseInit(timer, &TIM_TimeBaseStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
TIM_OCStructInit(&TIM_OCInitStructure);
|
||||||
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
TIM_OCInitStructure.TIM_OCMode = TIM_OCMode_PWM1;
|
||||||
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
if (timerHardware->output & TIMER_OUTPUT_N_CHANNEL) {
|
||||||
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
TIM_OCInitStructure.TIM_OutputNState = TIM_OutputNState_Enable;
|
||||||
|
@ -171,8 +182,17 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
|
|
||||||
DMA_Stream_TypeDef *stream = timerHardware->dmaStream;
|
DMA_Stream_TypeDef *stream = timerHardware->dmaStream;
|
||||||
|
|
||||||
|
if (stream == NULL) {
|
||||||
|
/* trying to use a non valid stream */
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
|
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
|
||||||
DMA_Cmd(stream, DISABLE);
|
DMA_Cmd(stream, DISABLE);
|
||||||
DMA_DeInit(stream);
|
DMA_DeInit(stream);
|
||||||
|
|
||||||
DMA_StructInit(&DMA_InitStructure);
|
DMA_StructInit(&DMA_InitStructure);
|
||||||
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
|
DMA_InitStructure.DMA_Channel = timerHardware->dmaChannel;
|
||||||
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
|
DMA_InitStructure.DMA_PeripheralBaseAddr = (uint32_t)timerChCCR(timerHardware);
|
||||||
|
@ -194,8 +214,6 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
|
|
||||||
DMA_ITConfig(stream, DMA_IT_TC, ENABLE);
|
DMA_ITConfig(stream, DMA_IT_TC, ENABLE);
|
||||||
DMA_ClearITPendingBit(stream, dmaFlag_IT_TCIF(timerHardware->dmaStream));
|
DMA_ClearITPendingBit(stream, dmaFlag_IT_TCIF(timerHardware->dmaStream));
|
||||||
|
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
|
||||||
}
|
}
|
||||||
|
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -57,6 +57,11 @@ uint8_t getTimerIndex(TIM_TypeDef *timer)
|
||||||
|
|
||||||
void pwmWriteDigital(uint8_t index, uint16_t value)
|
void pwmWriteDigital(uint8_t index, uint16_t value)
|
||||||
{
|
{
|
||||||
|
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
motorDmaOutput_t * const motor = &dmaMotors[index];
|
motorDmaOutput_t * const motor = &dmaMotors[index];
|
||||||
|
|
||||||
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
uint16_t packet = (value << 1) | 0; // Here goes telemetry bit (false for now)
|
||||||
|
@ -87,6 +92,10 @@ void pwmCompleteDigitalMotorUpdate(uint8_t motorCount)
|
||||||
{
|
{
|
||||||
UNUSED(motorCount);
|
UNUSED(motorCount);
|
||||||
|
|
||||||
|
if (!pwmMotorsEnabled) {
|
||||||
|
return;
|
||||||
|
}
|
||||||
|
|
||||||
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
|
for (uint8_t i = 0; i < dmaMotorTimerCount; i++) {
|
||||||
//TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
//TIM_SetCounter(dmaMotorTimers[i].timer, 0);
|
||||||
//TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
//TIM_DMACmd(dmaMotorTimers[i].timer, dmaMotorTimers[i].timerDmaSources, ENABLE);
|
||||||
|
@ -121,7 +130,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
const uint8_t timerIndex = getTimerIndex(timer);
|
const uint8_t timerIndex = getTimerIndex(timer);
|
||||||
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
const bool configureTimer = (timerIndex == dmaMotorTimerCount-1);
|
||||||
|
|
||||||
IOInit(motorIO, OWNER_MOTOR, RESOURCE_OUTPUT, 0);
|
IOInit(motorIO, OWNER_MOTOR, 0);
|
||||||
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
|
IOConfigGPIOAF(motorIO, IO_CONFIG(GPIO_MODE_AF_PP, GPIO_SPEED_FREQ_VERY_HIGH, GPIO_PULLUP), timerHardware->alternateFunction);
|
||||||
|
|
||||||
__DMA1_CLK_ENABLE();
|
__DMA1_CLK_ENABLE();
|
||||||
|
@ -145,6 +154,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
motor->TimHandle.Instance = timerHardware->tim;
|
motor->TimHandle.Instance = timerHardware->tim;
|
||||||
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;;
|
motor->TimHandle.Init.Prescaler = (SystemCoreClock / timerClockDivisor(timer) / hz) - 1;;
|
||||||
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
motor->TimHandle.Init.Period = MOTOR_BITLENGTH;
|
||||||
|
motor->TimHandle.Init.RepetitionCounter = 0;
|
||||||
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
motor->TimHandle.Init.ClockDivision = TIM_CLOCKDIVISION_DIV1;
|
||||||
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
motor->TimHandle.Init.CounterMode = TIM_COUNTERMODE_UP;
|
||||||
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
|
if(HAL_TIM_PWM_Init(&motor->TimHandle) != HAL_OK)
|
||||||
|
@ -201,6 +211,7 @@ void pwmDigitalMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t
|
||||||
/* Link hdma_tim to hdma[x] (channelx) */
|
/* Link hdma_tim to hdma[x] (channelx) */
|
||||||
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);
|
__HAL_LINKDMA(&motor->TimHandle, hdma[motor->timerDmaSource], motor->hdma_tim);
|
||||||
|
|
||||||
|
dmaInit(timerHardware->dmaIrqHandler, OWNER_MOTOR, RESOURCE_INDEX(motorIndex));
|
||||||
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
dmaSetHandler(timerHardware->dmaIrqHandler, motor_DMA_IRQHandler, NVIC_BUILD_PRIORITY(1, 2), motorIndex);
|
||||||
|
|
||||||
/* Initialize TIMx DMA handle */
|
/* Initialize TIMx DMA handle */
|
||||||
|
|
|
@ -407,7 +407,7 @@ void pwmRxInit(const pwmConfig_t *pwmConfig)
|
||||||
port->timerHardware = timer;
|
port->timerHardware = timer;
|
||||||
|
|
||||||
IO_t io = IOGetByTag(pwmConfig->ioTags[channel]);
|
IO_t io = IOGetByTag(pwmConfig->ioTags[channel]);
|
||||||
IOInit(io, OWNER_PWMINPUT, RESOURCE_INPUT, RESOURCE_INDEX(channel));
|
IOInit(io, OWNER_PWMINPUT, RESOURCE_INDEX(channel));
|
||||||
IOConfigGPIO(io, IOCFG_IPD);
|
IOConfigGPIO(io, IOCFG_IPD);
|
||||||
|
|
||||||
#if defined(USE_HAL_DRIVER)
|
#if defined(USE_HAL_DRIVER)
|
||||||
|
@ -471,7 +471,7 @@ void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol)
|
||||||
port->timerHardware = timer;
|
port->timerHardware = timer;
|
||||||
|
|
||||||
IO_t io = IOGetByTag(ppmConfig->ioTag);
|
IO_t io = IOGetByTag(ppmConfig->ioTag);
|
||||||
IOInit(io, OWNER_PPMINPUT, RESOURCE_INPUT, 0);
|
IOInit(io, OWNER_PPMINPUT, 0);
|
||||||
IOConfigGPIO(io, IOCFG_IPD);
|
IOConfigGPIO(io, IOCFG_IPD);
|
||||||
|
|
||||||
#if defined(USE_HAL_DRIVER)
|
#if defined(USE_HAL_DRIVER)
|
||||||
|
|
62
src/main/drivers/resource.c
Normal file
62
src/main/drivers/resource.c
Normal file
|
@ -0,0 +1,62 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation,either version 3 of the License,or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not,see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
|
#include "resource.h"
|
||||||
|
|
||||||
|
const char * const ownerNames[OWNER_TOTAL_COUNT] = {
|
||||||
|
"FREE",
|
||||||
|
"PWM",
|
||||||
|
"PPM",
|
||||||
|
"MOTOR",
|
||||||
|
"SERVO",
|
||||||
|
"LED",
|
||||||
|
"ADC",
|
||||||
|
"ADC_BATT",
|
||||||
|
"ADC_CURR",
|
||||||
|
"ADC_EXT",
|
||||||
|
"ADC_RSSI",
|
||||||
|
"SERIAL_TX",
|
||||||
|
"SERIAL_RX",
|
||||||
|
"DEBUG",
|
||||||
|
"TIMER",
|
||||||
|
"SONAR_TRIGGER",
|
||||||
|
"SONAR_ECHO",
|
||||||
|
"SYSTEM",
|
||||||
|
"SPI_SCK",
|
||||||
|
"SPI_MISO",
|
||||||
|
"SPI_MOSI",
|
||||||
|
"I2C_SDA",
|
||||||
|
"I2C_SCL",
|
||||||
|
"SDCARD_CS",
|
||||||
|
"FLASH_CS",
|
||||||
|
"BARO_CS",
|
||||||
|
"MPU_CS",
|
||||||
|
"OSD_CS",
|
||||||
|
"RX_SPI_CS",
|
||||||
|
"SPI_CS",
|
||||||
|
"MPU_EXTI",
|
||||||
|
"BARO_EXTI",
|
||||||
|
"USB",
|
||||||
|
"USB_DETECT",
|
||||||
|
"BEEPER",
|
||||||
|
"OSD",
|
||||||
|
"SDCARD_DETECT",
|
||||||
|
"RX_BIND",
|
||||||
|
"INVERTER",
|
||||||
|
"LED_STRIP",
|
||||||
|
};
|
||||||
|
|
|
@ -1,56 +1,67 @@
|
||||||
|
/*
|
||||||
|
* This file is part of Cleanflight.
|
||||||
|
*
|
||||||
|
* Cleanflight is free software: you can redistribute it and/or modify
|
||||||
|
* it under the terms of the GNU General Public License as published by
|
||||||
|
* the Free Software Foundation, either version 3 of the License, or
|
||||||
|
* (at your option) any later version.
|
||||||
|
*
|
||||||
|
* Cleanflight is distributed in the hope that it will be useful,
|
||||||
|
* but WITHOUT ANY WARRANTY; without even the implied warranty of
|
||||||
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
|
||||||
|
* GNU General Public License for more details.
|
||||||
|
*
|
||||||
|
* You should have received a copy of the GNU General Public License
|
||||||
|
* along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
|
||||||
|
*/
|
||||||
|
|
||||||
#pragma once
|
#pragma once
|
||||||
|
|
||||||
#define RESOURCE_INDEX(x) (x + 1)
|
|
||||||
|
|
||||||
typedef enum {
|
typedef enum {
|
||||||
OWNER_FREE = 0,
|
OWNER_FREE = 0,
|
||||||
OWNER_PWMINPUT,
|
OWNER_PWMINPUT,
|
||||||
OWNER_PPMINPUT,
|
OWNER_PPMINPUT,
|
||||||
OWNER_MOTOR,
|
OWNER_MOTOR,
|
||||||
OWNER_SERVO,
|
OWNER_SERVO,
|
||||||
OWNER_SOFTSERIAL,
|
OWNER_LED,
|
||||||
OWNER_ADC,
|
OWNER_ADC,
|
||||||
OWNER_SERIAL,
|
OWNER_ADC_BATT,
|
||||||
|
OWNER_ADC_CURR,
|
||||||
|
OWNER_ADC_EXT,
|
||||||
|
OWNER_ADC_RSSI,
|
||||||
|
OWNER_SERIAL_TX,
|
||||||
|
OWNER_SERIAL_RX,
|
||||||
OWNER_PINDEBUG,
|
OWNER_PINDEBUG,
|
||||||
OWNER_TIMER,
|
OWNER_TIMER,
|
||||||
OWNER_SONAR_TRIGGER,
|
OWNER_SONAR_TRIGGER,
|
||||||
OWNER_SONAR_ECHO,
|
OWNER_SONAR_ECHO,
|
||||||
OWNER_SYSTEM,
|
OWNER_SYSTEM,
|
||||||
OWNER_SPI,
|
OWNER_SPI_SCK,
|
||||||
OWNER_I2C,
|
OWNER_SPI_MISO,
|
||||||
OWNER_SDCARD,
|
OWNER_SPI_MOSI,
|
||||||
OWNER_FLASH,
|
OWNER_I2C_SCL,
|
||||||
|
OWNER_I2C_SDA,
|
||||||
|
OWNER_SDCARD_CS,
|
||||||
|
OWNER_FLASH_CS,
|
||||||
|
OWNER_BARO_CS,
|
||||||
|
OWNER_MPU_CS,
|
||||||
|
OWNER_OSD_CS,
|
||||||
|
OWNER_RX_SPI_CS,
|
||||||
|
OWNER_SPI_CS,
|
||||||
|
OWNER_MPU_EXTI,
|
||||||
|
OWNER_BARO_EXTI,
|
||||||
OWNER_USB,
|
OWNER_USB,
|
||||||
|
OWNER_USB_DETECT,
|
||||||
OWNER_BEEPER,
|
OWNER_BEEPER,
|
||||||
OWNER_OSD,
|
OWNER_OSD,
|
||||||
OWNER_BARO,
|
OWNER_SDCARD_DETECT,
|
||||||
OWNER_MPU,
|
OWNER_RX_BIND,
|
||||||
OWNER_INVERTER,
|
OWNER_INVERTER,
|
||||||
OWNER_LED_STRIP,
|
OWNER_LED_STRIP,
|
||||||
OWNER_LED,
|
|
||||||
OWNER_RX,
|
|
||||||
OWNER_TX,
|
|
||||||
OWNER_SOFTSPI,
|
|
||||||
OWNER_RX_SPI,
|
|
||||||
OWNER_TOTAL_COUNT
|
OWNER_TOTAL_COUNT
|
||||||
} resourceOwner_t;
|
} resourceOwner_e;
|
||||||
|
|
||||||
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
|
extern const char * const ownerNames[OWNER_TOTAL_COUNT];
|
||||||
|
|
||||||
// Currently TIMER should be shared resource (softserial dualtimer and timerqueue needs to allocate timer channel, but pin can be used for other function)
|
#define RESOURCE_INDEX(x) (x + 1)
|
||||||
// with mode switching (shared serial ports, ...) this will need some improvement
|
#define RESOURCE_SOFT_OFFSET 10
|
||||||
typedef enum {
|
|
||||||
RESOURCE_NONE = 0,
|
|
||||||
RESOURCE_INPUT, RESOURCE_OUTPUT, RESOURCE_IO,
|
|
||||||
RESOURCE_TIMER,
|
|
||||||
RESOURCE_UART_TX, RESOURCE_UART_RX, RESOURCE_UART_TXRX,
|
|
||||||
RESOURCE_EXTI,
|
|
||||||
RESOURCE_I2C_SCL, RESOURCE_I2C_SDA,
|
|
||||||
RESOURCE_SPI_SCK, RESOURCE_SPI_MOSI, RESOURCE_SPI_MISO, RESOURCE_SPI_CS,
|
|
||||||
RESOURCE_ADC_BATTERY, RESOURCE_ADC_RSSI, RESOURCE_ADC_EXTERNAL1, RESOURCE_ADC_CURRENT,
|
|
||||||
RESOURCE_RX_CE,
|
|
||||||
RESOURCE_TOTAL_COUNT
|
|
||||||
} resourceType_t;
|
|
||||||
|
|
||||||
extern const char * const resourceNames[RESOURCE_TOTAL_COUNT];
|
|
||||||
|
|
|
@ -73,7 +73,7 @@ void rxSpiDeviceInit(rx_spi_type_e spiType)
|
||||||
#else
|
#else
|
||||||
UNUSED(spiType);
|
UNUSED(spiType);
|
||||||
const SPIDevice rxSPIDevice = spiDeviceByInstance(RX_SPI_INSTANCE);
|
const SPIDevice rxSPIDevice = spiDeviceByInstance(RX_SPI_INSTANCE);
|
||||||
IOInit(IOGetByTag(IO_TAG(RX_NSS_PIN)), OWNER_SPI, RESOURCE_SPI_CS, rxSPIDevice + 1);
|
IOInit(IOGetByTag(IO_TAG(RX_NSS_PIN)), OWNER_SPI_CS, rxSPIDevice + 1);
|
||||||
#endif // USE_RX_SOFTSPI
|
#endif // USE_RX_SOFTSPI
|
||||||
|
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
|
@ -83,7 +83,7 @@ void rxSpiDeviceInit(rx_spi_type_e spiType)
|
||||||
|
|
||||||
#ifdef RX_CE_PIN
|
#ifdef RX_CE_PIN
|
||||||
// CE as OUTPUT
|
// CE as OUTPUT
|
||||||
IOInit(IOGetByTag(IO_TAG(RX_CE_PIN)), OWNER_RX_SPI, RESOURCE_RX_CE, rxSPIDevice + 1);
|
IOInit(IOGetByTag(IO_TAG(RX_CE_PIN)), OWNER_RX_SPI_CS, rxSPIDevice + 1);
|
||||||
#if defined(STM32F10X)
|
#if defined(STM32F10X)
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(RX_CE_PIN)), SPI_IO_CS_CFG);
|
IOConfigGPIO(IOGetByTag(IO_TAG(RX_CE_PIN)), SPI_IO_CS_CFG);
|
||||||
#elif defined(STM32F3) || defined(STM32F4)
|
#elif defined(STM32F3) || defined(STM32F4)
|
||||||
|
|
|
@ -128,7 +128,7 @@ void sdcardInsertionDetectDeinit(void)
|
||||||
{
|
{
|
||||||
#ifdef SDCARD_DETECT_PIN
|
#ifdef SDCARD_DETECT_PIN
|
||||||
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
||||||
IOInit(sdCardDetectPin, OWNER_FREE, RESOURCE_NONE, 0);
|
IOInit(sdCardDetectPin, OWNER_FREE, 0);
|
||||||
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
|
IOConfigGPIO(sdCardDetectPin, IOCFG_IN_FLOATING);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -137,7 +137,7 @@ void sdcardInsertionDetectInit(void)
|
||||||
{
|
{
|
||||||
#ifdef SDCARD_DETECT_PIN
|
#ifdef SDCARD_DETECT_PIN
|
||||||
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
sdCardDetectPin = IOGetByTag(IO_TAG(SDCARD_DETECT_PIN));
|
||||||
IOInit(sdCardDetectPin, OWNER_SDCARD, RESOURCE_INPUT, 0);
|
IOInit(sdCardDetectPin, OWNER_SDCARD_DETECT, 0);
|
||||||
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
|
IOConfigGPIO(sdCardDetectPin, IOCFG_IPU);
|
||||||
#endif
|
#endif
|
||||||
}
|
}
|
||||||
|
@ -558,7 +558,7 @@ void sdcard_init(bool useDMA)
|
||||||
|
|
||||||
#ifdef SDCARD_SPI_CS_PIN
|
#ifdef SDCARD_SPI_CS_PIN
|
||||||
sdCardCsPin = IOGetByTag(IO_TAG(SDCARD_SPI_CS_PIN));
|
sdCardCsPin = IOGetByTag(IO_TAG(SDCARD_SPI_CS_PIN));
|
||||||
IOInit(sdCardCsPin, OWNER_SDCARD, RESOURCE_SPI_CS, 0);
|
IOInit(sdCardCsPin, OWNER_SDCARD_CS, 0);
|
||||||
IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG);
|
IOConfigGPIO(sdCardCsPin, SPI_IO_CS_CFG);
|
||||||
#endif // SDCARD_SPI_CS_PIN
|
#endif // SDCARD_SPI_CS_PIN
|
||||||
|
|
||||||
|
|
|
@ -20,7 +20,11 @@
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
|
|
||||||
typedef struct sdcardMetadata_t {
|
typedef struct sdcardConfig_s {
|
||||||
|
uint8_t useDma;
|
||||||
|
} sdcardConfig_t;
|
||||||
|
|
||||||
|
typedef struct sdcardMetadata_s {
|
||||||
uint8_t manufacturerID;
|
uint8_t manufacturerID;
|
||||||
uint16_t oemID;
|
uint16_t oemID;
|
||||||
|
|
||||||
|
|
|
@ -17,6 +17,7 @@
|
||||||
|
|
||||||
#include <stdbool.h>
|
#include <stdbool.h>
|
||||||
#include <stdint.h>
|
#include <stdint.h>
|
||||||
|
#include <string.h>
|
||||||
|
|
||||||
#include "platform.h"
|
#include "platform.h"
|
||||||
|
|
||||||
|
@ -25,6 +26,13 @@ typedef enum {
|
||||||
BAUDRATE_KISS = 38400
|
BAUDRATE_KISS = 38400
|
||||||
} escBaudRate_e;
|
} escBaudRate_e;
|
||||||
|
|
||||||
|
typedef enum {
|
||||||
|
PROTOCOL_SIMONK = 0,
|
||||||
|
PROTOCOL_BLHELI = 1,
|
||||||
|
PROTOCOL_KISS = 2,
|
||||||
|
PROTOCOL_KISSALL = 3
|
||||||
|
} escProtocol_e;
|
||||||
|
|
||||||
#if defined(USE_ESCSERIAL)
|
#if defined(USE_ESCSERIAL)
|
||||||
|
|
||||||
#include "build/build_config.h"
|
#include "build/build_config.h"
|
||||||
|
@ -80,11 +88,19 @@ typedef struct escSerial_s {
|
||||||
|
|
||||||
uint8_t escSerialPortIndex;
|
uint8_t escSerialPortIndex;
|
||||||
uint8_t mode;
|
uint8_t mode;
|
||||||
|
uint8_t outputCount;
|
||||||
|
|
||||||
timerCCHandlerRec_t timerCb;
|
timerCCHandlerRec_t timerCb;
|
||||||
timerCCHandlerRec_t edgeCb;
|
timerCCHandlerRec_t edgeCb;
|
||||||
} escSerial_t;
|
} escSerial_t;
|
||||||
|
|
||||||
|
typedef struct {
|
||||||
|
IO_t io;
|
||||||
|
uint8_t inverted;
|
||||||
|
} escOutputs_t;
|
||||||
|
|
||||||
|
escOutputs_t escOutputs[MAX_SUPPORTED_MOTORS];
|
||||||
|
|
||||||
extern timerHardware_t* serialTimerHardware;
|
extern timerHardware_t* serialTimerHardware;
|
||||||
extern escSerial_t escSerialPorts[];
|
extern escSerial_t escSerialPorts[];
|
||||||
|
|
||||||
|
@ -97,16 +113,38 @@ void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialTimerBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture);
|
||||||
static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
static void escSerialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity);
|
||||||
|
|
||||||
void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
void setTxSignalEsc(escSerial_t *escSerial, uint8_t state)
|
||||||
{
|
{
|
||||||
|
if((escSerial->mode = PROTOCOL_KISSALL))
|
||||||
|
{
|
||||||
|
for (volatile uint8_t i = 0; i < escSerial->outputCount; i++) {
|
||||||
|
uint8_t state_temp = state;
|
||||||
|
if(escOutputs[i].inverted) {
|
||||||
|
state_temp ^= ENABLE;
|
||||||
|
}
|
||||||
|
|
||||||
|
if (state_temp) {
|
||||||
|
IOHi(escOutputs[i].io);
|
||||||
|
} else {
|
||||||
|
IOLo(escOutputs[i].io);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
else
|
||||||
|
{
|
||||||
|
if(escSerial->rxTimerHardware->output & TIMER_OUTPUT_INVERTED) {
|
||||||
|
state ^= ENABLE;
|
||||||
|
}
|
||||||
|
|
||||||
if (state) {
|
if (state) {
|
||||||
IOHi(escSerial->txIO);
|
IOHi(escSerial->txIO);
|
||||||
} else {
|
} else {
|
||||||
IOLo(escSerial->txIO);
|
IOLo(escSerial->txIO);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg)
|
static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg)
|
||||||
{
|
{
|
||||||
|
@ -114,11 +152,11 @@ static void escSerialGPIOConfig(ioTag_t tag, ioConfig_t cfg)
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
IOInit(IOGetByTag(tag), OWNER_MOTOR, RESOURCE_OUTPUT, 0);
|
IOInit(IOGetByTag(tag), OWNER_MOTOR, 0);
|
||||||
IOConfigGPIO(IOGetByTag(tag), cfg);
|
IOConfigGPIO(IOGetByTag(tag), cfg);
|
||||||
}
|
}
|
||||||
|
|
||||||
void serialInputPortConfigEsc(const timerHardware_t *timerHardwarePtr)
|
void escSerialInputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
#ifdef STM32F10X
|
#ifdef STM32F10X
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU);
|
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_IPU);
|
||||||
|
@ -164,12 +202,12 @@ static void serialTimerRxConfigBL(const timerHardware_t *timerHardwarePtr, uint8
|
||||||
uint8_t mhz = SystemCoreClock / 2000000;
|
uint8_t mhz = SystemCoreClock / 2000000;
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, mhz);
|
timerConfigure(timerHardwarePtr, 0xFFFF, mhz);
|
||||||
serialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, (options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeBL);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
static void escSerialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||||
{
|
{
|
||||||
uint32_t timerPeriod=34;
|
uint32_t timerPeriod=34;
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
|
@ -178,7 +216,7 @@ static void serialTimerTxConfig(const timerHardware_t *timerHardwarePtr, uint8_t
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].timerCb, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
static void escSerialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||||
{
|
{
|
||||||
TIM_ICInitTypeDef TIM_ICInitStructure;
|
TIM_ICInitTypeDef TIM_ICInitStructure;
|
||||||
|
|
||||||
|
@ -192,17 +230,17 @@ static void serialICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity)
|
||||||
TIM_ICInit(tim, &TIM_ICInitStructure);
|
TIM_ICInit(tim, &TIM_ICInitStructure);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
static void escSerialTimerRxConfig(const timerHardware_t *timerHardwarePtr, uint8_t reference)
|
||||||
{
|
{
|
||||||
// start bit is usually a FALLING signal
|
// start bit is usually a FALLING signal
|
||||||
TIM_DeInit(timerHardwarePtr->tim);
|
TIM_DeInit(timerHardwarePtr->tim);
|
||||||
timerConfigure(timerHardwarePtr, 0xFFFF, 1);
|
timerConfigure(timerHardwarePtr, 0xFFFF, 1);
|
||||||
serialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
escSerialICConfig(timerHardwarePtr->tim, timerHardwarePtr->channel, TIM_ICPolarity_Falling);
|
||||||
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
timerChCCHandlerInit(&escSerialPorts[reference].edgeCb, onSerialRxPinChangeEsc);
|
||||||
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
timerChConfigCallbacks(timerHardwarePtr, &escSerialPorts[reference].edgeCb, NULL);
|
||||||
}
|
}
|
||||||
|
|
||||||
static void serialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
static void escSerialOutputPortConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_OUT_PP);
|
escSerialGPIOConfig(timerHardwarePtr->tag, IOCFG_OUT_PP);
|
||||||
timerChITConfig(timerHardwarePtr,DISABLE);
|
timerChITConfig(timerHardwarePtr,DISABLE);
|
||||||
|
@ -225,7 +263,11 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac
|
||||||
{
|
{
|
||||||
escSerial_t *escSerial = &(escSerialPorts[portIndex]);
|
escSerial_t *escSerial = &(escSerialPorts[portIndex]);
|
||||||
|
|
||||||
|
if(mode != PROTOCOL_KISSALL){
|
||||||
escSerial->rxTimerHardware = &(timerHardware[output]);
|
escSerial->rxTimerHardware = &(timerHardware[output]);
|
||||||
|
}
|
||||||
|
|
||||||
|
escSerial->mode = mode;
|
||||||
escSerial->txTimerHardware = &(timerHardware[ESCSERIAL_TIMER_TX_HARDWARE]);
|
escSerial->txTimerHardware = &(timerHardware[ESCSERIAL_TIMER_TX_HARDWARE]);
|
||||||
|
|
||||||
escSerial->port.vTable = escSerialVTable;
|
escSerial->port.vTable = escSerialVTable;
|
||||||
|
@ -247,30 +289,56 @@ serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbac
|
||||||
|
|
||||||
escSerial->escSerialPortIndex = portIndex;
|
escSerial->escSerialPortIndex = portIndex;
|
||||||
|
|
||||||
|
if(mode != PROTOCOL_KISSALL)
|
||||||
|
{
|
||||||
escSerial->txIO = IOGetByTag(escSerial->rxTimerHardware->tag);
|
escSerial->txIO = IOGetByTag(escSerial->rxTimerHardware->tag);
|
||||||
serialInputPortConfigEsc(escSerial->rxTimerHardware);
|
escSerialInputPortConfig(escSerial->rxTimerHardware);
|
||||||
|
|
||||||
setTxSignalEsc(escSerial, ENABLE);
|
setTxSignalEsc(escSerial, ENABLE);
|
||||||
|
}
|
||||||
delay(50);
|
delay(50);
|
||||||
|
|
||||||
if(mode==0){
|
if(mode==PROTOCOL_SIMONK){
|
||||||
serialTimerTxConfig(escSerial->txTimerHardware, portIndex);
|
escSerialTimerTxConfig(escSerial->txTimerHardware, portIndex);
|
||||||
serialTimerRxConfig(escSerial->rxTimerHardware, portIndex);
|
escSerialTimerRxConfig(escSerial->rxTimerHardware, portIndex);
|
||||||
}
|
}
|
||||||
else if(mode==1){
|
else if(mode==PROTOCOL_BLHELI){
|
||||||
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
|
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
|
||||||
serialTimerRxConfigBL(escSerial->rxTimerHardware, portIndex, options);
|
serialTimerRxConfigBL(escSerial->rxTimerHardware, portIndex, options);
|
||||||
}
|
}
|
||||||
else if(mode==2) {
|
else if(mode==PROTOCOL_KISS) {
|
||||||
serialOutputPortConfig(escSerial->rxTimerHardware); // rx is the pin used
|
escSerialOutputPortConfig(escSerial->rxTimerHardware); // rx is the pin used
|
||||||
|
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
|
||||||
|
}
|
||||||
|
else if(mode==PROTOCOL_KISSALL) {
|
||||||
|
escSerial->outputCount = 0;
|
||||||
|
memset(&escOutputs, 0, sizeof(escOutputs));
|
||||||
|
pwmOutputPort_t *pwmMotors = pwmGetMotors();
|
||||||
|
for (volatile uint8_t i = 0; i < MAX_SUPPORTED_MOTORS; i++) {
|
||||||
|
if (pwmMotors[i].enabled) {
|
||||||
|
if (pwmMotors[i].io != IO_NONE) {
|
||||||
|
for (volatile uint8_t j = 0; j < USABLE_TIMER_CHANNEL_COUNT; j++) {
|
||||||
|
if(pwmMotors[i].io == IOGetByTag(timerHardware[j].tag))
|
||||||
|
{
|
||||||
|
escSerialOutputPortConfig(&timerHardware[j]);
|
||||||
|
if(timerHardware[j].output & TIMER_OUTPUT_INVERTED) {
|
||||||
|
escOutputs[escSerial->outputCount].inverted = 1;
|
||||||
|
}
|
||||||
|
break;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
escOutputs[escSerial->outputCount].io = pwmMotors[i].io;
|
||||||
|
escSerial->outputCount++;
|
||||||
|
}
|
||||||
|
}
|
||||||
|
}
|
||||||
|
setTxSignalEsc(escSerial, ENABLE);
|
||||||
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
|
serialTimerTxConfigBL(escSerial->txTimerHardware, portIndex, baud);
|
||||||
}
|
}
|
||||||
escSerial->mode = mode;
|
|
||||||
return &escSerial->port;
|
return &escSerial->port;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
||||||
void serialInputPortDeConfig(const timerHardware_t *timerHardwarePtr)
|
void escSerialInputPortDeConfig(const timerHardware_t *timerHardwarePtr)
|
||||||
{
|
{
|
||||||
timerChClearCCFlag(timerHardwarePtr);
|
timerChClearCCFlag(timerHardwarePtr);
|
||||||
timerChITConfig(timerHardwarePtr,DISABLE);
|
timerChITConfig(timerHardwarePtr,DISABLE);
|
||||||
|
@ -284,7 +352,7 @@ void closeEscSerial(escSerialPortIndex_e portIndex, uint16_t output)
|
||||||
|
|
||||||
escSerial->rxTimerHardware = &(timerHardware[output]);
|
escSerial->rxTimerHardware = &(timerHardware[output]);
|
||||||
escSerial->txTimerHardware = &(timerHardware[ESCSERIAL_TIMER_TX_HARDWARE]);
|
escSerial->txTimerHardware = &(timerHardware[ESCSERIAL_TIMER_TX_HARDWARE]);
|
||||||
serialInputPortDeConfig(escSerial->rxTimerHardware);
|
escSerialInputPortDeConfig(escSerial->rxTimerHardware);
|
||||||
timerChConfigCallbacks(escSerial->txTimerHardware,NULL,NULL);
|
timerChConfigCallbacks(escSerial->txTimerHardware,NULL,NULL);
|
||||||
timerChConfigCallbacks(escSerial->rxTimerHardware,NULL,NULL);
|
timerChConfigCallbacks(escSerial->rxTimerHardware,NULL,NULL);
|
||||||
TIM_DeInit(escSerial->txTimerHardware->tim);
|
TIM_DeInit(escSerial->txTimerHardware->tim);
|
||||||
|
@ -339,7 +407,7 @@ reload:
|
||||||
escSerial->isTransmittingData = true;
|
escSerial->isTransmittingData = true;
|
||||||
|
|
||||||
//set output
|
//set output
|
||||||
serialOutputPortConfig(escSerial->rxTimerHardware);
|
escSerialOutputPortConfig(escSerial->rxTimerHardware);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -383,7 +451,7 @@ reload:
|
||||||
|
|
||||||
if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) {
|
if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) {
|
||||||
escSerial->isTransmittingData = false;
|
escSerial->isTransmittingData = false;
|
||||||
serialInputPortConfigEsc(escSerial->rxTimerHardware);
|
escSerialInputPortConfig(escSerial->rxTimerHardware);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -417,7 +485,9 @@ void processTxStateBL(escSerial_t *escSerial)
|
||||||
|
|
||||||
|
|
||||||
//set output
|
//set output
|
||||||
serialOutputPortConfig(escSerial->rxTimerHardware);
|
if(escSerial->mode==PROTOCOL_BLHELI) {
|
||||||
|
escSerialOutputPortConfig(escSerial->rxTimerHardware);
|
||||||
|
}
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -432,9 +502,9 @@ void processTxStateBL(escSerial_t *escSerial)
|
||||||
|
|
||||||
escSerial->isTransmittingData = false;
|
escSerial->isTransmittingData = false;
|
||||||
if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) {
|
if (isEscSerialTransmitBufferEmpty((serialPort_t *)escSerial)) {
|
||||||
if(escSerial->mode==1)
|
if(escSerial->mode==PROTOCOL_BLHELI)
|
||||||
{
|
{
|
||||||
serialInputPortConfigEsc(escSerial->rxTimerHardware);
|
escSerialInputPortConfig(escSerial->rxTimerHardware);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -463,7 +533,7 @@ void prepareForNextRxByteBL(escSerial_t *escSerial)
|
||||||
escSerial->isSearchingForStartBit = true;
|
escSerial->isSearchingForStartBit = true;
|
||||||
if (escSerial->rxEdge == LEADING) {
|
if (escSerial->rxEdge == LEADING) {
|
||||||
escSerial->rxEdge = TRAILING;
|
escSerial->rxEdge = TRAILING;
|
||||||
serialICConfig(
|
escSerialICConfig(
|
||||||
escSerial->rxTimerHardware->tim,
|
escSerial->rxTimerHardware->tim,
|
||||||
escSerial->rxTimerHardware->channel,
|
escSerial->rxTimerHardware->channel,
|
||||||
(escSerial->port.options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling
|
(escSerial->port.options & SERIAL_INVERTED) ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling
|
||||||
|
@ -551,7 +621,7 @@ void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
escSerial->transmissionErrors++;
|
escSerial->transmissionErrors++;
|
||||||
}
|
}
|
||||||
|
|
||||||
serialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
||||||
escSerial->rxEdge = LEADING;
|
escSerial->rxEdge = LEADING;
|
||||||
|
|
||||||
escSerial->rxBitIndex = 0;
|
escSerial->rxBitIndex = 0;
|
||||||
|
@ -569,10 +639,10 @@ void onSerialRxPinChangeBL(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
|
|
||||||
if (escSerial->rxEdge == TRAILING) {
|
if (escSerial->rxEdge == TRAILING) {
|
||||||
escSerial->rxEdge = LEADING;
|
escSerial->rxEdge = LEADING;
|
||||||
serialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Falling : TIM_ICPolarity_Rising);
|
||||||
} else {
|
} else {
|
||||||
escSerial->rxEdge = TRAILING;
|
escSerial->rxEdge = TRAILING;
|
||||||
serialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, inverted ? TIM_ICPolarity_Rising : TIM_ICPolarity_Falling);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
/*-------------------------BL*/
|
/*-------------------------BL*/
|
||||||
|
@ -605,7 +675,7 @@ void onSerialTimerEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture)
|
||||||
{
|
{
|
||||||
escSerial->isReceivingData=0;
|
escSerial->isReceivingData=0;
|
||||||
escSerial->receiveTimeout=0;
|
escSerial->receiveTimeout=0;
|
||||||
serialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Falling);
|
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Falling);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
|
@ -655,7 +725,7 @@ void onSerialRxPinChangeEsc(timerCCHandlerRec_t *cbRec, captureCompare_t capture
|
||||||
bits=1;
|
bits=1;
|
||||||
escSerial->internalRxBuffer = 0x80;
|
escSerial->internalRxBuffer = 0x80;
|
||||||
|
|
||||||
serialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Rising);
|
escSerialICConfig(escSerial->rxTimerHardware->tim, escSerial->rxTimerHardware->channel, TIM_ICPolarity_Rising);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
escSerial->receiveTimeout = 0;
|
escSerial->receiveTimeout = 0;
|
||||||
|
@ -763,7 +833,7 @@ void escSerialInitialize()
|
||||||
|
|
||||||
for (volatile uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
for (volatile uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||||
// set outputs to pullup
|
// set outputs to pullup
|
||||||
if(timerHardware[i].output==1)
|
if(timerHardware[i].output & TIMER_OUTPUT_ENABLED)
|
||||||
{
|
{
|
||||||
escSerialGPIOConfig(timerHardware[i].tag, IOCFG_IPU); //GPIO_Mode_IPU
|
escSerialGPIOConfig(timerHardware[i].tag, IOCFG_IPU); //GPIO_Mode_IPU
|
||||||
}
|
}
|
||||||
|
@ -844,15 +914,23 @@ static bool ProcessExitCommand(uint8_t c)
|
||||||
void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uint8_t mode)
|
void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uint8_t mode)
|
||||||
{
|
{
|
||||||
bool exitEsc = false;
|
bool exitEsc = false;
|
||||||
|
uint8_t motor_output = 0;
|
||||||
LED0_OFF;
|
LED0_OFF;
|
||||||
LED1_OFF;
|
LED1_OFF;
|
||||||
//StopPwmAllMotors();
|
//StopPwmAllMotors();
|
||||||
pwmDisableMotors();
|
pwmDisableMotors();
|
||||||
passPort = escPassthroughPort;
|
passPort = escPassthroughPort;
|
||||||
|
|
||||||
|
uint32_t escBaudrate = (mode == PROTOCOL_KISS) ? BAUDRATE_KISS : BAUDRATE_NORMAL;
|
||||||
|
|
||||||
|
if((mode == PROTOCOL_KISS) && (output == 255)){
|
||||||
|
motor_output = 255;
|
||||||
|
mode = PROTOCOL_KISSALL;
|
||||||
|
}
|
||||||
|
else {
|
||||||
uint8_t first_output = 0;
|
uint8_t first_output = 0;
|
||||||
for (volatile uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
for (volatile uint8_t i = 0; i < USABLE_TIMER_CHANNEL_COUNT; i++) {
|
||||||
if(timerHardware[i].output==1)
|
if(timerHardware[i].output & TIMER_OUTPUT_ENABLED)
|
||||||
{
|
{
|
||||||
first_output=i;
|
first_output=i;
|
||||||
break;
|
break;
|
||||||
|
@ -860,11 +938,10 @@ void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uin
|
||||||
}
|
}
|
||||||
|
|
||||||
//doesn't work with messy timertable
|
//doesn't work with messy timertable
|
||||||
uint8_t motor_output=first_output+output-1;
|
motor_output=first_output+output-1;
|
||||||
if(motor_output >=USABLE_TIMER_CHANNEL_COUNT)
|
if(motor_output >=USABLE_TIMER_CHANNEL_COUNT)
|
||||||
return;
|
return;
|
||||||
|
}
|
||||||
uint32_t escBaudrate = (mode == 2) ? BAUDRATE_KISS : BAUDRATE_NORMAL;
|
|
||||||
|
|
||||||
escPort = openEscSerial(ESCSERIAL1, NULL, motor_output, escBaudrate, 0, mode);
|
escPort = openEscSerial(ESCSERIAL1, NULL, motor_output, escBaudrate, 0, mode);
|
||||||
uint8_t ch;
|
uint8_t ch;
|
||||||
|
@ -898,7 +975,7 @@ void escEnablePassthrough(serialPort_t *escPassthroughPort, uint16_t output, uin
|
||||||
closeEscSerial(ESCSERIAL1, output);
|
closeEscSerial(ESCSERIAL1, output);
|
||||||
return;
|
return;
|
||||||
}
|
}
|
||||||
if(mode==1){
|
if(mode==PROTOCOL_BLHELI){
|
||||||
serialWrite(escPassthroughPort, ch); // blheli loopback
|
serialWrite(escPassthroughPort, ch); // blheli loopback
|
||||||
}
|
}
|
||||||
serialWrite(escPort, ch);
|
serialWrite(escPort, ch);
|
||||||
|
|
|
@ -101,7 +101,7 @@ void setTxSignal(softSerial_t *softSerial, uint8_t state)
|
||||||
|
|
||||||
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||||
{
|
{
|
||||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(portIndex));
|
IOInit(IOGetByTag(pin), OWNER_SERIAL_RX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
|
||||||
#ifdef STM32F1
|
#ifdef STM32F1
|
||||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(pin), IOCFG_IPU);
|
||||||
#else
|
#else
|
||||||
|
@ -111,7 +111,7 @@ void serialInputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||||
|
|
||||||
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
|
static void serialOutputPortConfig(ioTag_t pin, uint8_t portIndex)
|
||||||
{
|
{
|
||||||
IOInit(IOGetByTag(pin), OWNER_SOFTSERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(portIndex));
|
IOInit(IOGetByTag(pin), OWNER_SERIAL_TX, RESOURCE_INDEX(portIndex) + RESOURCE_SOFT_OFFSET);
|
||||||
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
|
IOConfigGPIO(IOGetByTag(pin), IOCFG_OUT_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
|
|
|
@ -109,8 +109,8 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
|
|
||||||
s->USARTx = USART1;
|
s->USARTx = USART1;
|
||||||
|
|
||||||
|
|
||||||
#ifdef USE_UART1_RX_DMA
|
#ifdef USE_UART1_RX_DMA
|
||||||
|
dmaInit(DMA1_CH5_HANDLER, OWNER_SERIAL_RX, 1);
|
||||||
s->rxDMAChannel = DMA1_Channel5;
|
s->rxDMAChannel = DMA1_Channel5;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
#endif
|
#endif
|
||||||
|
@ -118,7 +118,6 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
RCC_ClockCmd(RCC_APB2(USART1), ENABLE);
|
||||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
|
||||||
|
|
||||||
// UART1_TX PA9
|
// UART1_TX PA9
|
||||||
// UART1_RX PA10
|
// UART1_RX PA10
|
||||||
|
@ -127,17 +126,18 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL, RESOURCE_UART_TX, 1);
|
IOInit(IOGetByTag(IO_TAG(PA9)), OWNER_SERIAL_TX, 1);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA9)), IOCFG_AF_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL, RESOURCE_UART_RX, 1);
|
IOInit(IOGetByTag(IO_TAG(PA10)), OWNER_SERIAL_RX, 1);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA10)), IOCFG_IPU);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
|
dmaInit(DMA1_CH4_HANDLER, OWNER_SERIAL_TX, 1);
|
||||||
dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
dmaSetHandler(DMA1_CH4_HANDLER, uart_tx_dma_IRQHandler, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
||||||
|
|
||||||
#ifndef USE_UART1_RX_DMA
|
#ifndef USE_UART1_RX_DMA
|
||||||
|
@ -189,7 +189,6 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
|
||||||
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
RCC_ClockCmd(RCC_APB1(USART2), ENABLE);
|
||||||
RCC_ClockCmd(RCC_AHB(DMA1), ENABLE);
|
|
||||||
|
|
||||||
// UART2_TX PA2
|
// UART2_TX PA2
|
||||||
// UART2_RX PA3
|
// UART2_RX PA3
|
||||||
|
@ -198,12 +197,12 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL, RESOURCE_UART_TX, 2);
|
IOInit(IOGetByTag(IO_TAG(PA2)), OWNER_SERIAL_TX, 2);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA2)), IOCFG_AF_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL, RESOURCE_UART_RX, 2);
|
IOInit(IOGetByTag(IO_TAG(PA3)), OWNER_SERIAL_RX, 2);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(IO_TAG(PA3)), IOCFG_IPU);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -260,12 +259,12 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), (options & SERIAL_BIDIR_PP) ? IOCFG_AF_PP : IOCFG_AF_OD);
|
||||||
} else {
|
} else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL, RESOURCE_UART_TX, 3);
|
IOInit(IOGetByTag(IO_TAG(UART3_TX_PIN)), OWNER_SERIAL_TX, 3);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_TX_PIN)), IOCFG_AF_PP);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL, RESOURCE_UART_RX, 3);
|
IOInit(IOGetByTag(IO_TAG(UART3_RX_PIN)), OWNER_SERIAL_RX, 3);
|
||||||
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
IOConfigGPIO(IOGetByTag(IO_TAG(UART3_RX_PIN)), IOCFG_IPU);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -121,7 +121,7 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
|
||||||
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
((options & SERIAL_INVERTED) || (options & SERIAL_BIDIR_PP)) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP
|
||||||
);
|
);
|
||||||
|
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, index);
|
IOInit(tx, OWNER_SERIAL_TX, index);
|
||||||
IOConfigGPIOAF(tx, ioCfg, af);
|
IOConfigGPIOAF(tx, ioCfg, af);
|
||||||
|
|
||||||
if (!(options & SERIAL_INVERTED))
|
if (!(options & SERIAL_INVERTED))
|
||||||
|
@ -129,12 +129,12 @@ void serialUARTInit(IO_t tx, IO_t rx, portMode_t mode, portOptions_t options, ui
|
||||||
} else {
|
} else {
|
||||||
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
|
ioConfig_t ioCfg = IO_CONFIG(GPIO_Mode_AF, GPIO_Speed_50MHz, GPIO_OType_PP, (options & SERIAL_INVERTED) ? GPIO_PuPd_DOWN : GPIO_PuPd_UP);
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, index);
|
IOInit(tx, OWNER_SERIAL_TX, index);
|
||||||
IOConfigGPIOAF(tx, ioCfg, af);
|
IOConfigGPIOAF(tx, ioCfg, af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, index);
|
IOInit(rx, OWNER_SERIAL_RX, index);
|
||||||
IOConfigGPIOAF(rx, ioCfg, af);
|
IOConfigGPIOAF(rx, ioCfg, af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
@ -160,6 +160,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
s->USARTx = USART1;
|
s->USARTx = USART1;
|
||||||
|
|
||||||
#ifdef USE_UART1_RX_DMA
|
#ifdef USE_UART1_RX_DMA
|
||||||
|
dmaInit(DMA1_CH5_HANDLER, OWNER_SERIAL, 1);
|
||||||
s->rxDMAChannel = DMA1_Channel5;
|
s->rxDMAChannel = DMA1_Channel5;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
#endif
|
#endif
|
||||||
|
@ -177,6 +178,7 @@ uartPort_t *serialUART1(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1);
|
serialUARTInit(IOGetByTag(IO_TAG(UART1_TX_PIN)), IOGetByTag(IO_TAG(UART1_RX_PIN)), mode, options, GPIO_AF_7, 1);
|
||||||
|
|
||||||
#ifdef USE_UART1_TX_DMA
|
#ifdef USE_UART1_TX_DMA
|
||||||
|
dmaInit(DMA1_CH4_HANDLER, OWNER_SERIAL, 1);
|
||||||
dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
dmaSetHandler(DMA1_CH4_HANDLER, handleUsartTxDma, NVIC_PRIO_SERIALUART1_TXDMA, (uint32_t)&uartPort1);
|
||||||
#endif
|
#endif
|
||||||
|
|
||||||
|
@ -214,10 +216,12 @@ uartPort_t *serialUART2(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
s->USARTx = USART2;
|
s->USARTx = USART2;
|
||||||
|
|
||||||
#ifdef USE_UART2_RX_DMA
|
#ifdef USE_UART2_RX_DMA
|
||||||
|
dmaInit(DMA1_CH6_HANDLER, OWNER_SERIAL, 2);
|
||||||
s->rxDMAChannel = DMA1_Channel6;
|
s->rxDMAChannel = DMA1_Channel6;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART2_TX_DMA
|
#ifdef USE_UART2_TX_DMA
|
||||||
|
dmaInit(DMA1_CH7_HANDLER, OWNER_SERIAL, 2);
|
||||||
s->txDMAChannel = DMA1_Channel7;
|
s->txDMAChannel = DMA1_Channel7;
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||||
#endif
|
#endif
|
||||||
|
@ -269,10 +273,12 @@ uartPort_t *serialUART3(uint32_t baudRate, portMode_t mode, portOptions_t option
|
||||||
s->USARTx = USART3;
|
s->USARTx = USART3;
|
||||||
|
|
||||||
#ifdef USE_UART3_RX_DMA
|
#ifdef USE_UART3_RX_DMA
|
||||||
|
dmaInit(DMA1_CH3_HANDLER, OWNER_SERIAL, 3);
|
||||||
s->rxDMAChannel = DMA1_Channel3;
|
s->rxDMAChannel = DMA1_Channel3;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->RDR;
|
||||||
#endif
|
#endif
|
||||||
#ifdef USE_UART3_TX_DMA
|
#ifdef USE_UART3_TX_DMA
|
||||||
|
dmaInit(DMA1_CH2_HANDLER, OWNER_SERIAL, 3);
|
||||||
s->txDMAChannel = DMA1_Channel2;
|
s->txDMAChannel = DMA1_Channel2;
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->TDR;
|
||||||
#endif
|
#endif
|
||||||
|
|
|
@ -315,9 +315,13 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
if (uart->rxDMAStream) {
|
if (uart->rxDMAStream) {
|
||||||
s->rxDMAChannel = uart->DMAChannel;
|
s->rxDMAChannel = uart->DMAChannel;
|
||||||
s->rxDMAStream = uart->rxDMAStream;
|
s->rxDMAStream = uart->rxDMAStream;
|
||||||
|
dmaInit(dmaGetIdentifier(uart->rxDMAStream), OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
}
|
}
|
||||||
|
if (uart->txDMAStream) {
|
||||||
s->txDMAChannel = uart->DMAChannel;
|
s->txDMAChannel = uart->DMAChannel;
|
||||||
s->txDMAStream = uart->txDMAStream;
|
s->txDMAStream = uart->txDMAStream;
|
||||||
|
dmaInit(dmaGetIdentifier(uart->txDMAStream), OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
|
}
|
||||||
|
|
||||||
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->txDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
s->rxDMAPeripheralBaseAddr = (uint32_t)&s->USARTx->DR;
|
||||||
|
@ -343,12 +347,12 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
|
@ -406,22 +406,23 @@ uartPort_t *serialUART(UARTDevice device, uint32_t baudRate, portMode_t mode, po
|
||||||
IO_t rx = IOGetByTag(uart->rx);
|
IO_t rx = IOGetByTag(uart->rx);
|
||||||
|
|
||||||
if (options & SERIAL_BIDIR) {
|
if (options & SERIAL_BIDIR) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TXRX, RESOURCE_INDEX(device));
|
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
else {
|
else {
|
||||||
if (mode & MODE_TX) {
|
if (mode & MODE_TX) {
|
||||||
IOInit(tx, OWNER_SERIAL, RESOURCE_UART_TX, RESOURCE_INDEX(device));
|
IOInit(tx, OWNER_SERIAL_TX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(tx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
|
|
||||||
if (mode & MODE_RX) {
|
if (mode & MODE_RX) {
|
||||||
IOInit(rx, OWNER_SERIAL, RESOURCE_UART_RX, RESOURCE_INDEX(device));
|
IOInit(rx, OWNER_SERIAL_RX, RESOURCE_INDEX(device));
|
||||||
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
IOConfigGPIOAF(rx, IOCFG_AF_PP, uart->af);
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
|
||||||
// DMA TX Interrupt
|
// DMA TX Interrupt
|
||||||
|
dmaInit(uart->txIrq, OWNER_SERIAL_TX, (uint32_t)uart);
|
||||||
dmaSetHandler(uart->txIrq, dmaIRQHandler, uart->txPriority, (uint32_t)uart);
|
dmaSetHandler(uart->txIrq, dmaIRQHandler, uart->txPriority, (uint32_t)uart);
|
||||||
|
|
||||||
|
|
||||||
|
|
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