UAVCAN bootloaders split into separate repository (#7878)

This commit is contained in:
Daniel Agar 2017-09-04 13:33:02 -04:00
parent f641c1e15e
commit 474f216a0a
107 changed files with 157 additions and 18903 deletions

7
.gitmodules vendored
View File

@ -39,7 +39,10 @@
url = https://github.com/eProsima/micro-CDR.git
[submodule "platforms/nuttx/NuttX/nuttx"]
path = platforms/nuttx/NuttX/nuttx
url = git@github.com:PX4-NuttX/nuttx.git
url = https://github.com/PX4-NuttX/nuttx.git
[submodule "platforms/nuttx/NuttX/apps"]
path = platforms/nuttx/NuttX/apps
url = git@github.com:PX4-NuttX/apps.git
url = https://github.com/PX4-NuttX/apps.git
[submodule "cmake/configs/uavcan_board_ident"]
path = cmake/configs/uavcan_board_ident
url = https://github.com/PX4/uavcan_board_ident.git

View File

@ -183,7 +183,7 @@ excelsior_legacy_default: posix_excelsior_legacy qurt_excelsior_legacy
# --------------------------------------------------------------------
.PHONY: qgc_firmware px4fmu_firmware misc_qgc_extra_firmware alt_firmware
.PHONY: sizes check quick_check check_format tests
.PHONY: sizes check quick_check
.PHONY: check_posix_sitl_default check_px4fmu-v3_default
# QGroundControl flashable NuttX firmware
@ -220,20 +220,11 @@ alt_firmware: \
check_s2740vc-v1_default \
sizes
checks_bootloaders: \
check_esc35-v1_bootloader \
check_px4esc-v1_bootloader \
check_px4flow-v2_bootloader \
check_s2740vc-v1_bootloader \
# not fitting in flash check_px4cannode-v1_bootloader \
# not fitting in flash check_zubaxgnss-v1_bootloader \
sizes
sizes:
@-find build -name *.elf -type f | xargs size 2> /dev/null || :
# All default targets that don't require a special build environment
check: check_posix_sitl_default px4fmu_firmware misc_qgc_extra_firmware alt_firmware checks_bootloaders tests check_format
check: check_posix_sitl_default px4fmu_firmware misc_qgc_extra_firmware alt_firmware tests check_format
# quick_check builds a single nuttx and posix target, runs testing, and checks the style
quick_check: check_posix_sitl_default check_px4fmu-v3_default tests check_format

View File

@ -42,4 +42,5 @@ add_custom_command(OUTPUT nsh_romfsimg.c
)
add_library(romfs STATIC nsh_romfsimg.c)
add_dependencies(romfs platforms__common)
set_target_properties(romfs PROPERTIES LINKER_LANGUAGE C)

View File

@ -73,102 +73,97 @@ function(px4_generate_messages)
REQUIRED MSG_FILES OS TARGET
ARGN ${ARGN})
if("${nuttx_config_type}" STREQUAL "bootloader")
# do nothing for bootloaders
else()
set(QUIET)
if (NOT VERBOSE)
set(QUIET "-q")
endif()
set(QUIET)
if (NOT VERBOSE)
set(QUIET "-q")
endif()
# headers
set(msg_out_path ${PX4_BINARY_DIR}/src/modules/uORB/topics)
set(msg_list)
foreach(msg_file ${MSG_FILES})
get_filename_component(msg ${msg_file} NAME_WE)
list(APPEND msg_list ${msg})
endforeach()
# headers
set(msg_out_path ${PX4_BINARY_DIR}/src/modules/uORB/topics)
set(msg_list)
foreach(msg_file ${MSG_FILES})
get_filename_component(msg ${msg_file} NAME_WE)
list(APPEND msg_list ${msg})
endforeach()
set(msg_files_out)
foreach(msg ${msg_list})
list(APPEND msg_files_out ${msg_out_path}/${msg}.h)
endforeach()
set(msg_files_out)
foreach(msg ${msg_list})
list(APPEND msg_files_out ${msg_out_path}/${msg}.h)
endforeach()
add_custom_command(OUTPUT ${msg_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--headers
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_out_path}
-e msg/templates/uorb
-t ${PX4_BINARY_DIR}/topics_temporary_header
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic headers"
VERBATIM
)
add_custom_command(OUTPUT ${msg_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--headers
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_out_path}
-e msg/templates/uorb
-t ${PX4_BINARY_DIR}/topics_temporary_header
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic headers"
VERBATIM
)
# !sources
set(msg_source_out_path ${PX4_BINARY_DIR}/topics_sources)
set(msg_source_files_out ${msg_source_out_path}/uORBTopics.cpp)
foreach(msg ${msg_list})
list(APPEND msg_source_files_out ${msg_source_out_path}/${msg}.cpp)
endforeach()
add_custom_command(OUTPUT ${msg_source_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--sources
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_source_out_path}
-e msg/templates/uorb
-t ${PX4_BINARY_DIR}/topics_temporary_sources
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic sources"
VERBATIM
)
set_source_files_properties(${msg_source_files_out} PROPERTIES GENERATED TRUE)
# !sources
set(msg_source_out_path ${PX4_BINARY_DIR}/topics_sources)
set(msg_source_files_out ${msg_source_out_path}/uORBTopics.cpp)
foreach(msg ${msg_list})
list(APPEND msg_source_files_out ${msg_source_out_path}/${msg}.cpp)
endforeach()
add_custom_command(OUTPUT ${msg_source_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--sources
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_source_out_path}
-e msg/templates/uorb
-t ${PX4_BINARY_DIR}/topics_temporary_sources
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic sources"
VERBATIM
)
set_source_files_properties(${msg_source_files_out} PROPERTIES GENERATED TRUE)
# multi messages for target OS
set(msg_multi_out_path ${PX4_BINARY_DIR}/src/platforms/${OS}/px4_messages)
set(msg_multi_files_out)
foreach(msg ${msg_list})
list(APPEND msg_multi_files_out ${msg_multi_out_path}/px4_${msg}.h)
endforeach()
add_custom_command(OUTPUT ${msg_multi_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--headers
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_multi_out_path}
-e msg/templates/px4/uorb
-t ${PX4_BINARY_DIR}/multi_topics_temporary/${OS}
-p "px4_"
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic multi headers for ${OS}"
VERBATIM
)
# multi messages for target OS
set(msg_multi_out_path ${PX4_BINARY_DIR}/src/platforms/${OS}/px4_messages)
set(msg_multi_files_out)
foreach(msg ${msg_list})
list(APPEND msg_multi_files_out ${msg_multi_out_path}/px4_${msg}.h)
endforeach()
add_custom_command(OUTPUT ${msg_multi_files_out}
COMMAND ${PYTHON_EXECUTABLE}
Tools/px_generate_uorb_topic_files.py
--headers
${QUIET}
-f ${MSG_FILES}
-i ${INCLUDES}
-o ${msg_multi_out_path}
-e msg/templates/px4/uorb
-t ${PX4_BINARY_DIR}/multi_topics_temporary/${OS}
-p "px4_"
DEPENDS ${DEPENDS} ${MSG_FILES}
WORKING_DIRECTORY ${PX4_SOURCE_DIR}
COMMENT "Generating uORB topic multi headers for ${OS}"
VERBATIM
)
px4_add_library(${TARGET}
${msg_source_files_out}
${msg_multi_files_out}
${msg_files_out}
)
px4_add_library(${TARGET}
${msg_source_files_out}
${msg_multi_files_out}
${msg_files_out}
)
target_include_directories(${TARGET}
PRIVATE ${PX4_SOURCE_DIR}/src/lib/micro-CDR/include
PRIVATE ${PX4_BINARY_DIR}/src/lib/micro-CDR/include/microcdr
)
target_link_libraries(${TARGET} PRIVATE lib__micro-CDR)
endif()
target_include_directories(${TARGET}
PRIVATE ${PX4_SOURCE_DIR}/src/lib/micro-CDR/include
PRIVATE ${PX4_BINARY_DIR}/src/lib/micro-CDR/include/microcdr
)
target_link_libraries(${TARGET} PRIVATE lib__micro-CDR)
endfunction()
#=============================================================================

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader)

View File

@ -34,14 +34,11 @@ px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
SW_MINOR ${uavcanblid_sw_version_minor}
)
include_directories(${PX4_SOURCE_DIR}/src/drivers/boards/esc35-v1/bootloader)
set(config_module_list
#
# Board support modules
#
drivers/boards
drivers/bootloaders
drivers/device
drivers/led
drivers/stm32

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader)

View File

@ -24,7 +24,7 @@ add_definitions(
)
px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
BIN ${CMAKE_CURRENT_BINARY_DIR}/src/firmware/nuttx/px4cannode-v1.bin
BIN ${PX4_BINARY_DIR}/src/firmware/nuttx/px4cannode-v1.bin
HWNAME ${uavcanblid_name}
HW_MAJOR ${uavcanblid_hw_version_major}
HW_MINOR ${uavcanblid_hw_version_minor}
@ -32,8 +32,6 @@ px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
SW_MINOR ${uavcanblid_sw_version_minor}
)
include_directories(${PX4_SOURCE_DIR}/src/drivers/boards/px4cannode-v1/bootloader)
set(config_module_list
#
# Board support modules

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader)

View File

@ -26,7 +26,7 @@ add_definitions(
)
px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
BIN ${CMAKE_CURRENT_BINARY_DIR}/src/firmware/nuttx/px4esc-v1.bin
BIN ${PX4_BINARY_DIR}/src/firmware/nuttx/px4esc-v1.bin
HWNAME ${uavcanblid_name}
HW_MAJOR ${uavcanblid_hw_version_major}
HW_MINOR ${uavcanblid_hw_version_minor}
@ -34,8 +34,6 @@ px4_nuttx_make_uavcan_bootloadable(BOARD ${BOARD}
SW_MINOR ${uavcanblid_sw_version_minor}
)
include_directories(${PX4_SOURCE_DIR}/src/drivers/boards/px4esc-v1/bootloader)
set(config_module_list
#
# Board support modules

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader)

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m4 CONFIG bootloader)

View File

@ -1,2 +0,0 @@
include(nuttx/px4_uavcan_bootloader)
px4_nuttx_configure(HWCLASS m3 CONFIG bootloader)

@ -0,0 +1 @@
Subproject commit f8851c841ecdaacc41a5219cc83e4a178a09bc08

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 1)
set(uavcanblid_hw_version_minor 0)
set(uavcanblid_name "\"com.auav.esc35-v1\"")

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 1)
set(uavcanblid_hw_version_minor 0)
set(uavcanblid_name "\"org.pixhawk.px4cannode-v1\"")

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 1)
set(uavcanblid_hw_version_minor 6)
set(uavcanblid_name "\"org.pixhawk.px4esc-v1\"")

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 2)
set(uavcanblid_hw_version_minor 0)
set(uavcanblid_name "\"org.pixhawk.px4flow-v2\"")

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 1)
set(uavcanblid_hw_version_minor 0)
set(uavcanblid_name "\"com.thiemar.s2740vc-v1\"")

View File

@ -1,3 +0,0 @@
set(uavcanblid_hw_version_major 1)
set(uavcanblid_hw_version_minor 0)
set(uavcanblid_name "\"com.zubax.gnss\"")

View File

@ -188,9 +188,7 @@ function(px4_os_add_flags)
#set(added_link_dirs ${nuttx_export_dir}/libs)
set(added_definitions -D__PX4_NUTTX)
if(NOT ${nuttx_config_type} STREQUAL "bootloader")
list(APPEND added_definitions -D__DF_NUTTX)
endif()
list(APPEND added_definitions -D__DF_NUTTX)
if("${config_nuttx_hw_stack_check_${BOARD}}" STREQUAL "y")
set(instrument_flags
@ -241,7 +239,7 @@ function(px4_os_prebuild_targets)
add_custom_target(${OUT} DEPENDS nuttx_context)
# parse nuttx config options for cmake
file(STRINGS ${PX4_SOURCE_DIR}/nuttx-configs/${BOARD}/${nuttx_config_type}/defconfig ConfigContents)
file(STRINGS ${PX4_SOURCE_DIR}/nuttx-configs/${BOARD}/nsh/defconfig ConfigContents)
foreach(NameAndValue ${ConfigContents})
# Strip leading spaces
string(REGEX REPLACE "^[ ]+" "" NameAndValue ${NameAndValue})
@ -271,7 +269,6 @@ endfunction()
# Usage:
# px4_nuttx_configure(
# HWCLASS <m3|m4>
# CONFIG <nsh|bootloader
# [ROMFS <y|n>
# ROMFSROOT <root>]
# )
@ -306,13 +303,6 @@ function(px4_nuttx_configure)
set(CMAKE_SYSTEM_PROCESSOR ${CMAKE_SYSTEM_PROCESSOR} CACHE INTERNAL "system processor" FORCE)
set(CMAKE_TOOLCHAIN_FILE ${PX4_SOURCE_DIR}/cmake/toolchains/Toolchain-arm-none-eabi.cmake CACHE INTERNAL "toolchain file" FORCE)
# CONFIG (nsh/bootloader)
if(CONFIG)
set(nuttx_config_type ${CONFIG} PARENT_SCOPE)
else()
set(nuttx_config_type "nsh" PARENT_SCOPE)
endif()
# ROMFS
if("${ROMFS}" STREQUAL "y")
if (NOT DEFINED ROMFSROOT)

View File

@ -1,56 +0,0 @@
############################################################################
#
# Copyright (c) 2017 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include(nuttx/px4_impl_nuttx)
message(STATUS "PX4 bootloader: ${BOARD}")
# Bring in common uavcan hardware identity definitions
include(configs/uavcan_board_ident/${BOARD})
add_definitions(
-DHW_UAVCAN_NAME=${uavcanblid_name}
-DHW_VERSION_MAJOR=${uavcanblid_hw_version_major}
-DHW_VERSION_MINOR=${uavcanblid_hw_version_minor}
)
include_directories(src/drivers/boards/${BOARD}/bootloader)
set(config_module_list
drivers/boards/common
drivers/boards/${BOARD}/bootloader
drivers/bootloaders
)
add_library(nuttx_startup ${PX4_SOURCE_DIR}/platforms/nuttx/NuttX/nuttx/arch/arm/src/stm32/gnu/stm32_vectors.S)
target_compile_definitions(nuttx_startup PRIVATE -D__ASSEMBLY__)
add_dependencies(nuttx_startup nuttx_arch_build)

View File

@ -1,164 +0,0 @@
############################################################################
# configs/esc35-v1/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,184 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
S2740VC - v1.2 STM32F302K8U6
esc35 - v1.0 STM32F303CC
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,130 +0,0 @@
/****************************************************************************
* configs/esc35-v1/scripts/ld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F303CC has 256KiB of FLASH beginning at address 0x0800:0000 and
* 40KiB of SRAM beginning at address 0x2000:0000. With an addtional 8 KiB
* located at 0x1000:0000.
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point
* in the 0x0800:0000 address range.
* The bootloader uses the first 16KiB of flash.
* Paramater storage will use the next 8 2KiB Sectors.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 16K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 40K
ccsram (rwx): ORIGIN = 0x10000000, LENGTH = 8K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
/* The STM32F303CC has 256KiB of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -1,162 +0,0 @@
############################################################################
# nuttx-configs/px4cannode-v1/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m3 \
-mthumb \
-march=armv7-m
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,184 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
S2740VC - v1.2 STM32F302K8U6
esc35 - v1.0 STM32F303CC
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,127 +0,0 @@
/****************************************************************************
* nuttx-configs/px4cannode-v1/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F103RB has 128Kb of FLASH beginning at address 0x0800:0000 and
* 20KiB of SRAM beginning at address 0x2000:0000. When booting from FLASH,
* FLASH memory is aliased to address 0x0000:0000 where the code expects to
* begin execution by jumping to the entry point in the 0x0800:0000 address
* range.
* The bootloader only uses the first 8KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 8K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 20K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
/* The STM32F103CB has 20Kb of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -1,164 +0,0 @@
############################################################################
# configs/px4esc-v1/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,184 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
S2740VC - v1.2 STM32F302K8U6
esc35 - v1.0 STM32F303CC
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,129 +0,0 @@
/****************************************************************************
* nuttx-configs/px4esc-v1/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F446RE has 512KiB of FLASH beginning at address 0x0800:0000 and
* 112KiB of SRAM beginning at address 0x2000:0000. With an addtional 16 KiB
* located at 0x2001:c000.
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point
* in the 0x0800:0000 address range.
* The bootloader only uses the first 16KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 16K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
sram1 (rwx) : ORIGIN = 0x2001C000, LENGTH = 16K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
/* The STM32F446RE has 112KiB of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -1,164 +0,0 @@
############################################################################
# nuttx-configs/px4flow-v2/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,182 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,134 +0,0 @@
/****************************************************************************
* nuttx-configs/px4flow-v2/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F427 has 2048KiB of FLASH beginning at address 0x0800:0000 and
* 256KiB of SRAM. SRAM is split up into three blocks:
*
* 1) 112KiB of SRAM beginning at address 0x2000:0000
* 2) 16KiB of SRAM beginning at address 0x2001:c000
* 3) 64KiB of SRAM beginning at address 0x2002:0000
* 4) 64KiB of TCM SRAM beginning at address 0x1000:0000
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
* the 0x0800:0000 address range.
*
* The bootloader only uses the first 16KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 16K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 192K
ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -1,164 +0,0 @@
############################################################################
# configs/s2740vc/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m4 \
-mthumb \
-march=armv7e-m \
-mfpu=fpv4-sp-d16 \
-mfloat-abi=hard
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,184 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Pixhawk ESC- v1.6-prto -STM32F446RET6
Px4Flow STM32F407VGT6
Px4FlowFuture STM32F427VIT7 Rev_C silicon (no PB12 silicon bug, full 2M Flash available)
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
S2740VC - v1.2 STM32F302K8U6
esc35 - v1.0 STM32F303CC
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,127 +0,0 @@
/****************************************************************************
* configs/s2740vc/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F302K8 has 64KiB of FLASH beginning at address 0x0800:0000 and
* 16KiB of SRAM beginning at address 0x2000:0000. When booting from FLASH,
* FLASH memory is aliased to address 0x0000:0000 where the code expects to
* begin execution by jumping to the entry point in the 0x0800:0000 address
* range.
* The bootloader only uses the first 8KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 8K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 16K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
_eronly = ABSOLUTE(.);
/* The STM32F103CB has 20Kb of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -1,162 +0,0 @@
############################################################################
# nuttx-configs/zubaxgnss-v1/bootloader/Make.defs
#
# Copyright (C) 2015 Gregory Nutt. All rights reserved.
# Author: Gregory Nutt <gnutt@nuttx.org>
# David Sidrane <david_s5@nscdg.com>
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name NuttX nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
include ${TOPDIR}/.config
include ${TOPDIR}/tools/Config.mk
include $(TOPDIR)/PX4_Warnings.mk
include $(TOPDIR)/PX4_Config.mk
#
# We only support building with the ARM bare-metal toolchain from
# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
#
CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI${HOST_OS_FIRST_LETTER}
include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
CONFIG_BOOTLOADER=y
CC = $(CROSSDEV)gcc
CXX = $(CROSSDEV)g++
CPP = $(CROSSDEV)gcc -E
LD = $(CROSSDEV)ld
AR = $(CROSSDEV)ar rcs
NM = $(CROSSDEV)nm
OBJCOPY = $(CROSSDEV)objcopy
OBJDUMP = $(CROSSDEV)objdump
MAXOPTIMIZATION = -Os
ARCHCPUFLAGS = -mcpu=cortex-m3 \
-mthumb \
-march=armv7-m
# Enable precise stack overflow tracking
ifeq ($(CONFIG_ARMV7M_STACKCHECK),y)
INSTRUMENTATIONDEFINES = -finstrument-functions -ffixed-r10
endif
# Use our linker script
LDSCRIPT = bootloaderld.script
ifeq ($(WINTOOL),y)
# Windows-native toolchains
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}"
ARCHXXINCLUDES = -I. -isystem "${shell cygpath -w $(TOPDIR)/include}" -isystem "${shell cygpath -w $(TOPDIR)/include/cxx}"
ARCHSCRIPT = -T "${shell cygpath -w $(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)}"
else
ifeq ($(PX4_WINTOOL),y)
# Windows-native toolchains (MSYS)
DIRLINK = $(TOPDIR)/tools/copydir.sh
DIRUNLINK = $(TOPDIR)/tools/unlink.sh
MKDEP = $(TOPDIR)/tools/mknulldeps.sh
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
else
# Linux/Cygwin-native toolchain
MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
endif
endif
# Tool versions
ARCHCCVERSION = ${shell $(CC) -v 2>&1 | sed -n '/^gcc version/p' | sed -e 's/^gcc version \([0-9\.]\)/\1/g' -e 's/[-\ ].*//g' -e '1q'}
ARCHCCMAJOR = ${shell echo $(ARCHCCVERSION) | cut -d'.' -f1}
# Optimization flags
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-fno-strict-aliasing \
-fno-strength-reduce \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
endif
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
ARCHWARNINGS = $(PX4_ARCHWARNINGS)
ARCHCWARNINGS = $(PX4_ARCHWARNINGS) $(PX4_ARCHCWARNINGS)
ARCHWARNINGSXX = $(ARCHWARNINGS) $(PX4_ARCHWARNINGSXX)
ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# This seems to be the only way to add linker flags
EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
CPPFLAGS = $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES)
AFLAGS = $(CFLAGS) -D__ASSEMBLY__
NXFLATLDFLAGS1 = -r -d -warn-common
NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat.ld -no-check-sections
LDNXFLATFLAGS = -e main -s 2048
OBJEXT = .o
LIBEXT = .a
EXEEXT =
# Produce partially-linked $1 from files in $2
define PRELINK
@echo "PRELINK: $1"
$(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
endef
HOSTCC = gcc
HOSTINCLUDES = -I.
HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
HOSTLDFLAGS =
LDFLAGS += --wrap up_svcall

View File

@ -1,179 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
This file currently list the SoC that are in uses and the features from the Mfg description.
It includes what is current upported in Nuttx and nearest Soc to help with porting
Pixhawk ESC- v1.2 - STM32F105RCT6
Pixhawk ESC- v1.3 - STM32F105RCT6
Pixhawk ESC- v1.4 - STM32F105RCT6
Pixhawk ESC- v1.5 - STM32F205RCT6
Pixhawk ESC- v1.5-prto -STM32F205RET6
Olimexino-STM32 STM32F103RBT6
Olimex LPC-P11C24 LPC11C24FBD48
freedom-kl25z MKL25Z128VLK4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 80LQFP
freedom-kl26z MKL26Z128VLH4 MCU 48 MHz, 128 KB flash, 16 KB SRAM, USB OTG (FS), 64 LQFP
Using:
Part Number Package Marketing Status Core Operating Frequency(F) (Processor speed) FLASH Size (Prog) Data E2PROM nom (B) Internal RAM Size 16-bit timers (IC/OC/PWM) 32-bit timer (IC/OC/PWM) Other timer functions A/D Converter I/Os (High Current) Display controller D/A Converter Integrated op-amps Serial Interface Supply Current(Icc) (Lowest power mode) typ (µA) Supply Current(Icc) (Run mode (per Mhz)) typ (µA) Operating Temperature min (°C) Operating Temperature max (°C)
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F105RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 256 - 64 7x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 2xI2C 3xUSART 2xUART USB OTG FS 2xCAN 1.9 393 -40 105
STM32F205RC LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 256 - 96 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
STM32F205RE LQFP 64 10x10x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - 2x12-bit - 3xSPI 2xI2S 3xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN SDIO 2.5 188 -40 105
Nuttx:
STM32F103RB LQFP 64 10x10x1.4 Active ARM Cortex-M3 72 128 - 20 4x16-bit - 2 x WDG, RTC, 24-bit down counter 16x12-bit 51 - - - 2xSPI 2xI2C 3xUSART(IrDA, ISO 7816) USB CAN 1.7 373 -40 85
STM32F207IG BGA 176; LQFP Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Type number Core Clock speed [max] (MHz) Flash (kB) RAM (kB) GPIO CAN UART I²C SPI ADC channels ADC (bits) Timers Timer (bits) PWM Package name Temperature range (°C) Demoboard
LPC11C24FBD48 Cortex-M0 50 32 8 36 1 1 1 2 8 10 4 16; 32 11 LQFP48 -40 °C to +85 °C OM13012
Products Parts Order Status Budgetary Price excluding tax(US$) HW dev. tools Core: Type Operating Frequency (Max) (MHz) Cache (KB) Total Flash (KB) Internal RAM (KB) Boot ROM (KB) UART SPI I2C I2S USB OTG USB features GPIOs ADC DAC 16-bit PWM (ch) 16-bit Timer (ch) Other Analog blocks Human Machine Interface VDD (min) (V) VDD (max) (V) Package type Pin count Package dimension (WxLxH) (mm3) Pin pitch (mm) Ambient Operating Temperature (Min-Max) (°C)
KL2x MKL25Z128VLK4 N Active 10000 @ US$2.18 each FRDM-KL25Z, TWR-KL25Z48M ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 - 1 (FS) USB OTG LS/FS 66 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 80 12x12x1.6 0.5 -40 to 105
KL2x MKL26Z128VLH4 Y Active 10000 @ US$1.90 each FRDM-KL26Z ARM Cortex-M0+ 48 0.064 128 - - 3 2 2 1 1 (FS) USB 2.0 FS Certified 50 16-bit (SAR) x 1 12-bit x 1, 6-bit x 1 10 11 Comparator Touch System Interface 1.71 3.6 LQFP 64 10x10x1.6 0.5 -40 to 105
Nuttx:
STM32F103RB
STM32F105VB
STM32F107VC
STM32F207IG BGA 176; LQFP 176 24x24x1.4 Active ARM Cortex-M3 120 1024 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 105
STM32F207ZE LQFP 144 20x20x1.4 Active ARM Cortex-M3 120 512 - 128 12x16-bit 2x32-bit 2 x WDG, RTC, 24-bit down counter 24x12-bit 140 - 2x12-bit - 3xSPI 2xI2S 2xI2C 4xUSART(IrDA, ISO 7816) 2xUART 2xUSB OTG (FS+FS/HS) 2xCAN Ethernet MAC10/100 SDIO 2.5 188 -40 85
Nuttx HAS:
STM32F100C8
STM32F100CB
STM32F100R8
STM32F100RB
STM32F100RC
STM32F100RD
STM32F100RE
STM32F100V8
STM32F100VB
STM32F100VC
STM32F100VD
STM32F100VE
STM32F102CB
STM32F103C4
STM32F103C8
STM32F103CB
STM32F103R8
STM32F103RB
STM32F103RC
STM32F103RD
STM32F103RE
STM32F103RG
STM32F103T8
STM32F103TB
STM32F103V8
STM32F103VB
STM32F103VC
STM32F103VE
STM32F103ZE
STM32F105VB
STM32F107VC
STM32F207IG
STM32F207ZE
STM32F302CB
STM32F302CC
STM32F302RB
STM32F302RC
STM32F302VB
STM32F302VC
STM32F303CB
STM32F303CC
STM32F303RB
STM32F303RC
STM32F303VB
STM32F303VC
STM32F372C8
STM32F372CB
STM32F372CC
STM32F372R8
STM32F372RB
STM32F372RC
STM32F372V8
STM32F372VB
STM32F372VC
STM32F373C8
STM32F373CB
STM32F373CC
STM32F373R8
STM32F373RB
STM32F373RC
STM32F373V8
STM32F373VB
STM32F373VC
STM32F401RE
STM32F405RG
STM32F405VG
STM32F405ZG
STM32F407IE
STM32F407IG
STM32F407VE
STM32F407VG
STM32F407ZE
STM32F407ZG
STM32F411RE
STM32F427I
STM32F427V
STM32F427Z
STM32F429B
STM32F429I
STM32F429N
STM32F429V
STM32F429Z
STM32L151C6
STM32L151C8
STM32L151CB
STM32L151R6
STM32L151R8
STM32L151RB
STM32L151V6
STM32L151V8
STM32L151VB
STM32L152C6
STM32L152C8
STM32L152CB
STM32L152R6
STM32L152R8
STM32L152RB
STM32L152V6
STM32L152V8
STM32L152VB
STM32L162VE
STM32L162ZD

File diff suppressed because it is too large Load Diff

View File

@ -1,130 +0,0 @@
/****************************************************************************
* nuttx-configs/zubaxgnss-v1/scripts/bootloaderld.script
*
* Copyright (C) 2015 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name NuttX nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* The STM32F105RCT6 has 256KiB of FLASH beginning at address 0x0800:0000 and
* 64KiB of SRAM beginning at address 0x2000:0000. When booting from FLASH,
* FLASH memory is aliased to address 0x0000:0000 where the code expects to
* begin execution by jumping to the entry point in the 0x0800:0000 address
* range.
* The bootloader only uses the first 8KiB of flash.
*/
MEMORY
{
flash (rx) : ORIGIN = 0x08000000, LENGTH = 8K
sram (rwx) : ORIGIN = 0x20000000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
ENTRY(__start) /* treat __start as the anchor for dead code stripping */
EXTERN(_vectors) /* force the vectors to be included in the output */
/*
* Ensure that abort() is present in the final object. The exception handling
* code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
*/
EXTERN(abort)
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
. = ALIGN(8);
*(.text .text.*)
*(.fixup)
*(.gnu.warning)
*(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
. = ALIGN(8);
_etext = ABSOLUTE(.);
} > flash
/*
* Init functions (static constructors and the like)
*/
.init_section : {
_sinit = ABSOLUTE(.);
KEEP(*(.init_array .init_array.*))
_einit = ABSOLUTE(.);
} > flash
.ARM.extab : {
*(.ARM.extab*)
} > flash
__exidx_start = ABSOLUTE(.);
.ARM.exidx : {
*(.ARM.exidx*)
} > flash
__exidx_end = ABSOLUTE(.);
. = ALIGN(8);
_eronly = ABSOLUTE(.);
/* The STM32F103CB has 20Kb of SRAM beginning at the following address */
.data : {
_sdata = ABSOLUTE(.);
*(.data .data.*)
*(.gnu.linkonce.d.*)
CONSTRUCTORS
_edata = ABSOLUTE(.);
} > sram AT > flash
.bss : {
_sbss = ABSOLUTE(.);
*(.bss .bss.*)
*(.gnu.linkonce.b.*)
*(COMMON)
_ebss = ABSOLUTE(.);
} > sram
/* Stabs debugging sections. */
.stab 0 : { *(.stab) }
.stabstr 0 : { *(.stabstr) }
.stab.excl 0 : { *(.stab.excl) }
.stab.exclstr 0 : { *(.stab.exclstr) }
.stab.index 0 : { *(.stab.index) }
.stab.indexstr 0 : { *(.stab.indexstr) }
.comment 0 : { *(.comment) }
.debug_abbrev 0 : { *(.debug_abbrev) }
.debug_info 0 : { *(.debug_info) }
.debug_line 0 : { *(.debug_line) }
.debug_pubnames 0 : { *(.debug_pubnames) }
.debug_aranges 0 : { *(.debug_aranges) }
}

View File

@ -32,15 +32,12 @@
############################################################################
if (${OS} MATCHES "nuttx")
if (NOT ${LABEL} STREQUAL "bootloader")
px4_add_library(boards_common
board_crashdump.c
board_dma_alloc.c
board_gpio_init.c
)
add_dependencies(boards_common nuttx_build)
endif()
px4_add_library(boards_common
board_crashdump.c
board_dma_alloc.c
board_gpio_init.c
)
add_dependencies(boards_common nuttx_build)
if (${CONFIG_ARCH_CHIP} MATCHES "kinetis")
add_subdirectory(kinetis)

View File

@ -50,5 +50,4 @@ px4_add_module(
esc35_usb.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (c) 2016 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__esc35-v1__bootloader
SRCS
boot.c
led.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__esc35-v1__bootloader drivers_bootloaders)

View File

@ -1,224 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2016 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_AHBENR) | RCC_AHBENR_IOPAEN |
RCC_AHBENR_IOPBEN, STM32_RCC_AHBENR);
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
stm32_configgpio(GPIO_CAN_SILENT);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
typedef begin_packed_struct struct led_t {
uint16_t red : 5;
uint16_t green : 6;
uint16_t blue : 5;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(0, off, 0, 0, 0, 0),
led(1, reset, 10, 63, 31, 255),
led(2, autobaud_start, 0, 63, 0, 1),
led(3, autobaud_end, 0, 63, 0, 2),
led(4, allocation_start, 0, 0, 31, 2),
led(5, allocation_end, 0, 63, 31, 3),
led(6, fw_update_start, 15, 63, 31, 3),
led(7, fw_update_erase_fail, 15, 63, 15, 3),
led(8, fw_update_invalid_response, 31, 0, 0, 1),
led(9, fw_update_timeout, 31, 0, 0, 2),
led(a, fw_update_invalid_crc, 31, 0, 0, 4),
led(b, jump_to_app, 0, 63, 0, 10),
};
void board_indicate(uiindication_t indication)
{
rgb_led(i2l[indication].red << 3,
i2l[indication].green << 2,
i2l[indication].blue << 3,
i2l[indication].hz);
}

View File

@ -1,121 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2016 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
#undef OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Bootloader */
#define OPT_BOOTLOADER_SIZE_IN_K (16 * 1024)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K (8 * 2048) /* Parameters will use the 8 2KiB sectors */
#define OPT_APPLICATION_IMAGE_OFFSET (OPT_BOOTLOADER_SIZE_IN_K + OPT_APPLICATION_RESERVER_IN_K)
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES STM32_FLASH_NPAGES
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE (FLASH_NUMBER_PAGES * FLASH_PAGE_SIZE)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))

View File

@ -1,114 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/board/board.h>
#include "chip/stm32_tim.h"
#include "led.h"
#define TMR_BASE STM32_TIM2_BASE
#define TMR_FREQUENCY STM32_APB1_TIM2_CLKIN
#define TMR_REG(o) (TMR_BASE+(o))
void rgb_led(int r, int g, int b, int freqs)
{
long fosc = TMR_FREQUENCY;
long prescale = 2048;
long p1s = fosc / prescale;
long p0p5s = p1s / 2;
uint16_t val;
static bool once = 0;
if (!once) {
once = 1;
/* Enabel Clock to Block */
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM2EN);
/* Reload */
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= ATIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
/* Set Prescaler STM32_TIM_SETCLOCK */
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
/* Enable STM32_TIM_SETMODE*/
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC4M_SHIFT) | ATIM_CCMR2_OC4PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
putreg16(ATIM_CCER_CC2E | ATIM_CCER_CC2P |
ATIM_CCER_CC3E | ATIM_CCER_CC3P |
ATIM_CCER_CC4E | ATIM_CCER_CC4P, TMR_REG(STM32_GTIM_CCER_OFFSET));
stm32_configgpio(GPIO_TIM2_CH2OUT);
stm32_configgpio(GPIO_TIM2_CH3OUT);
stm32_configgpio(GPIO_TIM2_CH4OUT);
}
long p = freqs == 0 ? p1s : p1s / freqs;
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR4_OFFSET));
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
if (freqs == 0) {
val &= ~ATIM_CR1_CEN;
} else {
val |= ATIM_CR1_CEN | GTIM_CR1_ARPE;
}
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= GTIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
}

View File

@ -1,37 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2016 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
__BEGIN_DECLS
void rgb_led(int r, int g, int b, int freqs);
__END_DECLS

View File

@ -41,5 +41,4 @@ px4_add_module(
px4cannode_spi.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,43 +0,0 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4cannode-v1__bootloader
COMPILE_FLAGS
SRCS
boot.c
led.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__px4cannode-v1__bootloader drivers_bootloaders)

View File

@ -1,220 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
stm32_configgpio(GPIO_CAN_CTRL);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
typedef begin_packed_struct struct led_t {
uint16_t red : 5;
uint16_t green : 6;
uint16_t blue : 5;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(0, off, 0, 0, 0, 0),
led(1, reset, 10, 63, 31, 255),
led(2, autobaud_start, 0, 63, 0, 1),
led(3, autobaud_end, 0, 63, 0, 2),
led(4, allocation_start, 0, 0, 31, 2),
led(5, allocation_end, 0, 63, 31, 3),
led(6, fw_update_start, 15, 63, 31, 3),
led(7, fw_update_erase_fail, 15, 63, 15, 3),
led(8, fw_update_invalid_response, 31, 0, 0, 1),
led(9, fw_update_timeout, 31, 0, 0, 2),
led(a, fw_update_invalid_crc, 31, 0, 0, 4),
led(b, jump_to_app, 0, 63, 0, 10),
};
void board_indicate(uiindication_t indication)
{
rgb_led(i2l[indication].red << 3,
i2l[indication].green << 2,
i2l[indication].blue << 3,
i2l[indication].hz);
}

View File

@ -1,139 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*8)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K 0
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES STM32_FLASH_NPAGES
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE (FLASH_NUMBER_PAGES*FLASH_PAGE_SIZE)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif
/* Bootloader Option*****************************************************************
*
* GPIO Function MPU Board
* Pin # Name
* -- ----- -------------------------------- ----------------------------
* * PC[09] PC9/TIM3_CH4 40 BOOT0
*/
#define GPIO_GETNODEINFO_JUMPER (BUTTON_BOOT0n&~(GPIO_EXTI))

View File

@ -1,114 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/board/board.h>
#include "chip/stm32_tim.h"
#include "led.h"
#define TMR_BASE STM32_TIM3_BASE
#define TMR_FREQUENCY STM32_APB1_TIM3_CLKIN
#define TMR_REG(o) (TMR_BASE+(o))
void rgb_led(int r, int g, int b, int freqs)
{
long fosc = TMR_FREQUENCY;
long prescale = 2048;
long p1s = fosc / prescale;
long p0p5s = p1s / 2;
uint16_t val;
static bool once = 0;
if (!once) {
once = 1;
/* Enabel Clock to Block */
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN);
/* Reload */
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= ATIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
/* Set Prescaler STM32_TIM_SETCLOCK */
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
/* Enable STM32_TIM_SETMODE*/
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
ATIM_CCER_CC2E | ATIM_CCER_CC2P |
ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
stm32_configgpio(GPIO_TIM3_CH1OUT);
stm32_configgpio(GPIO_TIM3_CH2OUT);
stm32_configgpio(GPIO_TIM3_CH3OUT);
}
long p = freqs == 0 ? p1s : p1s / freqs;
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
if (freqs == 0) {
val &= ~ATIM_CR1_CEN;
} else {
val |= ATIM_CR1_CEN;
}
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
}

View File

@ -1,37 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
__BEGIN_DECLS
void rgb_led(int r, int g, int b, int freqs);
__END_DECLS

View File

@ -39,5 +39,4 @@ px4_add_module(
px4esc_usb.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4esc-v1__bootloader
SRCS
boot.c
led.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__px4esc-v1__bootloader drivers_bootloaders)

View File

@ -1,219 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
typedef begin_packed_struct struct led_t {
uint16_t red : 5;
uint16_t green : 6;
uint16_t blue : 5;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(0, off, 0, 0, 0, 0),
led(1, reset, 10, 63, 31, 255),
led(2, autobaud_start, 0, 63, 0, 1),
led(3, autobaud_end, 0, 63, 0, 2),
led(4, allocation_start, 0, 0, 31, 2),
led(5, allocation_end, 0, 63, 31, 3),
led(6, fw_update_start, 15, 63, 31, 3),
led(7, fw_update_erase_fail, 15, 63, 15, 3),
led(8, fw_update_invalid_response, 31, 0, 0, 1),
led(9, fw_update_timeout, 31, 0, 0, 2),
led(a, fw_update_invalid_crc, 31, 0, 0, 4),
led(b, jump_to_app, 0, 63, 0, 10),
};
void board_indicate(uiindication_t indication)
{
rgb_led(i2l[indication].red << 3,
i2l[indication].green << 2,
i2l[indication].blue << 3,
i2l[indication].hz);
}

View File

@ -1,139 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Boot loader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*16)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K (32*1024) /* Parameters will use the 2nd, 3rd 16KiB sectors*/
#define OPT_APPLICATION_IMAGE_OFFSET (OPT_BOOTLOADER_SIZE_IN_K + OPT_APPLICATION_RESERVER_IN_K)
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES STM32_FLASH_NPAGES
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE ((4*16*1024) + (1*64*1024) + (3*128*1024))
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif
/* Bootloader Option*****************************************************************
*
* GPIO Function MPU Board
* Pin # Name
* -- ----- -------------------------------- ----------------------------
* PB[07] PB7/TIM2_CH2/TIM4_CH4/TIM11_CH1/I2C1_SDA 59 WAIT_GETNODEINFO
*/
#define GPIO_GETNODEINFO_JUMPER GPIO_WAIT_GETNODEINFO

View File

@ -1,114 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/board/board.h>
#include "chip/stm32_tim.h"
#include "led.h"
#define TMR_BASE STM32_TIM3_BASE
#define TMR_FREQUENCY STM32_APB1_TIM3_CLKIN
#define TMR_REG(o) (TMR_BASE+(o))
void rgb_led(int r, int g, int b, int freqs)
{
long fosc = TMR_FREQUENCY;
long prescale = 2048;
long p1s = fosc / prescale;
long p0p5s = p1s / 2;
uint16_t val;
static bool once = 0;
if (!once) {
once = 1;
/* Enabel Clock to Block */
modifyreg32(STM32_RCC_APB1ENR, 0, RCC_APB1ENR_TIM3EN);
/* Reload */
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= ATIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
/* Set Prescaler STM32_TIM_SETCLOCK */
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
/* Enable STM32_TIM_SETMODE*/
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC4M_SHIFT) | ATIM_CCMR2_OC4PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
putreg16(ATIM_CCER_CC2E | ATIM_CCER_CC2P |
ATIM_CCER_CC3E | ATIM_CCER_CC3P |
ATIM_CCER_CC4E | ATIM_CCER_CC4P, TMR_REG(STM32_GTIM_CCER_OFFSET));
stm32_configgpio(GPIO_TIM3_CH2OUT);
stm32_configgpio(GPIO_TIM3_CH3OUT);
stm32_configgpio(GPIO_TIM3_CH4OUT);
}
long p = freqs == 0 ? p1s : p1s / freqs;
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR4_OFFSET));
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
if (freqs == 0) {
val &= ~ATIM_CR1_CEN;
} else {
val |= ATIM_CR1_CEN;
}
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
}

View File

@ -1,37 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
__BEGIN_DECLS
void rgb_led(int r, int g, int b, int freqs);
__END_DECLS

View File

@ -41,5 +41,4 @@ px4_add_module(
px4flow_can.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__px4flow-v2__bootloader
SRCS
boot.c
led.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__px4flow-v2__bootloader drivers_bootloaders)

View File

@ -1,219 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(n, code, r , g , b, h) {.red = (r),.green = (g), .blue = (b),.hz = (h)}
typedef begin_packed_struct struct led_t {
uint16_t red : 5;
uint16_t green : 6;
uint16_t blue : 5;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(0, off, 0, 0, 0, 0),
led(1, reset, 10, 63, 31, 255),
led(2, autobaud_start, 0, 63, 0, 1),
led(3, autobaud_end, 0, 63, 0, 2),
led(4, allocation_start, 0, 0, 31, 2),
led(5, allocation_end, 0, 63, 31, 3),
led(6, fw_update_start, 15, 63, 31, 3),
led(7, fw_update_erase_fail, 15, 63, 15, 3),
led(8, fw_update_invalid_response, 31, 0, 0, 1),
led(9, fw_update_timeout, 31, 0, 0, 2),
led(a, fw_update_invalid_crc, 31, 0, 0, 4),
led(b, jump_to_app, 0, 63, 0, 10),
};
void board_indicate(uiindication_t indication)
{
rgb_led(i2l[indication].red << 3,
i2l[indication].green << 2,
i2l[indication].blue << 3,
i2l[indication].hz);
}

View File

@ -1,139 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (16 * 1024)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K (32*1024) /* Parameters will use the 2nd, 3rd 16KiB sectors*/
#define OPT_APPLICATION_IMAGE_OFFSET (OPT_BOOTLOADER_SIZE_IN_K + OPT_APPLICATION_RESERVER_IN_K)
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES STM32_FLASH_NPAGES
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE ((2 * ((4*16) + (64) + (3*128) + (4*128))) * 1024)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif
/* Bootloader Option*****************************************************************
*
* GPIO Function MPU Board
* Pin # Name
* -- ----- -------------------------------- ----------------------------
* * TODO TBD (Using ADDR0 for now)
*/
#define GPIO_GETNODEINFO_JUMPER GPIO_WAIT_GETNODEINFO

View File

@ -1,118 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/board/board.h>
#include "chip/stm32_tim.h"
#include "boot_config.h"
#include "led.h"
#define TMR_BASE STM32_TIM1_BASE
#define TMR_FREQUENCY STM32_APB2_TIM1_CLKIN
#define TMR_REG(o) (TMR_BASE+(o))
void rgb_led(int r, int g, int b, int freqs)
{
long fosc = TMR_FREQUENCY;
long prescale = 4096;
long p1s = fosc / prescale;
long p0p5s = p1s / 2;
uint16_t val;
static bool once = 0;
if (!once) {
once = 1;
/* Enabel Clock to Block */
modifyreg32(STM32_RCC_APB2ENR, 0, RCC_APB2ENR_TIM1EN);
/* Reload */
val = getreg16(TMR_REG(STM32_BTIM_EGR_OFFSET));
val |= ATIM_EGR_UG;
putreg16(val, TMR_REG(STM32_BTIM_EGR_OFFSET));
/* Set Prescaler STM32_TIM_SETCLOCK */
putreg16(prescale, TMR_REG(STM32_BTIM_PSC_OFFSET));
/* Enable STM32_TIM_SETMODE*/
putreg16(ATIM_CR1_CEN | ATIM_CR1_ARPE, TMR_REG(STM32_BTIM_CR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC1M_SHIFT) | ATIM_CCMR1_OC1PE |
(ATIM_CCMR_MODE_PWM1 << ATIM_CCMR1_OC2M_SHIFT) | ATIM_CCMR1_OC2PE, TMR_REG(STM32_GTIM_CCMR1_OFFSET));
putreg16((ATIM_CCMR_MODE_PWM1 << ATIM_CCMR2_OC3M_SHIFT) | ATIM_CCMR2_OC3PE, TMR_REG(STM32_GTIM_CCMR2_OFFSET));
putreg16(ATIM_CCER_CC3E | ATIM_CCER_CC3P |
ATIM_CCER_CC2E | ATIM_CCER_CC2P |
ATIM_CCER_CC1E | ATIM_CCER_CC1P, TMR_REG(STM32_GTIM_CCER_OFFSET));
stm32_configgpio(GPIO_TIM1_CH1OUT);
stm32_configgpio(GPIO_TIM1_CH2OUT);
stm32_configgpio(GPIO_TIM1_CH3OUT);
putreg16(ATIM_BDTR_MOE, TMR_REG(STM32_ATIM_BDTR_OFFSET));
}
long p = freqs == 0 ? p1s : p1s / freqs;
putreg32(p, TMR_REG(STM32_BTIM_ARR_OFFSET));
p = freqs == 0 ? p1s + 1 : p0p5s / freqs;
#if defined(MIS_WIRED_V20)
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
#else
putreg32((r * p) / 255, TMR_REG(STM32_GTIM_CCR1_OFFSET));
putreg32((g * p) / 255, TMR_REG(STM32_GTIM_CCR2_OFFSET));
putreg32((b * p) / 255, TMR_REG(STM32_GTIM_CCR3_OFFSET));
#endif
val = getreg16(TMR_REG(STM32_BTIM_CR1_OFFSET));
if (freqs == 0) {
val &= ~ATIM_CR1_CEN;
} else {
val |= ATIM_CR1_CEN;
}
putreg16(val, TMR_REG(STM32_BTIM_CR1_OFFSET));
}

View File

@ -1,37 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
__BEGIN_DECLS
void rgb_led(int r, int g, int b, int freqs);
__END_DECLS

View File

@ -49,5 +49,4 @@ px4_add_module(
s2740vc_can.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,41 +0,0 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__s2740vc-v1__bootloader
SRCS
boot.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__s2740vc-v1__bootloader drivers_bootloaders)

View File

@ -1,193 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_AHBENR) | RCC_AHBENR_IOPAEN |
RCC_AHBENR_IOPBEN, STM32_RCC_AHBENR);
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
stm32_configgpio(GPIO_CAN_RX_2);
stm32_configgpio(GPIO_CAN_TX_2);
stm32_configgpio(GPIO_CAN_SILENT);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
void board_indicate(uiindication_t indication)
{
}

View File

@ -1,139 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 10
#define OPT_BL_NUMBER_TIMERS 7
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*/
#define OPT_WAIT_FOR_GETNODEINFO 1
/* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO */
/* #define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1 */
/* #define OPT_ENABLE_WD */
#define OPT_RESTART_TIMEOUT_MS 20000u
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*8)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K 0
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES 32
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE (FLASH_NUMBER_PAGES*FLASH_PAGE_SIZE)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif
/* Bootloader Option*****************************************************************
*
* GPIO Function MPU Board
* Pin # Name
* -- ----- -------------------------------- ----------------------------
* * PC[09] PC9/TIM3_CH4 40 BOOT0
*/
#define GPIO_GETNODEINFO_JUMPER (BUTTON_BOOT0n&~(GPIO_EXTI))

View File

@ -40,5 +40,4 @@ px4_add_module(
zubax_gnss_led.c
DEPENDS
platforms__common
)
include_directories(bootloader)
)

View File

@ -1,42 +0,0 @@
############################################################################
#
# Copyright (c) 2015 PX4 Development Team. All rights reserved.
#
# Redistribution and use in source and binary forms, with or without
# modification, are permitted provided that the following conditions
# are met:
#
# 1. Redistributions of source code must retain the above copyright
# notice, this list of conditions and the following disclaimer.
# 2. Redistributions in binary form must reproduce the above copyright
# notice, this list of conditions and the following disclaimer in
# the documentation and/or other materials provided with the
# distribution.
# 3. Neither the name PX4 nor the names of its contributors may be
# used to endorse or promote products derived from this software
# without specific prior written permission.
#
# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
# POSSIBILITY OF SUCH DAMAGE.
#
############################################################################
px4_add_module(
MODULE drivers__boards__zubaxgnss-v1__bootloader
SRCS
boot.c
led.c
DEPENDS
nuttx_build
)
target_link_libraries(drivers__boards__zubaxgnss-v1__bootloader drivers_bootloaders)

View File

@ -1,222 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include "boot_config.h"
#include "board.h"
#include <debug.h>
#include <string.h>
#include <arch/board/board.h>
#include <nuttx/board.h>
#include "led.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/************************************************************************************
* Name: stm32_boardinitialize
*
* Description:
* All STM32 architectures must provide the following entry point. This entry point
* is called early in the initialization -- after all memory has been configured
* and mapped but before any devices have been initialized.
*
************************************************************************************/
__EXPORT void stm32_boardinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1ENR) | RCC_APB1ENR_CAN1EN, STM32_RCC_APB1ENR);
stm32_configgpio(GPIO_CAN1_RX);
stm32_configgpio(GPIO_CAN1_TX);
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
putreg32(getreg32(STM32_RCC_APB1RSTR) & ~RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
stm32_configgpio(GPIO_LED_CAN1);
stm32_configgpio(GPIO_LED_CAN2);
stm32_configgpio(GPIO_LED_INFO);
#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
stm32_configgpio(GPIO_GETNODEINFO_JUMPER);
#endif
}
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code prior to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void)
{
putreg32(getreg32(STM32_RCC_APB1RSTR) | RCC_APB1RSTR_CAN1RST,
STM32_RCC_APB1RSTR);
}
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrieve the product name. The returned value is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The maximum number of charter that can be written
*
* Returned Value:
* The length of characters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen)
{
DEBUGASSERT(maxlen > UAVCAN_STRLEN(HW_UAVCAN_NAME));
memcpy(product_name, HW_UAVCAN_NAME, UAVCAN_STRLEN(HW_UAVCAN_NAME));
return UAVCAN_STRLEN(HW_UAVCAN_NAME);
}
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version)
{
memset(hw_version, 0, sizeof(uavcan_HardwareVersion_t));
hw_version->major = HW_VERSION_MAJOR;
hw_version->minor = HW_VERSION_MINOR;
return board_get_mfguid(*(mfguid_t *) hw_version->unique_id);
}
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
#define led(code, a, b, c, h) {.led_a = (a), .led_b = (b), .led_c = (c), .hz = (h)}
typedef begin_packed_struct struct led_t {
uint8_t led_a : 1;
uint8_t led_b : 1;
uint8_t led_c : 1;
uint8_t hz;
} end_packed_struct led_t;
static const led_t i2l[] = {
led(off, 0, 0, 0, 0),
led(reset, 1, 1, 1, 255),
led(autobaud_start, 0, 1, 0, 255),
led(autobaud_end, 0, 1, 1, 255),
led(allocation_start, 1, 0, 0, 255),
led(allocation_end, 1, 0, 1, 255),
led(fw_update_start, 1, 1, 0, 255),
led(fw_update_erase_fail, 0, 0, 1, 5),
led(fw_update_invalid_response, 0, 1, 0, 5),
led(fw_update_timeout, 0, 1, 1, 5),
led(fw_update_invalid_crc, 1, 0, 0, 5),
led(jump_to_app, 1, 1, 1, 1),
};
void board_indicate(uiindication_t indication)
{
set_leds(i2l[indication].led_a,
i2l[indication].led_b,
i2l[indication].led_c,
i2l[indication].hz);
}

View File

@ -1,130 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file boot_config.h
*
* bootloader definitions that configures the behavior and options
* of the Boot loader
* This file is relies on the parent folder's boot_config.h file and defines
* different usages of the hardware for bootloading
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/* Bring in the board_config.h definitions
* todo:make this be pulled in from a targed's build
* files in nuttx*/
#include "../board_config.h"
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define OPT_PREFERRED_NODE_ID ANY_NODE_ID
//todo:wrap OPT_x in in ifdefs for command line definitions
#define OPT_TBOOT_MS 5000
#define OPT_NODE_STATUS_RATE_MS 800
#define OPT_NODE_INFO_RATE_MS 50
#define OPT_BL_NUMBER_TIMERS 8
/*
* This Option set is set to 1 ensure a provider of firmware has an
* opportunity update the node's firmware.
* This Option is the default policy and can be overridden by
* a jumper
* When this Policy is set, the node will ignore tboot and
* wait indefinitely for a GetNodeInfo request before booting.
*
* OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT is used to allow
* the polarity of the jumper to be True Active
*
* wait OPT_WAIT_FOR_GETNODEINFO OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
* Jumper
* yes 1 0 x
* yes 1 1 Active
* no 1 1 Not Active
* no 0 0 X
* yes 0 1 Active
* no 0 1 Not Active
*
*/
#define OPT_WAIT_FOR_GETNODEINFO 0
#undef OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO
#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 0
#define OPT_ENABLE_WD 1
#define OPT_RESTART_TIMEOUT_MS 20000
/* Reserved for the Booloader */
#define OPT_BOOTLOADER_SIZE_IN_K (1024*8)
/* Reserved for the application out of the total
* system flash minus the BOOTLOADER_SIZE_IN_K
*/
#define OPT_APPLICATION_RESERVER_IN_K 0
#define OPT_APPLICATION_IMAGE_OFFSET OPT_BOOTLOADER_SIZE_IN_K
#define OPT_APPLICATION_IMAGE_LENGTH (FLASH_SIZE-(OPT_BOOTLOADER_SIZE_IN_K+OPT_APPLICATION_RESERVER_IN_K))
#define FLASH_BASE STM32_FLASH_BASE
#define FLASH_NUMBER_PAGES STM32_FLASH_NPAGES
#define FLASH_PAGE_SIZE STM32_FLASH_PAGESIZE
#define FLASH_SIZE (FLASH_NUMBER_PAGES*FLASH_PAGE_SIZE)
#define APPLICATION_LOAD_ADDRESS (FLASH_BASE + OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_SIZE (FLASH_SIZE-OPT_APPLICATION_IMAGE_OFFSET)
#define APPLICATION_LAST_8BIT_ADDRRESS ((uint8_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint8_t)))
#define APPLICATION_LAST_32BIT_ADDRRESS ((uint32_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint32_t)))
#define APPLICATION_LAST_64BIT_ADDRRESS ((uint64_t *)((APPLICATION_LOAD_ADDRESS+APPLICATION_SIZE)-sizeof(uint64_t)))
/* If this board uses big flash that have large sectors */
#if defined(CONFIG_STM32_FLASH_CONFIG_E) || \
defined(CONFIG_STM32_FLASH_CONFIG_F) || \
defined(CONFIG_STM32_FLASH_CONFIG_G) || \
defined(CONFIG_STM32_FLASH_CONFIG_I)
#define OPT_USE_YIELD
#endif

View File

@ -1,95 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <px4_config.h>
#include <stdint.h>
#include <stdbool.h>
#include <arch/board/board.h>
#include "chip/stm32_tim.h"
#include "led.h"
#include "timer.h"
#include "board_config.h"
const int LED_TICK = 10;
static bool led_a;
static bool led_b;
static bool led_c;
static int period;
static void led_process(bl_timer_id id, void *context)
{
static int dc = 0;
static bool toggle = true;
dc += LED_TICK;
if (dc >= period) {
dc = 0;
toggle ^= true;
}
stm32_gpiowrite(GPIO_LED_INFO, led_a ? toggle : false);
stm32_gpiowrite(GPIO_LED_CAN1, led_b ? toggle : false);
stm32_gpiowrite(GPIO_LED_CAN2, led_c ? toggle : false);
}
void set_leds(bool a, bool b, bool c, int freqs)
{
static bl_timer_id tid = (bl_timer_id) - 1;
if (tid == (bl_timer_id) - 1) {
bl_timer_cb_t p = null_cb;
p.cb = led_process;
tid = timer_allocate(modeRepeating | modeStarted, LED_TICK, &p);
}
led_a = a;
led_b = b;
led_c = c;
if (freqs == 0) {
timer_stop(tid);
} else {
period = 1000 / freqs;
timer_restart(tid, LED_TICK);
}
}

View File

@ -1,39 +0,0 @@
/****************************************************************************
*
* Copyright (C) 2015 PX4 Development Team. All rights reserved.
* Author: David Sidrane<david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#include <stdbool.h>
__BEGIN_DECLS
void set_leds(bool a, bool b, bool c, int freqs);
__END_DECLS

View File

@ -32,17 +32,9 @@
############################################################################
px4_add_library(drivers_bootloaders
src/arch/stm32/drivers/can/driver.c
src/common/boot_app_shared.c
src/common/nuttx_stubs.c
src/fs/flash.c
src/protocol/uavcan.c
src/sched/timer.c
src/uavcan/main.c
src/util/crc.c
src/util/random.c
boot_app_shared.c
)
add_dependencies(drivers_bootloaders nuttx_build)
add_dependencies(drivers_bootloaders platforms__common)
include_directories(include)
target_include_directories(drivers_bootloaders INTERFACE include)

View File

@ -48,7 +48,7 @@
#include <errno.h>
#include "boot_app_shared.h"
#include "crc.h"
#include "systemlib/crc.h"
/****************************************************************************
* Pre-processor Definitions

View File

@ -1,58 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file board.h
*
* bootloader board interface
* This file contains the common interfaces that all boards
* have to supply
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define BIT(pos) (1ull<<(pos))
#define BIT_MASK(length) (BIT(length)-1)
#define BITFEILD_MASK(lsb_pos, length) ( BIT_MASK(length) << (lsb_pos))
#define BITFEILD_ISOLATE(x, lsb_pos, length) ((x) & (BITFEILD_MASK((lsb_pos), (length))))
#define BITFEILD_EXCLUDE(x, lsb_pos, length) ((x) & ~(BITFEILD_MASK((lsb_pos), (length))))
#define BITFEILD_GET(y, lsb_pos, length) (((y)>>(lsb_pos)) & BIT_MASK(length))
#define BITFEILD_SET(y, x, lsb_pos, length) ( y= ((y) & ~BF_MASK(lsb_pos, length)) | BITFEILD_ISOLATE(x, lsb_pos, length))

View File

@ -1,77 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
/****************************************************************************
* Global Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: sched_yield()
*
* Description:
* This function should be called in situation were the cpu may be
* busy for a long time without interrupts or the ability to run code
* to insure that the timer based process will be run.
*
*
* Input Parameters:
* None
*
* Returned value:
* None
*
****************************************************************************/
#if defined(OPT_USE_YIELD)
void bl_sched_yield(void);
#else
# define bl_sched_yield()
#endif

View File

@ -1,151 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/*
* @file board.h
*
* bootloader board interface
* This file contains the common interfaces that all boards
* have to supply
*/
#pragma once
/************************************************************************************
* Included Files
************************************************************************************/
#include "uavcan.h"
#include <nuttx/compiler.h>
#include <stdint.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
typedef enum {
off,
reset,
autobaud_start,
autobaud_end,
allocation_start,
allocation_end,
fw_update_start,
fw_update_erase_fail,
fw_update_invalid_response,
fw_update_timeout,
fw_update_invalid_crc,
jump_to_app,
} uiindication_t;
/************************************************************************************
* Public data
************************************************************************************/
#ifndef __ASSEMBLY__
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/************************************************************************************
* Name: stm32_boarddeinitialize
*
* Description:
* This function is called by the bootloader code priore to booting
* the application. Is should place the HW into an benign initialized state.
*
************************************************************************************/
void stm32_boarddeinitialize(void);
/****************************************************************************
* Name: board_get_product_name
*
* Description:
* Called to retrive the product name. The retuned alue is a assumed
* to be written to a pascal style string that will be length prefixed
* and not null terminated
*
* Input Parameters:
* product_name - A pointer to a buffer to write the name.
* maxlen - The imum number of chatater that can be written
*
* Returned Value:
* The length of charaacters written to the buffer.
*
****************************************************************************/
uint8_t board_get_product_name(uint8_t *product_name, size_t maxlen);
/****************************************************************************
* Name: board_get_hardware_version
*
* Description:
* Called to retrieve the hardware version information. The function
* will first initialize the the callers struct to all zeros.
*
* Input Parameters:
* hw_version - A pointer to a uavcan_hardwareversion_t.
*
* Returned Value:
* Length of the unique_id
*
****************************************************************************/
size_t board_get_hardware_version(uavcan_HardwareVersion_t *hw_version);
/****************************************************************************
* Name: board_indicate
*
* Description:
* Provides User feedback to indicate the state of the bootloader
* on board specific hardware.
*
* Input Parameters:
* indication - A member of the uiindication_t
*
* Returned Value:
* None
*
****************************************************************************/
void board_indicate(uiindication_t indication);
#endif /* __ASSEMBLY__ */

View File

@ -1,246 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* Included Files
****************************************************************************/
#include "timer.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
typedef enum {
CanPayloadLength = 8,
} can_const_t;
typedef enum {
CAN_OK = 0,
CAN_BOOT_TIMEOUT,
CAN_ERROR
} can_error_t;
typedef enum {
CAN_UNKNOWN = 0,
CAN_125KBAUD = 1,
CAN_250KBAUD = 2,
CAN_500KBAUD = 3,
CAN_1MBAUD = 4
} can_speed_t;
typedef enum {
CAN_Mode_Normal = 0, // Bits 30 and 31 00
CAN_Mode_LoopBack = 1, // Bit 30: Loop Back Mode (Debug)
CAN_Mode_Silent = 2, // Bit 31: Silent Mode (Debug)
CAN_Mode_Silent_LoopBack = 3 // Bits 30 and 31 11
} can_mode_t;
/*
* Receive from FIFO 1 -- filters are configured to push the messages there,
* and there are send/receive functions called off the SysTick ISR so
* we partition the usage of the CAN hardware to avoid the same FIFOs/mailboxes
* as the rest of the application uses.
*/
typedef enum {
Fifo0 = 0,
MailBox0 = 0,
Fifo1 = 1,
MailBox1 = 1,
Fifo2 = 2,
MailBox2 = 2,
FifoNone = 3,
MailBoxNone = 3,
} can_fifo_mailbox_t;
/****************************************************************************
* Global Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: can_speed2freq
*
* Description:
* This function maps a can_speed_t to a bit rate in Hz
*
* Input Parameters:
* can_speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
*
* Returned value:
* Bit rate in Hz
*
****************************************************************************/
int can_speed2freq(can_speed_t speed);
/****************************************************************************
* Name: can_speed2freq
*
* Description:
* This function maps a frequency in Hz to a can_speed_t in the range
* CAN_125KBAUD to CAN_1MBAUD.
*
* Input Parameters:
* freq - Bit rate in Hz
*
* Returned value:
* A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
*
****************************************************************************/
can_speed_t can_freq2speed(int freq);
/****************************************************************************
* Name: can_tx
*
* Description:
* This function is called to transmit a CAN frame using the supplied
* mailbox. It will busy wait on the mailbox if not available.
*
* Input Parameters:
* message_id - The CAN message's EXID field
* length - The number of bytes of data - the DLC field
* message - A pointer to 8 bytes of data to be sent (all 8 bytes will be
* loaded into the CAN transmitter but only length bytes will
* be sent.
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
* mailbox.
*
* Returned value:
* The CAN_OK of the data sent or CAN_ERROR if a time out occurred
*
****************************************************************************/
uint8_t can_tx(uint32_t message_id, size_t length, const uint8_t *message,
uint8_t mailbox);
/****************************************************************************
* Name: can_rx
*
* Description:
* This function is called to receive a CAN frame from a supplied fifo.
* It does not block if there is not available, but returns 0
*
* Input Parameters:
* message_id - A pointer to return the CAN message's EXID field
* length - A pointer to return the number of bytes of data - the DLC field
* message - A pointer to return 8 bytes of data to be sent (all 8 bytes will
* be written from the CAN receiver but only length bytes will be sent.
* fifo A can_fifo_mailbox_t fifixxx value to choose the incoming fifo.
*
* Returned value:
* The length of the data read or 0 if the fifo was empty
*
****************************************************************************/
uint8_t can_rx(uint32_t *message_id, size_t *length, uint8_t *message,
uint8_t fifo);
/****************************************************************************
* Name: can_init
*
* Description:
* This function is used to initialize the CAN block for a given bit rate and
* mode.
*
* Input Parameters:
* speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
* mode - One of the can_mode_t of Normal, LoopBack and Silent or
* combination thereof.
*
* Returned value:
* OK - on Success or a negate errno value
*
****************************************************************************/
int can_init(can_speed_t speed, can_mode_t mode);
/****************************************************************************
* Name: can_autobaud
*
* Description:
* This function will attempt to detect the bit rate in use on the CAN
* interface until the timeout provided expires or the successful detection
* occurs.
*
* It will initialize the CAN block for a given bit rate
* to test that a message can be received. The CAN interface is left
* operating at the detected bit rate and in CAN_Mode_Normal mode.
*
* Input Parameters:
* can_speed - A pointer to return detected can_speed_t from CAN_UNKNOWN to
* CAN_1MBAUD
* timeout - The timer id of a timer to use as the maximum time to wait for
* successful bit rate detection. This timer may be not running
* in which case the auto baud code will try indefinitely to
* detect the bit rate.
*
* Returned value:
* CAN_OK - on Success or a CAN_BOOT_TIMEOUT
*
****************************************************************************/
int can_autobaud(can_speed_t *can_speed, bl_timer_id timeout);
/****************************************************************************
* Name: can_cancel_on_error
*
* Description:
* This function will test for transition completion or any error.
* If the is a error the the transmit will be aborted.
*
* Input Parameters:
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
* mailbox.
*
* Returned value:
* None
*
****************************************************************************/
void can_cancel_on_error(uint8_t mailbox);

View File

@ -1,106 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Public Type Definitions
****************************************************************************/
typedef enum {
FLASH_OK = 0,
FLASH_ERROR,
FLASH_ERASE_ERROR,
FLASH_ERASE_VERIFY_ERROR,
FLASH_ERROR_SUICIDE,
FLASH_ERROR_AFU,
} flash_error_t;
/****************************************************************************
* Global Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: bl_flash_erase
*
* Description:
* This function erases the flash starting at address and ending at
* address + nbytes.
*
* Input Parameters:
* address - A word-aligned address within the first page of flash to erase
* nbytes - The number of bytes to erase, rounding up to the next page.
*
*
*
* Returned value:
* On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
flash_error_t bl_flash_erase(size_t address, size_t nbytes);
/****************************************************************************
* Name: bl_flash_write
*
* Description:
* This function writes the flash starting at the given address
*
* Input Parameters:
* flash_address - The address of the flash to write
* must be word aligned
* data - A pointer to a buffer count bytes to be written
* to the flash.
* count - Number of bytes to write
*
* Returned value:
* On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
flash_error_t bl_flash_write(uint32_t flash_address, uint8_t *data, ssize_t count);

View File

@ -1,92 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/****************************************************************************
* Included Files
****************************************************************************/
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define CRC16_INITIAL 0xFFFFu
#define CRC16_OUTPUT_XOR 0x0000u
#define CRC64_INITIAL 0xFFFFFFFFFFFFFFFFull
#define CRC64_OUTPUT_XOR 0xFFFFFFFFFFFFFFFFull
/****************************************************************************
* Public Type Definitions
****************************************************************************/
/****************************************************************************
* Global Variables
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: util_srand
*
* Description:
* This function seeds the random number generator
*
*
* Input Parameters:
* seed - The seed
*
* Returned value:
* None
*
****************************************************************************/
void util_srand(uint16_t seed);
/****************************************************************************
* Name: util_random
*
* Description:
* This function returns a random number between min and max
*
*
* Input Parameters:
* min - The minimum value the return value can be.
* max - The maximum value the return value can be.
*
* Returned value:
* A random number
*
****************************************************************************/
uint16_t util_random(uint16_t min, uint16_t max);

View File

@ -1,451 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/*
* We support two classes of timer interfaces. The first one is for structured
* timers that have an API for life cycle management and use. (timer_xx)
* The Second type of methods are for interfacing to a high resolution
* counter with fast access and are provided via an in line API (timer_hrt)
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <stdbool.h>
#include <stdint.h>
#include "stm32.h"
#include "nvic.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define TIMER_HRT_CYCLES_PER_US (STM32_HCLK_FREQUENCY/1000000)
#define TIMER_HRT_CYCLES_PER_MS (STM32_HCLK_FREQUENCY/1000)
/****************************************************************************
* Public Type Definitions
****************************************************************************/
/* Types for timer access */
typedef uint8_t bl_timer_id; /* A timer handle */
typedef uint32_t time_ms_t; /* A timer value */
typedef volatile time_ms_t *time_ref_t; /* A pointer to the internal
counter in the structure of a timer
used to do a time out test value */
typedef uint32_t time_hrt_cycles_t; /* A timer value type of the hrt */
/*
* Timers
*
* There are 3 modes of operation for the timers.
* All modes support a call back on expiration.
*
*/
typedef enum {
/* Specifies a one-shot timer. After notification timer is discarded. */
modeOneShot = 1,
/* Specifies a repeating timer. */
modeRepeating = 2,
/* Specifies a persistent start / stop timer. */
modeTimeout = 3,
/* Or'ed in to start the timer when allocated */
modeStarted = 0x40
} bl_timer_modes_t;
/* The call back function signature type */
typedef void (*bl_timer_ontimeout)(bl_timer_id id, void *context);
/*
* A helper type for timer allocation to setup a callback
* There is a null_cb object (see below) that can be used to
* a bl_timer_cb_t.
*
* Typical usage is:
*
* void my_process(bl_timer_id id, void *context) {
* ...
* };
*
* bl_timer_cb_t mycallback = null_cb;
* mycallback.cb = my_process;
* bl_timer_id mytimer = timer_allocate(modeRepeating|modeStarted, 100, &mycallback);
*/
typedef struct {
void *context;
bl_timer_ontimeout cb;
} bl_timer_cb_t;
/****************************************************************************
* Global Variables
****************************************************************************/
extern const bl_timer_cb_t null_cb;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: timer_init
*
* Description:
* Called early in os_start to initialize the data associated with
* the timers
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
void timer_init(void);
/****************************************************************************
* Name: timer_allocate
*
* Description:
* Is used to allocate a timer. Allocation does not involve memory
* allocation as the data for the timer are compile time generated.
* See OPT_BL_NUMBER_TIMERS
*
* There is an inherent priority to the timers in that the first timer
* allocated is the first timer run per tick.
*
* There are 3 modes of operation for the timers. All modes support an
* optional call back on expiration.
*
* modeOneShot - Specifies a one-shot timer. After notification timer
* is resource is freed.
* modeRepeating - Specifies a repeating timer that will reload and
* call an optional.
* modeTimeout - Specifies a persistent start / stop timer.
*
* modeStarted - Or'ed in to start the timer when allocated
*
*
* Input Parameters:
* mode - One of bl_timer_modes_t with the Optional modeStarted
* msfromnow - The reload and initial value for the timer in Ms.
* fc - A pointer or NULL (0). If it is non null it can be any
* of the following:
*
* a) A bl_timer_cb_t populated on the users stack or
* in the data segment. The values are copied into the
* internal data structure of the timer and therefore do
* not have to persist after the call to timer_allocate
*
* b) The address of null_cb. This is identical to passing
* null for the value of fc.
*
* Returned Value:
* On success a value from 0 - OPT_BL_NUMBER_TIMERS-1 that is
* the bl_timer_id for subsequent timer operations
* -1 on failure. This indicates there are no free timers.
*
****************************************************************************/
bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow,
bl_timer_cb_t *fc);
/****************************************************************************
* Name: timer_free
*
* Description:
* Is used to free a timer. Freeing a timer does not involve memory
* deallocation as the data for the timer are compile time generated.
* See OPT_BL_NUMBER_TIMERS
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_free(bl_timer_id id);
/****************************************************************************
* Name: timer_start
*
* Description:
* Is used to Start a timer. The reload value is copied to the counter.
* And the running bit it set. There is no problem in Starting a running
* timer. But it will restart the timeout.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_start(bl_timer_id id);
/****************************************************************************
* Name: timer_restart
*
* Description:
* Is used to re start a timer with a new reload count. The reload value
* is copied to the counter and the running bit it set. There is no
* problem in restarting a running timer.
*
* Input Parameters:
* id - Returned from timer_allocate;
* ms - Is a time_ms_t and the new reload value to use.
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_restart(bl_timer_id id, time_ms_t ms);
/****************************************************************************
* Name: timer_stop
*
* Description:
* Is used to stop a timer. It is Ok to stop a stopped timer.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_stop(bl_timer_id id);
/****************************************************************************
* Name: timer_expired
*
* Description:
* Test if a timer that was configured as a modeTimeout timer is expired.
* To be expired the time has to be running and have a count of 0.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* No Zero if the timer is expired otherwise zero.
*
****************************************************************************/
int timer_expired(bl_timer_id id);
/****************************************************************************
* Name: timer_ref
*
* Description:
* Returns an time_ref_t that is a reference (pointer) to the internal counter
* of the timer selected by id. It should only be used with calls to
* timer_ref_expired.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* An internal reference that should be treated as opaque by the caller and
* should only be used with calls to timer_ref_expired.
* There is no reference counting on the reference and therefore does not
* require any operation to free it.
*
****************************************************************************/
time_ref_t timer_ref(bl_timer_id id);
/****************************************************************************
* Name: timer_ref_expired
*
* Description:
* Test if a timer, that was configured as a modeTimeout timer is expired
* based on the reference provided.
*
* Input Parameters:
* ref - Returned timer_ref;
*
* Returned Value:
* Non Zero if the timer is expired otherwise zero.
*
****************************************************************************/
static inline int timer_ref_expired(time_ref_t ref)
{
return *ref == 0;
}
/****************************************************************************
* Name: timer_tic
*
* Description:
* Returns the system tic counter that counts in units of
* (CONFIG_USEC_PER_TICK/1000). By default 10 Ms.
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
time_ms_t timer_tic(void);
/****************************************************************************
* Name: timer_hrt_read
*
* Description:
* Returns the hardware SysTic counter that counts in units of
* STM32_HCLK_FREQUENCY. This file defines TIMER_HRT_CYCLES_PER_US
* and TIMER_HRT_CYCLES_PER_MS that should be used to define times.
*
* Input Parameters:
* None
*
* Returned Value:
* The current value of the HW counter in the type of time_hrt_cycles_t.
*
****************************************************************************/
static inline time_hrt_cycles_t timer_hrt_read(void)
{
return getreg32(NVIC_SYSTICK_CURRENT);
}
/****************************************************************************
* Name: timer_hrt_clear_wrap
*
* Description:
* Clears the wrap flag by reading the timer
*
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
static inline void timer_hrt_clear_wrap(void)
{
(void)timer_hrt_read();
}
/****************************************************************************
* Name: timer_hrt_wrap
*
* Description:
* Returns true if SysTic counted to 0 since last time it was
* read.
*
* Input Parameters:
* None
*
* Returned Value:
* Returns true if timer counted to 0 since last time this was read.
*
****************************************************************************/
static inline bool timer_hrt_wrap(void)
{
uint32_t rv = getreg32(NVIC_SYSTICK_CTRL);
return ((rv & NVIC_SYSTICK_CTRL_COUNTFLAG) ? true : false);
}
/****************************************************************************
* Name: timer_hrt_max
*
* Description:
* Returns the hardware SysTic reload value +1
*
* Input Parameters:
* None
*
* Returned Value:
* The current SysTic reload of the HW counter in the type of
* time_hrt_cycles_t.
*
****************************************************************************/
static inline time_hrt_cycles_t timer_hrt_max(void)
{
return getreg32(NVIC_SYSTICK_RELOAD) + 1;
}
/****************************************************************************
* Name: timer_hrt_elapsed
*
* Description:
* Returns the difference between 2 time values, taking into account
* the way the timer wrap.
*
* Input Parameters:
* begin - Beginning timer count.
* end - Ending timer count.
*
* Returned Value:
* The difference from begin to end
*
****************************************************************************/
static inline time_hrt_cycles_t timer_hrt_elapsed(time_hrt_cycles_t begin, time_hrt_cycles_t end)
{
/* It is a down count from NVIC_SYSTICK_RELOAD */
time_hrt_cycles_t elapsed = begin - end;
time_hrt_cycles_t reload = timer_hrt_max();
/* Did it wrap */
if (elapsed > reload) {
elapsed += reload;
}
return elapsed;
}

View File

@ -1,841 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
#pragma once
/*
* Uavcan protocol CAN ID formats and Tail byte component definitions
*
* Most all the constants below are auto generated by the compiler in the
* section above.
* For all UAVCAN_BIT_DEFINE({item name}, lsb_pos, length) entries
* it defines the following enumeration constants:
*
* Mask{item name} - The mask that is positioned at the lsb and
* length long
* BitPos{item name} - The bit position of the lsb
* Length{item name} - The number of bits in the field
*
*
* For the UAVCAN_DSDL_TYPE_DEF(name, dtid, service, signature, packsize,
* mailbox, fifo, inbound, outbound)
* it defines:
*
* uavcan dtid definitions are in the form nnnn.type_name.uavcan
*
* DSDL{type_name} - An internal zero based ID for the transfer
* format E.G DSDLNodeInfo would return the internal
* constant index derived from the line that
* UAVCAN_DSDL_TYPE_DEF(GetNodeInfo... is defined on
* in uavcan_dsdl_defs.h (as of this writing it would
* be the value 1)
*
* DTID{type_name} - The uavcan Number nnn.name E.G DTIDNodeInfo
*
* ServiceNotMessage{type_name} - True for DTID that are uavcan Services Type
* Defined Transfer Type
*
* SignatureCRC16{type_name} - Required for multi-frame Transfer Type
*
* PackedSize{type_name} - The packed size of the Transfer Type
*
* MailBox{type_name} - When sending this Transfer Type, use this
* mailbox
*
* Fifo{type_name} - When receiving this Transfer Type, use this
* fifo. - Filers need to be configured
*
* Fifo{type_name} - The uavcan Number nnn.name E.G DTIDNodeInfo
*
* InTailInit{type_name} - The value of the tail byte to expect at
* the end of a transfer
*
* OutTailInit{type_name} - The value of the tail byte to to use when
* sending this transfer
*
* For all UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length)
* it defines the following enumeration constants:
*
* Mask{item name} - The mask that is positioned at the lsb and
* length long
* BitPos{item name} - The bit position of the lsb
* Length{item name} - The number of bits in the field
* PayloadOffset{<name><field_name>} - The offset in the payload
* PayloadLength{<name><field_name>} - The number of bytes
*
*/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/compiler.h>
#include <stdint.h>
#include <stdbool.h>
#include <stdlib.h>
#include "bitminip.h"
#include "can.h"
#include "systemlib/px4_macros.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define sizeof_member(t, m) sizeof(((t *)0)->m)
#define UAVCAN_STRLEN(x) sizeof((x))-1
#define uavcan_exclude(x, name) BITFEILD_EXCLUDE((x), BitPos##name,Length##name)
#define uavcan_make_uint16(d0, d1) (uint16_t)(((d1) << 8u) | (d0))
#define uavcan_dsdl_field(op, data_typ_name, field_name) (op##data_typ_name##field_name)
#define uavcan_bit_pos(data_typ_name, field_name) uavcan_dsdl_field(BitPos, data_typ_name, field_name)
#define uavcan_bit_mask(data_typ_name, field_name) uavcan_dsdl_field(Mask, data_typ_name, field_name)
#define uavcan_bit_count(data_typ_name, field_name) uavcan_dsdl_field(Length, data_typ_name, field_name)
#define uavcan_byte_offset(data_typ_name, field_name) uavcan_dsdl_field(PayloadOffset, data_typ_name, field_name)
#define uavcan_byte_count(data_typ_name, field_name) uavcan_dsdl_field(PayloadLength, data_typ_name, field_name)
#define uavcan_pack(d, data_typ_name, field_name) \
(((d) << uavcan_bit_pos(data_typ_name, field_name)) & uavcan_bit_mask(data_typ_name, field_name))
#define uavcan_ppack(d, data_typ_name, field_name) uavcan_pack(d->field_name, data_typ_name, field_name)
#define uavcan_rpack(d, data_typ_name, field_name) uavcan_pack(d.field_name, data_typ_name, field_name)
#define uavcan_unpack(d, data_typ_name, field_name) \
(((d) & uavcan_bit_mask(data_typ_name, field_name)) >> uavcan_bit_pos(data_typ_name, field_name))
#define uavcan_punpack(d, data_typ_name, field_name) uavcan_unpack(d->field_name, data_typ_name, field_name)
#define uavcan_runpack(d, data_typ_name, field_name) uavcan_unpack(d.field_name, data_typ_name, field_name)
#define uavcan_protocol_mask(field_name) (Mask##field_name)
/****************************************************************************
* Auto Generated Public Type Definitions
****************************************************************************/
/* CAN ID fields */
#define UAVCAN_BIT_DEFINE(field_name, lsb_pos, length) Mask##field_name = BITFEILD_MASK((lsb_pos), (length)),
typedef enum uavcan_can_id_mask_t {
#include "uavcan_can_id_defs.h"
} uavcan_can_id_mask_t;
#undef UAVCAN_BIT_DEFINE
#define UAVCAN_BIT_DEFINE(field_name, lsb_pos, length) BitPos##field_name = (lsb_pos),
typedef enum uavcan_can_id_pos_t {
#include "uavcan_can_id_defs.h"
} uavcan_can_id_pos_t;
#undef UAVCAN_BIT_DEFINE
#define UAVCAN_BIT_DEFINE(field_name, lsb_pos, length) Length##field_name = (length),
typedef enum uavcan_can_id_length_t {
#include "uavcan_can_id_defs.h"
} uavcan_can_id_length_t;
#undef UAVCAN_BIT_DEFINE
/****************************************************************************
* Public Type Definitions
****************************************************************************/
typedef enum uavcan_direction_t {
InBound = true,
OutBound = false,
MessageIn = InBound,
MessageOut = OutBound,
} uavcan_direction_t;
/*
* Uavcan protocol CAN ID formats and Tail byte component definitions
*
* Most all the constants below are auto generated by the compiler in the
* section above.
* It defines Mask{item name}, BitPos{item name} and Length{item name}
* for all UAVCAN_BIT_DEFINE({item name}, lsb_pos, length) entries
*
* [CAN ID[4]][data[0-7][tail[1]]]
*
*/
/* General UAVCAN Constants */
typedef enum uavcan_general_t {
UavcanPriorityMax = 0,
UavcanPriorityMin = 31,
} uavcan_general_t;
/* CAN ID definitions for native data manipulation */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wattributes"
#pragma GCC diagnostic ignored "-Wpacked"
typedef begin_packed_struct struct can_id_t {
union {
uint32_t u32;
uint8_t b[sizeof(uint32_t)];
};
} end_packed_struct can_id_t;
/* UAVCAN CAN ID Usage: Message definition */
typedef struct uavcan_message_t {
uint32_t source_node_id : LengthUavCanMessageSourceNodeID;
uint32_t service_not_message : LengthUavCanMessageServiceNotMessage;
uint32_t type_id : LengthUavCanMessageTypeID;
uint32_t priority : LengthUavCanMessagePriority;
} uavcan_message_t;
/* UAVCAN CAN ID Usage: Anonymous Message Constants */
typedef enum uavcan_anon_const_t {
UavcanAnonymousNodeID = 0,
} uavcan_anon_const_t;
/* UAVCAN CAN ID Usage: Anonymous Message definition */
typedef struct uavcan_anonymous_message_t {
uint32_t source_node_id : LengthUavCanAnonMessageSourceNodeID;
uint32_t service_not_message : LengthUavCanAnonMessageServiceNotMessage;
uint32_t type_id : LengthUavCanAnonMessageTypeID;
uint32_t discriminator : LengthUavCanAnonMessageDiscriminator;
uint32_t priority : LengthUavCanAnonMessagePriority;
} uavcan_anonymous_message_t;
/* UAVCAN CAN ID Usage: Service Constants */
typedef enum uavcan_service_const_t {
UavcanServiceRetries = 3,
UavcanServiceTimeOutMs = 1000,
} uavcan_service_const_t;
/* UAVCAN CAN ID Usage: Service definition */
typedef struct uavcan_service_t {
uint32_t source_node_id : LengthUavCanServiceSourceNodeID;
uint32_t service_not_message : LengthUavCanServiceServiceNotMessage;
uint32_t dest_node_id : LengthUavCanServiceDestinationNodeID;
uint32_t request_not_response : LengthUavCanServiceRequestNotResponse;
uint32_t type_id : LengthUavCanServiceTypeID;
uint32_t priority : LengthUavCanServicePriority;
} uavcan_service_t;
/* UAVCAN Tail Byte definitions for native data manipulation */
#pragma GCC diagnostic push
#pragma GCC diagnostic ignored "-Wpacked"
typedef begin_packed_struct struct can_tail_t {
union {
uint8_t u8;
};
} end_packed_struct can_tail_t;
#pragma GCC diagnostic pop
/* UAVCAN Tail Byte definitions */
typedef struct uavcan_tail_t {
uint8_t transfer_id : LengthUavCanTransferID;
uint8_t toggle : LengthUavCanToggle;
uint8_t eot : LengthUavCanEndOfTransfer;
uint8_t sot : LengthUavCanStartOfTransfer;
} uavcan_tail_t;
/* UAVCAN Tail Byte Initialization constants */
typedef enum uavcan_tail_init_t {
SingleFrameTailInit = (MaskUavCanStartOfTransfer | MaskUavCanEndOfTransfer),
MultiFrameTailInit = (MaskUavCanStartOfTransfer),
BadTailState = (MaskUavCanStartOfTransfer | MaskUavCanToggle),
MaxUserPayloadLength = CanPayloadLength - sizeof(uavcan_tail_t),
} uavcan_tail_init_t;
/*
* Assert that assumptions in code are true
* The code assumes it can manipulate a ALL sub protocol objects
* using MaskUavCanMessageServiceNotMessage, MaskUavCanMessagePriority
* and MaskUavCanMessageSourceNodeID
*/
CCASSERT(MaskUavCanServicePriority == MaskUavCanAnonMessagePriority);
CCASSERT(MaskUavCanServicePriority == MaskUavCanMessagePriority);
CCASSERT(MaskUavCanServiceSourceNodeID == MaskUavCanAnonMessageSourceNodeID);
CCASSERT(MaskUavCanServiceSourceNodeID == MaskUavCanMessageSourceNodeID);
CCASSERT(MaskUavCanMessageServiceNotMessage == MaskUavCanAnonMessageServiceNotMessage);
CCASSERT(MaskUavCanMessageServiceNotMessage == MaskUavCanMessageServiceNotMessage);
/****************************************************************************
* Auto Generated Public Type Definitions
****************************************************************************/
/* UAVCAN DSDL Type Definitions*/
#define NA 0
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length)
#define UAVCAN_DSDL_MESG_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
UAVCAN_DSDL_TYPE_DEF(Msg##name, (dtid), (signature), (packsize), (mailbox), (fifo), (inbound), (outbound))
#define UAVCAN_DSDL_SREQ_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
UAVCAN_DSDL_TYPE_DEF(Req##name, (dtid), (signature), (packsize), (mailbox), (fifo), (inbound), (outbound))
#define UAVCAN_DSDL_SRSP_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
UAVCAN_DSDL_TYPE_DEF(Rsp##name, (dtid), (signature), (packsize), (mailbox), (fifo), (inbound), (outbound))
#define END_COMPONENTS SizeDSDLComponents,
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
DSDL##name,
typedef enum uavcan_dsdl_t {
#include "uavcan_dsdl_defs.h"
SizeDSDL,
} uavcan_dsdl_t;
#undef UAVCAN_DSDL_TYPE_DEF
#undef END_COMPONENTS
#define END_COMPONENTS
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length)
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
DTID##name = (dtid),
typedef enum uavcan_dsdl_dtid_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_dtid_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
SignatureCRC16##name = (signature),
typedef enum uavcan_dsdl_sig_crc16_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_sig_crc16_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
PackedSize##name = (packsize),
typedef enum uavcan_dsdl_packedsize_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_packedsize_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
MailBox##name = (mailbox),
typedef enum uavcan_dsdl_mb_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_mb_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
Fifo##name = (fifo),
typedef enum uavcan_dsdl_fifo_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_fifo_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
InTailInit##name = (inbound),
typedef enum uavcan_dsdl_inbound_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_inbound_t;
#undef UAVCAN_DSDL_TYPE_DEF
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
OutTailInit##name = (outbound),
typedef enum uavcan_dsdl_outbound_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_outbound_t;
#undef UAVCAN_DSDL_TYPE_DEF
#undef UAVCAN_DSDL_SRSP_DEF
#undef UAVCAN_DSDL_SREQ_DEF
#undef UAVCAN_DSDL_MESG_DEF
#undef UAVCAN_DSDL_BIT_DEF
/* UAVCAN DSDL Fields of Type Definitions definitions*/
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound)
#define UAVCAN_DSDL_MESG_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound)
#define UAVCAN_DSDL_SREQ_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound)
#define UAVCAN_DSDL_SRSP_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound)
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) \
Mask##data_typ_name##field_name = BITFEILD_MASK((lsb_pos), (length)),
typedef enum uavcan_dsdl_mask_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_mask_t;
#undef UAVCAN_DSDL_BIT_DEF
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) \
BitPos##data_typ_name##field_name = (lsb_pos),
typedef enum uavcan_dsdl_pos_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_pos_t;
#undef UAVCAN_DSDL_BIT_DEF
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) \
Length##data_typ_name##field_name = (length),
typedef enum uavcan_dsdl_length_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_length_t;
#undef UAVCAN_DSDL_BIT_DEF
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) \
PayloadOffset##data_typ_name##field_name = (payload_offset),
typedef enum uavcan_dsdl_payload_offset_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_payload_offset_t;
#undef UAVCAN_DSDL_BIT_DEF
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) \
PayloadLength##data_typ_name##field_name = (payload_length),
typedef enum uavcan_dsdl_payload_length_t {
#include "uavcan_dsdl_defs.h"
} uavcan_dsdl_payload_length_t;
#undef UAVCAN_DSDL_TYPE_DEF
#undef UAVCAN_DSDL_SRSP_DEF
#undef UAVCAN_DSDL_SREQ_DEF
#undef UAVCAN_DSDL_MESG_DEF
#undef UAVCAN_DSDL_BIT_DEF
#undef END_COMPONENTS
#undef NA
/****************************************************************************
* Public Type Definitions
****************************************************************************/
/* Uavcan function return values */
typedef enum uavcan_error_t {
UavcanOk = 0,
UavcanBootTimeout = 1,
UavcanError = 3
} uavcan_error_t;
/*
* Uavcan protocol CAN ID formats and Tail byte
*
* [CAN ID[4]][data[0-7][tail[1]]]
*
*/
typedef begin_packed_struct struct uavcan_protocol_t {
union {
can_id_t id;
uavcan_message_t msg;
uavcan_anonymous_message_t ana;
uavcan_service_t ser;
};
union {
can_tail_t tail_init;
uavcan_tail_t tail;
};
} end_packed_struct uavcan_protocol_t;
/*
* Uavcan protocol DSDL Type Definitions
*/
/****************************************
* Uavcan NodeStatus
****************************************/
typedef enum uavcan_NodeStatusConsts_t {
MAX_BROADCASTING_PERIOD_MS = 1000,
MIN_BROADCASTING_PERIOD_MS = 2,
OFFLINE_TIMEOUT_MS = 2000,
HEALTH_OK = 0,
HEALTH_WARNING = 1,
HEALTH_ERROR = 2,
HEALTH_CRITICAL = 3,
MODE_OPERATIONAL = 0,
MODE_INITIALIZATION = 1,
MODE_MAINTENANCE = 2,
MODE_SOFTWARE_UPDATE = 3,
MODE_OFFLINE = 7,
} uavcan_NodeStatusConsts_t;
typedef begin_packed_struct struct uavcan_NodeStatus_t {
uint32_t uptime_sec;
union {
uint8_t u8;
struct {
uint8_t sub_mode: LengthNodeStatussub_mode;
uint8_t mode : LengthNodeStatusmode;
uint8_t health : LengthNodeStatushealth;
};
};
uint16_t vendor_specific_status_code;
} end_packed_struct uavcan_NodeStatus_t;
/****************************************
* Uavcan GetNodeInfo composition
****************************************/
/* SoftwareVersion */
typedef enum uavcan_SoftwareVersionConsts_t {
OPTIONAL_FIELD_FLAG_VCS_COMMIT = 1,
OPTIONAL_FIELD_FLAG_IMAGE_CRC = 2,
} uavcan_SoftwareVersionConsts_t;
typedef begin_packed_struct struct uavcan_SoftwareVersion_t {
uint8_t major;
uint8_t minor;
uint8_t optional_field_flags;
uint32_t vcs_commit;
uint64_t image_crc;
} end_packed_struct uavcan_SoftwareVersion_t;
CCASSERT(PackedSizeSoftwareVersion == sizeof(uavcan_SoftwareVersion_t));
/* HardwareVersion */
typedef begin_packed_struct struct uavcan_HardwareVersion_t {
uint8_t major;
uint8_t minor;
uint8_t unique_id[PayloadLengthHardwareVersionunique_id];
uint8_t certificate_of_authenticity_length;
uint8_t certificate_of_authenticity[PayloadLengthHardwareVersioncertificate_of_authenticity];
} end_packed_struct uavcan_HardwareVersion_t;
typedef enum uavcan_HardwareVersionConsts_t {
FixedSizeHardwareVersion = sizeof_member(uavcan_HardwareVersion_t, major) + \
sizeof_member(uavcan_HardwareVersion_t, minor) + \
sizeof_member(uavcan_HardwareVersion_t, unique_id) + \
sizeof_member(uavcan_HardwareVersion_t, certificate_of_authenticity_length),
} uavcan_HardwareVersionConsts_t;
typedef begin_packed_struct struct uavcan_GetNodeInfo_request_t {
uint8_t empty[CanPayloadLength];
} end_packed_struct uavcan_GetNodeInfo_request_t;
/* GetNodeInfo Response */
typedef begin_packed_struct struct uavcan_GetNodeInfo_response_t {
uavcan_NodeStatus_t nodes_status;
uavcan_SoftwareVersion_t software_version;
uavcan_HardwareVersion_t hardware_version;
uint8_t name[PayloadLengthGetNodeInfoname];
uint8_t name_length;
} end_packed_struct uavcan_GetNodeInfo_response_t;
typedef enum uavcan_GetNodeInfoConsts_t {
FixedSizeGetNodeInfo = PackedSizeMsgNodeStatus + PackedSizeSoftwareVersion + FixedSizeHardwareVersion,
} uavcan_GetNodeInfoConsts_t;
/****************************************
* Uavcan LogMessage
****************************************/
typedef enum uavcan_LogMessageConsts_t {
LOGMESSAGE_LEVELDEBUG = 0,
LOGMESSAGE_LEVELINFO = 1,
LOGMESSAGE_LEVELWARNING = 2,
LOGMESSAGE_LEVELERROR = 3,
} uavcan_LogMessageConsts_t;
typedef begin_packed_struct struct uavcan_LogMessage_t {
uint8_t level;
uint8_t source[uavcan_byte_count(LogMessage, source)];
uint8_t text[uavcan_byte_count(LogMessage, text)];
} end_packed_struct uavcan_LogMessage_t;
CCASSERT(sizeof(uavcan_LogMessage_t) == PackedSizeMsgLogMessage);
/****************************************
* Uavcan Allocation
****************************************/
typedef enum uavcan_AllocationConsts_t {
MAX_REQUEST_PERIOD_MS = 1400,
MIN_REQUEST_PERIOD_MS = 600,
MAX_FOLLOWUP_DELAY_MS = 400,
MIN_FOLLOWUP_DELAY_MS = 0,
FOLLOWUP_TIMEOUT_MS = 500,
MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST = 6,
ANY_NODE_ID = 0,
PriorityAllocation = UavcanPriorityMin - 1,
} uavcan_AllocationConsts_t;
typedef begin_packed_struct struct uavcan_Allocation_t {
uint8_t node_id; /* bottom bit is the first part flag */
uint8_t unique_id[PayloadLengthAllocationunique_id];
} end_packed_struct uavcan_Allocation_t;
/****************************************
* Uavcan Path
****************************************/
typedef begin_packed_struct struct uavcan_Path_t {
uint8_t u8[PayloadLengthPathpath];
} uavcan_Path_t;
typedef enum uavcan_PathConst_t {
SEPARATOR = '/',
} end_packed_struct uavcan_PathConst_t;
/****************************************
* Uavcan GetInfo Composition
****************************************/
typedef enum uavcan_ErrorConst_t {
FILE_ERROR_OK = 0,
FILE_ERROR_UNKNOWN_ERROR = 32767,
FILE_ERROR_NOT_FOUND = 2,
FILE_ERROR_IO_ERROR = 5,
FILE_ERROR_ACCESS_DENIED = 13,
FILE_ERROR_IS_DIRECTORY = 21,
FILE_ERROR_INVALID_VALUE = 22,
FILE_ERROR_FILE_TOO_LARGE = 27,
FILE_ERROR_OUT_OF_SPACE = 28,
FILE_ERROR_NOT_IMPLEMENTED = 38,
} uavcan_ErrorConst_t;
typedef begin_packed_struct struct uavcan_Error_t {
uint16_t value;
} end_packed_struct uavcan_Error_t;
typedef enum uavcan_EntryTypeConst_t {
ENTRY_TYPE_FLAG_FILE = 1,
ENTRY_TYPE_FLAG_DIRECTORY = 2,
ENTRY_TYPE_FLAG_SYMLINK = 4,
ENTRY_TYPE_FLAG_READABLE = 8,
ENTRY_TYPE_FLAG_WRITEABLE = 16,
} uavcan_EntryTypeConst_t;
typedef begin_packed_struct struct uavcan_EntryType_t {
uint8_t flags;
} end_packed_struct uavcan_EntryType_t;
/****************************************
* Uavcan BeginFirmwareUpdate
****************************************/
typedef enum uavcan_BeginFirmwareUpdateConst_t {
ERROR_OK = 0,
ERROR_INVALID_MODE = 1,
ERROR_IN_PROGRESS = 2,
ERROR_UNKNOWN = 255,
} uavcan_BeginFirmwareUpdateConst_t;
typedef begin_packed_struct struct uavcan_BeginFirmwareUpdate_request {
uint8_t source_node_id;
uavcan_Path_t image_file_remote_path;
} end_packed_struct uavcan_BeginFirmwareUpdate_request;
typedef begin_packed_struct struct uavcan_BeginFirmwareUpdate_response {
uint8_t error;
} end_packed_struct uavcan_BeginFirmwareUpdate_response;
/****************************************
* Uavcan GetInfo
****************************************/
typedef begin_packed_struct struct uavcan_GetInfo_request_t {
uavcan_Path_t path;
} uavcan_GetInfo_request_t;
typedef enum uavcan_GetInfo_requestConst_t {
FixedSizeGetInfoRequest = 0,
} end_packed_struct uavcan_GetInfo_requestConst_t;
typedef begin_packed_struct struct uavcan_GetInfo_response_t {
uint32_t size;
uint8_t msbsize;
uavcan_Error_t error;
uavcan_EntryType_t entry_type;
} end_packed_struct uavcan_GetInfo_response_t;
/****************************************
* Uavcan Read Composition
****************************************/
typedef begin_packed_struct struct uavcan_Read_request_t {
uint32_t offset;
uint8_t msboffset;
uavcan_Path_t path;
} end_packed_struct uavcan_Read_request_t;
typedef enum uavcan_ReadRequestConsts_t {
FixedSizeReadRequest = sizeof_member(uavcan_Read_request_t, offset) + \
sizeof_member(uavcan_Read_request_t, msboffset),
} uavcan_ReadRequestConsts_t;
typedef begin_packed_struct struct uavcan_Read_response_t {
uavcan_Error_t error;
uint8_t data[PayloadLengthReaddata];
} end_packed_struct uavcan_Read_response_t;
/****************************************************************************
* Global Variables
****************************************************************************/
extern uint8_t g_this_node_id;
extern uint8_t g_server_node_id;
extern uint8_t g_uavcan_priority;
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/****************************************************************************
* Name: uavcan_pack_GetNodeInfo_response
*
* Description:
* This function packs the data of a uavcan_NodeStatus_t into
* a uavcan_GetNodeInfo_response_t structure as array of bytes.
* Then it packs the uavcan_GetNodeInfo_response_t
*
* Input Parameters:
* response The uavcan_GetNodeInfo_response_t to be packed
* node_status - The uavcan_NodeStatus_t that is part of the composition
*
* Returned value:
* Number of bytes written.
*
****************************************************************************/
size_t uavcan_pack_GetNodeInfo_response(uavcan_GetNodeInfo_response_t
*response);
/****************************************************************************
* Name: uavcan_tx_dsdl
*
* Description:
* This helper function sends a uavcan service protocol, it
* assumes the protocol object has the destination node id set.
*
* Input Parameters:
* dsdl - An Uavcan DSDL Identifier (Auto Generated)
* protocol - A pointer to a uavcan_protocol_t to configure the send,
* the transfer with the dest_node_id set to that of the
* node we are making the request of.
* transfer - A pointer to the packed data of the transfer to be sent.
* length - The number of bytes of data
*
* Returned value:
* The UavcanOk of the data sent. Anything else indicates if a timeout
* occurred.
*
****************************************************************************/
uavcan_error_t uavcan_tx_dsdl(uavcan_dsdl_t dsdl, uavcan_protocol_t *protocol,
const uint8_t *transfer, size_t transfer_length);
/****************************************************************************
* Name: uavcan_rx_dsdl
*
* Description:
* This function receives a uavcan Service response protocol transfer
*
* Input Parameters:
* dsdl - An Uavcan DSDL Identifier (Auto Generated)
* protocol - A pointer to a uavcan_protocol_t to configure the receive,
* based the dsdl for the DTID Service.
* If the request must come from a specific server
* then protocol->ser.source_node_id, should be set
* to that node id;
*
* in_out_transfer_length - The number of bytes of data to receive and the
* number received.
* timeout_ms - The amount of time in mS to wait for the initial transfer
*
* Returned value:
* None
*
****************************************************************************/
uavcan_error_t uavcan_rx_dsdl(uavcan_dsdl_t dsdl, uavcan_protocol_t *protocol,
uint8_t *transfer, size_t *in_out_transfer_length,
uint32_t timeout_ms);
/****************************************************************************
* Name: uavcan_tx_log_message
*
* Description:
* This functions sends uavcan LogMessage type data. The Source will be
* taken from the application defined debug_log_source
*
* Input Parameters:
* level - Log Level of the LogMessage Constants DEBUG, INFO, WARN, ERROR
* stage - The Stage the application is at. see Aplication defined
* LOGMESSAGE_STAGE_x
* status - The status of that stage. See Application defined
* LOGMESSAGE_RESULT_x
*
* Returned Value:
* None
*
****************************************************************************/
/* The application must define this */
extern const uint8_t debug_log_source[uavcan_byte_count(LogMessage, source)];
void uavcan_tx_log_message(uavcan_LogMessageConsts_t level, uint8_t stage,
uint8_t status);
/****************************************************************************
* Name: uavcan_tx_allocation_message
*
* Description:
* This function sends a uavcan allocation message.
*
* Input Parameters:
* requested_node_id - This node's preferred node id 0 for no preference.
* unique_id_length - This node's length of it's unique identifier.
* unique_id - A pointer to the bytes that represent unique
* identifier.
* unique_id_offset - The offset equal 0 or the number of bytes in the
* the last received message that matched the unique ID
* field.
* random - The value to use as the discriminator of the
* anonymous message
*
* Returned value:
* None
*
****************************************************************************/
void uavcan_tx_allocation_message(uint8_t requested_node_id,
size_t unique_id_length,
const uint8_t *unique_id,
uint8_t unique_id_offset,
uint16_t random);

View File

@ -1,66 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* This file not a typical h file, is defines the UAVCAN dsdl
* usage and may be included several times in header or source
* file
*/
/* UAVCAN_BIT_DEFINE( field_name, lsb_pos, length) */
/* Message Frame Format */
UAVCAN_BIT_DEFINE(UavCanMessagePriority, 24, 5)
UAVCAN_BIT_DEFINE(UavCanMessageTypeID, 8, 16)
UAVCAN_BIT_DEFINE(UavCanMessageServiceNotMessage, 7, 1)
UAVCAN_BIT_DEFINE(UavCanMessageSourceNodeID, 0, 7)
/* Anonymous message Frame Format */
UAVCAN_BIT_DEFINE(UavCanAnonMessagePriority, 24, 5)
UAVCAN_BIT_DEFINE(UavCanAnonMessageDiscriminator, 10, 14)
UAVCAN_BIT_DEFINE(UavCanAnonMessageTypeID, 8, 2)
UAVCAN_BIT_DEFINE(UavCanAnonMessageServiceNotMessage, 7, 1)
UAVCAN_BIT_DEFINE(UavCanAnonMessageSourceNodeID, 0, 7)
/* Service Frame Format */
UAVCAN_BIT_DEFINE(UavCanServicePriority, 24, 5)
UAVCAN_BIT_DEFINE(UavCanServiceTypeID, 16, 8)
UAVCAN_BIT_DEFINE(UavCanServiceRequestNotResponse, 15, 1)
UAVCAN_BIT_DEFINE(UavCanServiceDestinationNodeID, 8, 7)
UAVCAN_BIT_DEFINE(UavCanServiceServiceNotMessage, 7, 1)
UAVCAN_BIT_DEFINE(UavCanServiceSourceNodeID, 0, 7)
/* Tail Format */
UAVCAN_BIT_DEFINE(UavCanStartOfTransfer, 7, 1)
UAVCAN_BIT_DEFINE(UavCanEndOfTransfer, 6, 1)
UAVCAN_BIT_DEFINE(UavCanToggle, 5, 1)
UAVCAN_BIT_DEFINE(UavCanTransferID, 0, 5)

View File

@ -1,187 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/* This file not a typical h file, is defines the UAVCAN dsdl
* usage and may be included several times in header or source
* file
*/
/* Components */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(CRC, lsb, 0, 8, 0, 1)
UAVCAN_DSDL_BIT_DEF(CRC, msb, 0, 8, 1, 1)
UAVCAN_DSDL_BIT_DEF(CRC, data, 0, 8, 2, 4)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_TYPE_DEF(Path, 0, 0, 200, NA, NA,
NA, NA)
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(Path, path, 0, 8, 0,
200)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_TYPE_DEF(SoftwareVersion, 0, 0, 15, NA, NA,
NA, NA)
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(SoftwareVersion, major, 0, 8, 0,
1)
UAVCAN_DSDL_BIT_DEF(SoftwareVersion, minor, 0, 8, 1,
1)
UAVCAN_DSDL_BIT_DEF(SoftwareVersion, optional_field_flags, 0, 8, 2,
1)
UAVCAN_DSDL_BIT_DEF(SoftwareVersion, vcs_commit, 0, 32, 3,
4)
UAVCAN_DSDL_BIT_DEF(SoftwareVersion, image_crc, 0, NA, 7,
8) // NA becuase bit mask is 64
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_TYPE_DEF(HardwareVersion, 0, 0, NA, NA, NA,
NA, NA)
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(HardwareVersion, unique_id, 0, 8, 0,
16)
UAVCAN_DSDL_BIT_DEF(HardwareVersion, certificate_of_authenticity, 0, 8, 0,
255)
END_COMPONENTS
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_MESG_DEF(Allocation, 1, 0xf258, 0, MailBox0, Fifo0,
MultiFrameTailInit, SingleFrameTailInit) /* Message */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(Allocation, node_id, 1, 7, 0,
1)
UAVCAN_DSDL_BIT_DEF(Allocation, first_part_of_unique_id, 0, 1, 0,
1)
UAVCAN_DSDL_BIT_DEF(Allocation, unique_id, 0, 8, 1,
16)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_MESG_DEF(NodeStatus, 341, 0xbe5f, 7, MailBox1, FifoNone,
SingleFrameTailInit, SingleFrameTailInit) /* Message */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(NodeStatus, uptime_sec, 0, 32, 0,
4)
UAVCAN_DSDL_BIT_DEF(NodeStatus, health, 6, 2, 5,
1)
UAVCAN_DSDL_BIT_DEF(NodeStatus, mode, 3, 3, 5,
1)
UAVCAN_DSDL_BIT_DEF(NodeStatus, sub_mode, 0, 3, 5,
1)
UAVCAN_DSDL_BIT_DEF(NodeStatus, vendor_specific_status_code, 0, 16, 6,
2)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_SREQ_DEF(GetNodeInfo, 1, 0xd9a7, 0, MailBox1, Fifo1,
SingleFrameTailInit, MultiFrameTailInit) /* Request */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) Empty */
UAVCAN_DSDL_SRSP_DEF(GetNodeInfo, 1, 0xd9a7, 0, MailBox1, Fifo1,
SingleFrameTailInit, MultiFrameTailInit) /* Response */
UAVCAN_DSDL_BIT_DEF(GetNodeInfo, status, 0, 8, 0,
PackedSizeMsgNodeStatus)
UAVCAN_DSDL_BIT_DEF(GetNodeInfo, software_version, 0, 8, NA,
NA)
UAVCAN_DSDL_BIT_DEF(GetNodeInfo, hardware_version, 0, 8, NA,
NA)
UAVCAN_DSDL_BIT_DEF(GetNodeInfo, name, 0, 8, NA,
80)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_SREQ_DEF(BeginFirmwareUpdate, 40, 0x729e, 0, MailBox0, Fifo0,
MultiFrameTailInit, SingleFrameTailInit) /* Request */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(BeginFirmwareUpdate, source_node_id, 0, 8, 0,
1)
UAVCAN_DSDL_BIT_DEF(BeginFirmwareUpdate, image_file_remote_path, 0, 8, 1,
PayloadLengthPathpath)
UAVCAN_DSDL_SRSP_DEF(BeginFirmwareUpdate, 40, 0x729e, 0, MailBox0, Fifo0,
MultiFrameTailInit, SingleFrameTailInit) /* Response */
UAVCAN_DSDL_BIT_DEF(BeginFirmwareUpdate, error, 0, 8, 0,
1)
UAVCAN_DSDL_BIT_DEF(BeginFirmwareUpdate, optional_error_message, 0, 8, 1,
128)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_SREQ_DEF(GetInfo, 45, 0x14b9, 0, MailBox0, Fifo0,
SingleFrameTailInit, MultiFrameTailInit) /* Request */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(GetInfo, path, 0, 8, 0,
PayloadLengthPathpath)
UAVCAN_DSDL_SRSP_DEF(GetInfo, 45, 0x14b9, 0, MailBox0, Fifo0,
SingleFrameTailInit, MultiFrameTailInit) /* Response */
UAVCAN_DSDL_BIT_DEF(GetInfo, size, 0, 32, 0,
4) /* Response */
UAVCAN_DSDL_BIT_DEF(GetInfo, sizemsb, 0, 8, 4,
1)
UAVCAN_DSDL_BIT_DEF(GetInfo, error, 0, 16, 5,
2)
UAVCAN_DSDL_BIT_DEF(GetInfo, entry_type, 0, 8, 7,
1)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_SREQ_DEF(Read, 48, 0x2f12, 0, MailBox0, Fifo0,
SingleFrameTailInit, MultiFrameTailInit) /* Request */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(Read, offset, 0, 32, 0,
4) /* Request */
UAVCAN_DSDL_BIT_DEF(Read, msboffset, 0, 8, 4,
1)
UAVCAN_DSDL_BIT_DEF(Read, path, 0, 8, 5,
PayloadLengthPathpath)
UAVCAN_DSDL_SRSP_DEF(Read, 48, 0x2f12, 0, MailBox0, Fifo0,
SingleFrameTailInit, MultiFrameTailInit) // Responce
UAVCAN_DSDL_BIT_DEF(Read, error, 0, 16, 0,
2) /* Response */
UAVCAN_DSDL_BIT_DEF(Read, data, 0, 8, 2,
256)
/*UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packed size mailbox, fifo, inbound, outbound) */
UAVCAN_DSDL_MESG_DEF(LogMessage, 16383, 0x4570, 7, MailBox0, Fifo0,
NA, SingleFrameTailInit) /* Message */
/* UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length) */
UAVCAN_DSDL_BIT_DEF(LogMessage, level, 5, 3, 0,
1)
UAVCAN_DSDL_BIT_DEF(LogMessage, source_length, 0, 5, 0,
1)
UAVCAN_DSDL_BIT_DEF(LogMessage, source, 0, 8, 1,
4) // Bootloader specific uses is 4
UAVCAN_DSDL_BIT_DEF(LogMessage, text, 0, 8, 5,
2) // Bootloader specific uses is 2

View File

@ -1,616 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "boot_config.h"
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include <errno.h>
#include <limits.h>
#include "chip.h"
#include "stm32.h"
#include <chip/stm32_can.h>
#include "nvic.h"
#include "board.h"
#include "systemlib/px4_macros.h"
#include "can.h"
#include "crc.h"
#include "timer.h"
#include <arch/board/board.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define INAK_TIMEOUT 65535
#define CAN_TX_TIMEOUT_MS (200 /(1000/(1000000/CONFIG_USEC_PER_TICK)))
#define SJW_POS 24
#define BS1_POS 16
#define BS2_POS 20
#define CAN_TSR_RQCP_SHFTS 8
#define FILTER_ID 1
#define FILTER_MASK 2
#if STM32_PCLK1_FREQUENCY == 45000000 || STM32_PCLK1_FREQUENCY == 36000000
/* Sample 88.9 % */
# define QUANTA 9
# define BS1_VALUE 6
# define BS2_VALUE 0
#elif STM32_PCLK1_FREQUENCY == 42000000
/* Sample 85.7 % */
# define QUANTA 14
# define BS1_VALUE 10
# define BS2_VALUE 1
#else
# error Undefined QUANTA bsed on Clock Rate
#endif
#define CAN_1MBAUD_SJW 0
#define CAN_1MBAUD_BS1 BS1_VALUE
#define CAN_1MBAUD_BS2 BS2_VALUE
#define CAN_1MBAUD_PRESCALER (STM32_PCLK1_FREQUENCY/1000000/QUANTA)
#define CAN_500KBAUD_SJW 0
#define CAN_500KBAUD_BS1 BS1_VALUE
#define CAN_500KBAUD_BS2 BS2_VALUE
#define CAN_500KBAUD_PRESCALER (STM32_PCLK1_FREQUENCY/500000/QUANTA)
#define CAN_250KBAUD_SJW 0
#define CAN_250KBAUD_BS1 BS1_VALUE
#define CAN_250KBAUD_BS2 BS2_VALUE
#define CAN_250KBAUD_PRESCALER (STM32_PCLK1_FREQUENCY/250000/QUANTA)
#define CAN_125KBAUD_SJW 0
#define CAN_125KBAUD_BS1 BS1_VALUE
#define CAN_125KBAUD_BS2 BS2_VALUE
#define CAN_125KBAUD_PRESCALER (STM32_PCLK1_FREQUENCY/125000/QUANTA)
#define CAN_BTR_LBK_SHIFT 30
/*
* Number of CPU cycles for a single bit time at the supported speeds
*/
#define CAN_125KBAUD_BIT_CYCLES (8*(TIMER_HRT_CYCLES_PER_US))
#define CAN_BAUD_TIME_IN_MS 200
#define CAN_BAUD_SAMPLES_NEEDED 32
#define CAN_BAUD_SAMPLES_DISCARDED 8
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Name: read_msr_rx
****************************************************************************/
static inline uint32_t read_msr_rx(void)
{
return getreg32(STM32_CAN1_MSR) & CAN_MSR_RX;
}
/****************************************************************************
* Name: read_msr
****************************************************************************/
static uint32_t read_msr(time_hrt_cycles_t *now)
{
__asm__ __volatile__("\tcpsid i\n");
*now = timer_hrt_read();
uint32_t msr = read_msr_rx();
__asm__ __volatile__("\tcpsie i\n");
return msr;
}
/****************************************************************************
* Name: read_bits_times
****************************************************************************/
static int read_bits_times(time_hrt_cycles_t *times, size_t max)
{
uint32_t samplecnt = 0;
bl_timer_id ab_timer = timer_allocate(modeTimeout | modeStarted, CAN_BAUD_TIME_IN_MS, 0);
time_ref_t ab_ref = timer_ref(ab_timer);
uint32_t msr;
uint32_t last_msr = read_msr(times);
while (samplecnt < max && !timer_ref_expired(ab_ref)) {
do {
msr = read_msr(&times[samplecnt]);
} while (!(msr ^ last_msr) && !timer_ref_expired(ab_ref));
last_msr = msr;
samplecnt++;
}
timer_free(ab_timer);
return samplecnt;
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: can_speed2freq
*
* Description:
* This function maps a can_speed_t to a bit rate in Hz
*
* Input Parameters:
* can_speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
*
* Returned value:
* Bit rate in Hz
*
****************************************************************************/
int can_speed2freq(can_speed_t speed)
{
return 1000000 >> (CAN_1MBAUD - speed);
}
/****************************************************************************
* Name: can_speed2freq
*
* Description:
* This function maps a frequency in Hz to a can_speed_t in the range
* CAN_125KBAUD to CAN_1MBAUD.
*
* Input Parameters:
* freq - Bit rate in Hz
*
* Returned value:
* A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
*
****************************************************************************/
can_speed_t can_freq2speed(int freq)
{
return (freq == 1000000u ? CAN_1MBAUD : freq == 500000u ? CAN_500KBAUD : freq == 250000u ? CAN_250KBAUD : CAN_125KBAUD);
}
/****************************************************************************
* Name: can_tx
*
* Description:
* This function is called to transmit a CAN frame using the supplied
* mailbox. It will busy wait on the mailbox if not available.
*
* Input Parameters:
* message_id - The CAN message's EXID field
* length - The number of bytes of data - the DLC field
* message - A pointer to 8 bytes of data to be sent (all 8 bytes will be
* loaded into the CAN transmitter but only length bytes will
* be sent.
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
* mailbox.
*
* Returned value:
* The CAN_OK of the data sent or CAN_ERROR if a time out occurred
*
****************************************************************************/
uint8_t can_tx(uint32_t message_id, size_t length, const uint8_t *message,
uint8_t mailbox)
{
uint32_t data[2];
memcpy(data, message, sizeof(data));
/*
* Just block while waiting for the mailbox.
*/
uint32_t mask = CAN_TSR_TME0 << mailbox;
/* Reset the indication of timer expired */
timer_hrt_clear_wrap();
uint32_t cnt = CAN_TX_TIMEOUT_MS;
while ((getreg32(STM32_CAN1_TSR) & mask) == 0) {
if (timer_hrt_wrap()) {
timer_hrt_clear_wrap();
if (--cnt == 0) {
return CAN_ERROR;
}
}
}
/*
* To allow detection of completion - Set the LEC to
* 'No error' state off all 1s
*/
putreg32(CAN_ESR_LEC_MASK, STM32_CAN1_ESR);
putreg32(length & CAN_TDTR_DLC_MASK, STM32_CAN1_TDTR(mailbox));
putreg32(data[0], STM32_CAN1_TDLR(mailbox));
putreg32(data[1], STM32_CAN1_TDHR(mailbox));
putreg32((message_id << CAN_TIR_EXID_SHIFT) | CAN_TIR_IDE | CAN_TIR_TXRQ,
STM32_CAN1_TIR(mailbox));
return CAN_OK;
}
/****************************************************************************
* Name: can_rx
*
* Description:
* This function is called to receive a CAN frame from a supplied fifo.
* It does not block if there is not available, but returns 0
*
* Input Parameters:
* message_id - A pointer to return the CAN message's EXID field
* length - A pointer to return the number of bytes of data - the DLC field
* message - A pointer to return 8 bytes of data to be sent (all 8 bytes will
* be written from the CAN receiver but only length bytes will be sent.
* fifo A can_fifo_mailbox_t fifixxx value to choose the incoming fifo.
*
* Returned value:
* The length of the data read or 0 if the fifo was empty
*
****************************************************************************/
uint8_t can_rx(uint32_t *message_id, size_t *length, uint8_t *message,
uint8_t fifo)
{
uint32_t data[2];
uint8_t rv = 0;
const uint32_t fifos[] = { STM32_CAN1_RF0R, STM32_CAN1_RF1R };
if (getreg32(fifos[fifo & 1]) & CAN_RFR_FMP_MASK) {
rv = 1;
/* If so, process it */
*message_id = (getreg32(STM32_CAN1_RIR(fifo)) & CAN_RIR_EXID_MASK) >>
CAN_RIR_EXID_SHIFT;
*length = (getreg32(STM32_CAN1_RDTR(fifo)) & CAN_RDTR_DLC_MASK) >>
CAN_RDTR_DLC_SHIFT;
data[0] = getreg32(STM32_CAN1_RDLR(fifo));
data[1] = getreg32(STM32_CAN1_RDHR(fifo));
putreg32(CAN_RFR_RFOM, fifos[fifo & 1]);
memcpy(message, data, sizeof(data));
}
return rv;
}
/****************************************************************************
* Name: can_autobaud
*
* Description:
* This function will attempt to detect the bit rate in use on the CAN
* interface until the timeout provided expires or the successful detection
* occurs.
*
* It will initialize the CAN block for a given bit rate
* to test that a message can be received. The CAN interface is left
* operating at the detected bit rate and in CAN_Mode_Normal mode.
*
* Input Parameters:
* can_speed - A pointer to return detected can_speed_t from CAN_UNKNOWN to
* CAN_1MBAUD
* timeout - The timer id of a timer to use as the maximum time to wait for
* successful bit rate detection. This timer may be not running
* in which case the auto baud code will try indefinitely to
* detect the bit rate.
*
* Returned value:
* CAN_OK - on Success or a CAN_BOOT_TIMEOUT
*
****************************************************************************/
int can_autobaud(can_speed_t *can_speed, bl_timer_id timeout)
{
*can_speed = CAN_UNKNOWN;
volatile int attempt = 0;
/* Threshold are at 1.5 Bit times */
/*
* We are here because there was a reset or the app invoked
* the bootloader with no bit rate set.
*/
time_hrt_cycles_t bit_time;
time_hrt_cycles_t min_cycles;
int sample;
can_speed_t speed = CAN_125KBAUD;
time_hrt_cycles_t samples[128];
while (1) {
while (1) {
min_cycles = ULONG_MAX;
int samplecnt = read_bits_times(samples, arraySize(samples));
if (timer_expired(timeout)) {
return CAN_BOOT_TIMEOUT;
}
if ((getreg32(STM32_CAN1_RF0R) | getreg32(STM32_CAN1_RF1R)) &
CAN_RFR_FMP_MASK) {
*can_speed = speed;
can_init(speed, CAN_Mode_Normal);
return CAN_OK;
}
if (samplecnt < CAN_BAUD_SAMPLES_NEEDED) {
continue;
}
for (sample = 0; sample < samplecnt; sample += 2) {
bit_time = samples[sample] = timer_hrt_elapsed(samples[sample], samples[sample + 1]);
if (sample > CAN_BAUD_SAMPLES_DISCARDED && bit_time < min_cycles) {
min_cycles = bit_time;
}
}
break;
}
uint32_t bit34 = CAN_125KBAUD_BIT_CYCLES - CAN_125KBAUD_BIT_CYCLES / 4;
samples[1] = min_cycles;
speed = CAN_125KBAUD;
while (min_cycles < bit34 && speed < CAN_1MBAUD) {
speed++;
bit34 /= 2;
}
attempt++;
can_init(speed, CAN_Mode_Silent);
} /* while(1) */
return CAN_OK;
}
/****************************************************************************
* Name: can_init
*
* Description:
* This function is used to initialize the CAN block for a given bit rate and
* mode.
*
* Input Parameters:
* speed - A can_speed_t from CAN_125KBAUD to CAN_1MBAUD
* mode - One of the can_mode_t of Normal, LoopBack and Silent or
* combination thereof.
*
* Returned value:
* OK - on Success or a negate errno value
*
****************************************************************************/
int can_init(can_speed_t speed, can_mode_t mode)
{
int speedndx = speed - 1;
/*
* TODO: use full-word writes to reduce the number of loads/stores.
*
* Also consider filter use -- maybe set filters for all the message types we
* want. */
const uint32_t bitrates[] = {
(CAN_125KBAUD_SJW << SJW_POS) |
(CAN_125KBAUD_BS1 << BS1_POS) |
(CAN_125KBAUD_BS2 << BS2_POS) | (CAN_125KBAUD_PRESCALER - 1),
(CAN_250KBAUD_SJW << SJW_POS) |
(CAN_250KBAUD_BS1 << BS1_POS) |
(CAN_250KBAUD_BS2 << BS2_POS) | (CAN_250KBAUD_PRESCALER - 1),
(CAN_500KBAUD_SJW << SJW_POS) |
(CAN_500KBAUD_BS1 << BS1_POS) |
(CAN_500KBAUD_BS2 << BS2_POS) | (CAN_500KBAUD_PRESCALER - 1),
(CAN_1MBAUD_SJW << SJW_POS) |
(CAN_1MBAUD_BS1 << BS1_POS) |
(CAN_1MBAUD_BS2 << BS2_POS) | (CAN_1MBAUD_PRESCALER - 1)
};
/* Remove Unknow Offset */
if (speedndx < 0 || speedndx > (int)arraySize(bitrates)) {
return -EINVAL;
}
uint32_t timeout;
/*
* Reset state is 0x0001 0002 CAN_MCR_DBF|CAN_MCR_SLEEP
* knock down Sleep and raise CAN_MCR_INRQ
*/
putreg32(CAN_MCR_DBF | CAN_MCR_INRQ, STM32_CAN1_MCR);
/* Wait until initialization mode is acknowledged */
for (timeout = INAK_TIMEOUT; timeout > 0; timeout--) {
if ((getreg32(STM32_CAN1_MSR) & CAN_MSR_INAK) != 0) {
/* We are in initialization mode */
break;
}
}
if (timeout < 1) {
/*
* Initialization failed, not much we can do now other than try a normal
* startup. */
return -ETIME;
}
putreg32(bitrates[speedndx] | mode << CAN_BTR_LBK_SHIFT, STM32_CAN1_BTR);
putreg32(CAN_MCR_ABOM | CAN_MCR_AWUM | CAN_MCR_DBF | CAN_MCR_TXFP, STM32_CAN1_MCR);
for (timeout = INAK_TIMEOUT; timeout > 0; timeout--) {
if ((getreg32(STM32_CAN1_MSR) & CAN_MSR_INAK) == 0) {
/* We are in initialization mode */
break;
}
}
if (timeout < 1) {
return -ETIME;
}
/*
* CAN filter initialization -- accept everything on RX FIFO 0, and only
* GetNodeInfo requests on RX FIFO 1. */
/* Set FINIT - Initialization mode for the filters- */
putreg32(CAN_FMR_FINIT, STM32_CAN1_FMR);
putreg32(0, STM32_CAN1_FA1R); /* Disable all filters */
putreg32(3, STM32_CAN1_FS1R); /* Single 32-bit scale configuration for filters 0 and 1 */
/* Filter 0 masks -- DTIDGetNodeInfo requests only */
uavcan_protocol_t protocol;
protocol.id.u32 = 0;
protocol.ser.type_id = DTIDReqGetNodeInfo;
protocol.ser.service_not_message = true;
protocol.ser.request_not_response = true;
/* Set the Filter ID */
putreg32(protocol.id.u32 << CAN_RIR_EXID_SHIFT, STM32_CAN1_FIR(0, FILTER_ID));
/* Set the Filter Mask */
protocol.ser.type_id = BIT_MASK(LengthUavCanServiceTypeID);
putreg32(protocol.id.u32 << CAN_RIR_EXID_SHIFT, STM32_CAN1_FIR(0, FILTER_MASK));
/* Filter 1 masks -- everything is don't-care */
putreg32(0, STM32_CAN1_FIR(1, FILTER_ID));
putreg32(0, STM32_CAN1_FIR(1, FILTER_MASK));
putreg32(0, STM32_CAN1_FM1R); /* Mask mode for all filters */
putreg32(1, STM32_CAN1_FFA1R); /* FIFO 1 for filter 0, FIFO 0 for the
* rest of filters */
putreg32(3, STM32_CAN1_FA1R); /* Enable filters 0 and 1 */
/* Clear FINIT - Active mode for the filters- */
putreg32(0, STM32_CAN1_FMR);
return OK;
}
/****************************************************************************
* Name: can_cancel_on_error
*
* Description:
* This function will test for transition completion or any error.
* If the is a error the the transmit will be aborted.
*
* Input Parameters:
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
* mailbox.
*
* Returned value:
* CAN_OK - on Success or a CAN_ERROR if the cancellation was needed
*
****************************************************************************/
void can_cancel_on_error(uint8_t mailbox)
{
uint32_t rvalue;
/* Wait for completion the all 1's wat set in the tx code*/
while (CAN_ESR_LEC_MASK == ((rvalue = (getreg32(STM32_CAN1_ESR) & CAN_ESR_LEC_MASK))));
/* Any errors */
if (rvalue) {
putreg32(0, STM32_CAN1_ESR);
/* Abort the the TX in case of collision wuth NART false */
putreg32(CAN_TSR_ABRQ0 << (mailbox * CAN_TSR_RQCP_SHFTS), STM32_CAN1_TSR);
}
}

View File

@ -1,89 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2017 PX4 Development Team. All rights reserved.
* Author: David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
__EXPORT int __wrap_sem_wait(void *sem);
__EXPORT int __wrap_sem_post(void *sem);
/****************************************************************************
* Name: sem_wait and sem_post
*
* Description:
* These functions hijacks by the way of a compile time wrapper the systems
* sem_wait and sem_post functions.
*
****************************************************************************/
int __wrap_sem_wait(void *sem)
{
return 0;
}
int __wrap_sem_post(void *sem)
{
return 0;
}

View File

@ -1,177 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "boot_config.h"
#include <stdint.h>
#include <stdlib.h>
#include <nuttx/progmem.h>
#include "chip.h"
#include "stm32.h"
#include "flash.h"
#include "blsched.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: bl_flash_erase
*
* Description:
* This function erases the flash starting at address and ending at
* address + nbytes.
*
* Input Parameters:
* address - A word-aligned address within the first page of flash to erase
* nbytes - The number of bytes to erase, rounding up to the next page.
*
*
*
* Returned value:
* On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
flash_error_t bl_flash_erase(size_t address, size_t nbytes)
{
/*
* FIXME (?): this may take a long time, and while flash is being erased it
* might not be possible to execute interrupts, send NodeStatus messages etc.
* We can pass a per page callback or yeild */
flash_error_t status = FLASH_ERROR_AFU;
ssize_t bllastpage = up_progmem_getpage(address - 1);
if (bllastpage < 0) {
return FLASH_ERROR_AFU;
}
ssize_t appstartpage = up_progmem_getpage(address);
ssize_t appendpage = up_progmem_getpage(address + nbytes - 4);
if (appendpage < 0 || appstartpage < 0) {
return FLASH_ERROR_AFU;
}
status = FLASH_ERROR_SUICIDE;
if (bllastpage >= 0 && appstartpage > bllastpage) {
/* Erase the whole application flash region */
status = FLASH_OK;
while (status == FLASH_OK && appstartpage <= appendpage) {
bl_sched_yield();
ssize_t ps = up_progmem_erasepage(appstartpage++);
if (ps <= 0) {
status = FLASH_ERASE_ERROR;
}
}
}
return status;
}
/****************************************************************************
* Name: bl_flash_write
*
* Description:
* This function writes the flash starting at the given address
*
* Input Parameters:
* flash_address - The address of the flash to write
* must be word aligned
* data - A pointer to a buffer count bytes to be written
* to the flash.
* count - Number of bytes to write
*
* Returned value:
* On success FLASH_OK On Error one of the flash_error_t
*
****************************************************************************/
flash_error_t bl_flash_write(uint32_t flash_address, uint8_t *data, ssize_t count)
{
flash_error_t status = FLASH_ERROR;
if (flash_address >= APPLICATION_LOAD_ADDRESS &&
(flash_address + count) <= (uint32_t) APPLICATION_LAST_8BIT_ADDRRESS) {
if (count ==
up_progmem_write((size_t) flash_address, (void *)data, count)) {
status = FLASH_OK;
}
}
return status;
}

View File

@ -1,885 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
#include "boot_config.h"
#include <stdint.h>
#include <stdlib.h>
#include <string.h>
#include "chip.h"
#include "stm32.h"
#include "timer.h"
#include "uavcan.h"
#include "can.h"
#include "crc.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
#define CAN_REQUEST_TIMEOUT 1000
#define ANY_NODE_ID 0
#define THIS_NODE 1
#define FW_SERVER 2
#define REQ_NODE 3
/****************************************************************************
* Private Types
****************************************************************************/
typedef begin_packed_struct struct dsdl_t {
uavcan_protocol_t prototype;
uint16_t signature_crc16;
uint8_t intail;
uint8_t outtail;
uint8_t mailbox : 2;
uint8_t fifo : 2;
} end_packed_struct dsdl_t;
/* Values used in filter initialization */
typedef enum uavcan_transfer_stage_t {
Initialization,
OnStartOfTransfer
} uavcan_transfer_stage_t;
typedef enum uavcan_dsdl_ignore_t {
sizeDSDLTransfers = SizeDSDL - SizeDSDLComponents + 1
} uavcan_dsdl_ignore_t;
/****************************************************************************
* Private Data
****************************************************************************/
/* Forward declaration */
extern const dsdl_t dsdl_table[sizeDSDLTransfers];
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Public Data
****************************************************************************/
uint8_t g_uavcan_priority = PriorityAllocation;
uint8_t g_this_node_id = 0;
uint8_t g_server_node_id = 0;
/****************************************************************************
* Private Functions
****************************************************************************/
static inline uavcan_dsdl_t getDSDLOffset(uavcan_dsdl_t full) { return full - (SizeDSDLComponents + 1); }
/****************************************************************************
* Name: uavcan_init_comapare_masks
*
* Description:
* This function builds the masks needed for filtering Transfers
*
* Input Parameters:
* stage - Either Initialization, OnStartOfTransfer
* protocol - A pointer to a uavcan_protocol_t to configure the filters
* masks - A pointer to a uavcan_protocol_t return the filters
*
* Returned value:
* None
*
****************************************************************************/
static void uavcan_init_comapare_masks(uavcan_transfer_stage_t stage,
uavcan_protocol_t *protocol,
uavcan_protocol_t *masks)
{
switch (stage) {
default:
break;
case OnStartOfTransfer:
masks->id.u32 |= uavcan_protocol_mask(UavCanMessageSourceNodeID);
masks->tail_init.u8 |= uavcan_protocol_mask(UavCanTransferID);
break;
case Initialization:
masks->tail_init.u8 = uavcan_protocol_mask(UavCanToggle)
| uavcan_protocol_mask(UavCanStartOfTransfer);
if (protocol->msg.service_not_message) {
/* Specific Filter initialization for a Services */
masks->id.u32 = uavcan_protocol_mask(UavCanServiceTypeID)
| uavcan_protocol_mask(UavCanServiceRequestNotResponse)
| uavcan_protocol_mask(UavCanServiceDestinationNodeID)
| uavcan_protocol_mask(UavCanServiceServiceNotMessage);
if (protocol->ser.source_node_id != ANY_NODE_ID) {
masks->id.u32 |= uavcan_protocol_mask(UavCanMessageSourceNodeID);
}
} else {
/* Specific Filter initialization for a Message */
/* Is it anonymous? */
if (protocol->msg.source_node_id == ANY_NODE_ID) {
/* Intentional use of UavCanMessageTypeID because the response
* to the anonymous message is a message and the discriminator
* will be 0
*/
masks->id.u32 = uavcan_protocol_mask(UavCanMessageTypeID)
| uavcan_protocol_mask(UavCanAnonMessageServiceNotMessage);
} else {
masks->id.u32 = uavcan_protocol_mask(UavCanMessageTypeID)
| uavcan_protocol_mask(UavCanMessageServiceNotMessage)
| uavcan_protocol_mask(UavCanMessageSourceNodeID);
}
}
break;
}
}
/****************************************************************************
* Name: load_dsdl_protocol
*
* Description:
* This function builds the protocol for a given dsdl
* N.B The value set for a service is request.
*
* Input Parameters:
* dsdl - An uavcan DSDL Identifier (Auto Generated)
* direction_in_not_out - in or out bound
* protocol - A pointer to a uavcan_protocol_t to configure the filters
* masks - A pointer to a uavcan_protocol_t return the filters
*
* Returned value:
* None
*
****************************************************************************/
static const dsdl_t *load_dsdl_protocol(uavcan_dsdl_t dsdl,
uavcan_direction_t rx_not_tx,
uavcan_protocol_t *protocol,
uint8_t that_node_id)
{
const dsdl_t *pdsdl = &dsdl_table[getDSDLOffset(dsdl)];
protocol->id.u32 = pdsdl->prototype.id.u32;
protocol->msg.priority = g_uavcan_priority;
/* Preserver the transfer_id */
protocol->tail_init.u8 &= uavcan_protocol_mask(UavCanTransferID);
if (rx_not_tx) {
/* Rx */
protocol->tail_init.u8 |= pdsdl->intail;
/* Service */
if (pdsdl->prototype.msg.service_not_message) {
protocol->ser.dest_node_id = g_this_node_id;
protocol->ser.source_node_id = that_node_id;
}
} else {
/*
* Tx
* All Transfers sent have .source_node_id set
* to this node's id
* During allocation this value will be
* 0
*/
protocol->tail_init.u8 |= pdsdl->outtail;
protocol->msg.source_node_id = g_this_node_id;
/*
* All Service Transfer sent have
* The ser.dest_node_id
*/
if (pdsdl->prototype.msg.service_not_message) {
protocol->ser.dest_node_id = that_node_id;
}
}
return pdsdl;
}
/****************************************************************************
* Name: uavcan_tx
*
* Description:
* This function sends a single uavcan protocol based frame applying
* the tail byte.
*
* Input Parameters:
* protocol - A pointer to a uavcan_protocol_t to configure the send
* frame_data - A pointer to 8 bytes of data to be sent (all 8 bytes will be
* loaded into the CAN transmitter but only length bytes will
* be sent.
* length - The number of bytes of the frame_date (DLC field)
* mailbox - A can_fifo_mailbox_t MBxxx value to choose the outgoing
* mailbox.
*
* Returned value:
* The UavcanOk of the data sent. Anything else indicates if a timeout
* occurred.
*
****************************************************************************/
CCASSERT((int)UavcanOk == (int)CAN_OK);
static uavcan_error_t uavcan_tx(uavcan_protocol_t *protocol, uint8_t *frame_data,
size_t length, uint8_t mailbox)
{
frame_data[length++] = protocol->tail_init.u8;
return can_tx(protocol->id.u32, length, frame_data, mailbox);
}
/****************************************************************************
* Name: uavcan_tx_dsdl
*
* Description:
* This function sends a uavcan protocol transfer. For a Service
* The natural case for a Service Response is to send it to the Requestor
*
* Therefore, this function assumes that id this is a Service Transfer,
* the protocol object has the destination node id set in
* protocol->ser.source_node_id.
*
* Input Parameters:
* dsdl - An Uavcan DSDL Identifier (Auto Generated)
* protocol - A pointer to a uavcan_protocol_t to configure the send,
* For a service transfer the desination node id set in
* ser.source_node_id to that of the node we are sending to.
* transfer - A pointer to the packed data of the transfer to be sent.
* length - The number of bytes of data
*
* Returned value:
* The UavcanOk of the data sent. Anything else indicates if a timeout
* occurred.
*
****************************************************************************/
uavcan_error_t uavcan_tx_dsdl(uavcan_dsdl_t dsdl, uavcan_protocol_t *protocol,
const uint8_t *transfer, size_t transfer_length)
{
/*
* Since we do not discriminate between sending a Message or a
* Service (Request or Response)
* We assume this is a response from a rx request and msg.source_node_id
* is that of the requester and that will become the ser.dest_node_id
*/
const dsdl_t *pdsdl = load_dsdl_protocol(dsdl, OutBound, protocol, protocol->ser.source_node_id);
uint8_t payload[CanPayloadLength];
/*
* Only prepend CRC if the transfer will not fit within a single frame
*/
uint32_t m = 0;
if (transfer_length > MaxUserPayloadLength) {
uint16_t transfer_crc = crc16_signature(pdsdl->signature_crc16, transfer_length, transfer);
payload[PayloadOffsetCRClsb] = (uint8_t)transfer_crc;
payload[PayloadOffsetCRCmsb] = (uint8_t)(transfer_crc >> 8u);
m = PayloadOffsetCRCdata;
}
uint32_t i;
for (i = 0; i < transfer_length; i++) {
payload[m++] = transfer[i];
/* Is this the last byte? */
protocol->tail.eot = (i == (transfer_length - 1));
/* Either end of user portion of payload or last byte */
if (m == MaxUserPayloadLength || protocol->tail.eot) {
uavcan_error_t rv = uavcan_tx(protocol, payload, m, pdsdl->mailbox);
if (rv != UavcanOk) {
return rv;
}
/* Increment 1 bit frame sequence number */
protocol->tail.toggle ^= true;
protocol->tail.sot = false;
m = 0;
}
}
return UavcanOk;
}
/****************************************************************************
* Name: uavcan_rx
*
* Description:
* This function is called to receive a single CAN frame from the supplied
* fifo. It does not block if there is not available, but returns 0
*
* Input Parameters:
* protocol - A pointer to a uavcan_protocol_t to return the CAN ID and
* Tail byte
* frame_data - A pointer to return 8 bytes of the frame's data
* (all 8 bytes will be read from the CAN fifo but
* only length bytes will valid.
* length - A pointer to return the number of bytes of the frame_data
* (DLC field)
* fifo A can_fifo_mailbox_t fifixxx value to choose the incoming fifo.
*
* Returned value:
* The length of the data read or 0 if the fifo was empty
*
****************************************************************************/
//#define DEBUG_DTID 1
#define DEBUG_DTID_TRIGGER 4
#ifdef DEBUG_DTID
int trigger = DEBUG_DTID_TRIGGER;
int id = DEBUG_DTID;
bool msg = true;
bool svc = false;
#endif
static uint8_t uavcan_rx(uavcan_protocol_t *protocol, uint8_t *frame_data,
size_t *length, uint8_t fifo)
{
uint8_t rv = can_rx(&protocol->id.u32, length, frame_data, fifo);
if (rv) {
/* Remove the tail byte from length */
*length -= 1;
/* Save the tail byte from the last byte of frame*/
protocol->tail_init.u8 = frame_data[*length];
#ifdef DEBUG_DTID
#pragma message("!!!!!!! DEBUG_DTID is enabled !!!!")
static volatile int count = 0;
if ((msg && protocol->msg.type_id == id)
|| (svc && protocol->ser.type_id == id)
) {
if (count++ == trigger) {
count = 0;
static volatile int j = 0;
j++;
}
}
#endif
}
return rv;
}
/****************************************************************************
* Name: uavcan_rx_dsdl
*
* Description:
* This function receives a uavcan protocol transfer.
* For a Service the natural case for a Service Request is to receive from
* 1) Any Node
* 2) The established Server.
*
* Therefore, this function assumes that id this is a Service Transfer,
* the protocol object has the destination node id set in
* protocol->ser.source_node_id.
*
*
* Input Parameters:
* dsdl - An Uavcan DSDL Identifier (Auto Generated)
* protocol - A pointer to a uavcan_protocol_t to configure the receive,
* based the dsdl for the DTID Service.
* If the request must come from a specific server
* then protocol->ser.source_node_id, should be set
* to that node id;
*
* in_out_transfer_length - The number of bytes of data to receive and the
* number received.
* timeout_ms - The amount of time in mS to wait for the initial transfer
*
* Returned value:
* uavcan_error_t
*
****************************************************************************/
uavcan_error_t uavcan_rx_dsdl(uavcan_dsdl_t dsdl, uavcan_protocol_t *protocol,
uint8_t *transfer, size_t *in_out_transfer_length,
uint32_t timeout_ms)
{
const dsdl_t *pdsdl = load_dsdl_protocol(dsdl, InBound, protocol, protocol->msg.source_node_id);
bl_timer_id timer = timer_allocate(modeTimeout | modeStarted, timeout_ms, 0);
/*
* Set up comparison masks
* In the tail we care about the initial state sot, eot and toggle
* In the CAN ID We care about the Service Type ID, RequestNotResponse,
* ServiceNotMessage, and the destination id
* If the source id is not ANY_NODE_ID, that that must match too.
*/
uavcan_protocol_t masks;
uavcan_init_comapare_masks(Initialization, protocol, &masks);
uint8_t timeout = false;
uint16_t transfer_crc = 0;
size_t total_rx = 0;
uavcan_protocol_t rx_protocol;
do {
uint8_t payload[CanPayloadLength];
size_t rx_length;
if (!uavcan_rx(&rx_protocol, payload, &rx_length, pdsdl->fifo)
|| BadTailState == (rx_protocol.tail_init.u8 & BadTailState)
|| ((rx_protocol.id.u32 ^ protocol->id.u32) & masks.id.u32)
|| ((rx_protocol.tail_init.u8 ^ protocol->tail_init.u8) & masks.tail_init.u8)) {
continue;
}
timer_restart(timer, timeout_ms);
/*
If this is the first frame, capture the actual source node ID and
transfer ID for future comparisons
*/
size_t payload_index = 0;
/* Is this the start of transfer? */
if (rx_protocol.tail.sot) {
/*
* We expect only one Start Of Transfer per transfer
* So knock it down
*/
protocol->tail.sot = false;
/* Discard any data */
total_rx = 0;
/*
* Capture the source node id
* and the Transfer Id
*/
protocol->msg.source_node_id = rx_protocol.msg.source_node_id;
protocol->tail.transfer_id = rx_protocol.tail.transfer_id;
/*
* This is the start of transfer - update the
* masks for this phase or the transfer were
* source_node_id is known and transfer_id
* matters. From now on match source node and
* transfer ID too
*/
uavcan_init_comapare_masks(OnStartOfTransfer, protocol, &masks);
/* Is this a multi-frame transfer? */
if (rx_protocol.tail.eot == false) {
/* Capture the frame CRC */
transfer_crc = uavcan_make_uint16(payload[PayloadOffsetCRClsb], payload[PayloadOffsetCRCmsb]);
/*
* When the CRC is prepended to the payload
* the index of the data is past the CRC
*/
payload_index = PayloadOffsetCRCdata;
rx_length -= PayloadOffsetCRCdata;
}
}
if (rx_protocol.tail.transfer_id > protocol->tail.transfer_id
|| total_rx >= *in_out_transfer_length) {
uavcan_init_comapare_masks(Initialization, protocol, &masks);
protocol->tail.sot = true;
protocol->tail.toggle = false;
} else if (rx_protocol.tail.transfer_id < protocol->tail.transfer_id) {
continue;
}
/* Copy transfer bytes to the transfer */
if (total_rx + rx_length <= *in_out_transfer_length) {
memcpy(&transfer[total_rx], &payload[payload_index], rx_length);
total_rx += rx_length;
}
/* Increment 1 bit frame sequence number */
protocol->tail.toggle ^= true;
/* Is this the end of the transfer ?*/
if (rx_protocol.tail.eot) {
/* Return length of data received */
*in_out_transfer_length = total_rx;
break;
}
} while (!(timeout = timer_expired(timer)));
timer_free(timer);
return (!timeout && (rx_protocol.tail.sot
|| transfer_crc == crc16_signature(pdsdl->signature_crc16, total_rx, transfer))
? UavcanOk : UavcanError);
}
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: uavcan_pack_GetNodeInfo_response
*
* Description:
* This function packs the data of a uavcan_NodeStatus_t into
* a uavcan_GetNodeInfo_response_t structure as array of bytes.
* Then it packs the uavcan_GetNodeInfo_response_t
*
* Input Parameters:
* response The uavcan_GetNodeInfo_response_t to be packed
* node_status - The uavcan_NodeStatus_t that is part of the composition
*
* Returned value:
* Number of bytes written.
*
****************************************************************************/
size_t uavcan_pack_GetNodeInfo_response(uavcan_GetNodeInfo_response_t *response)
{
size_t contiguous_length = FixedSizeGetNodeInfo + \
response->hardware_version.certificate_of_authenticity_length;
/*
* Move name so it's contiguous with the end of certificate_of_authenticity[length]
* which very well may be just after certificate_of_authenticity_length if the length
* of the certificate_of_authenticity is 0
*/
memcpy(&((uint8_t *)response)[contiguous_length], response->name, response->name_length);
return contiguous_length + response->name_length;
}
/****************************************************************************
* Name: uavcan_pack_LogMessage
*
* Description:
* This function formats the data of a uavcan_logmessage_t structure into
* an array of bytes.
*
* Input Parameters:
* external - The array of bytes to populate.
* internal - The uavcan_logmessage_t to pack into the data
*
* Returned value:
* Number of bytes written.
*
****************************************************************************/
static size_t uavcan_pack_LogMessage(uint8_t *external,
const uavcan_LogMessage_t *internal)
{
/* Pack the 3 bit level in top bits followed by the length of source */
external[uavcan_byte_offset(LogMessage, level)] = uavcan_ppack(internal, LogMessage, level) \
| uavcan_pack(uavcan_byte_count(LogMessage, source), LogMessage, source_length);
memcpy(&external[uavcan_byte_offset(LogMessage, source)], internal->source,
PackedSizeMsgLogMessage - sizeof_member(uavcan_LogMessage_t, level));
return PackedSizeMsgLogMessage;
}
/****************************************************************************
* Name: uavcan_tx_log_message
*
* Description:
* This functions sends uavcan LogMessage type data. The Source will be
* taken from the application defined debug_log_source
*
* Input Parameters:
* level - Log Level of the LogMessage Constants DEBUG, INFO, WARN, ERROR
* stage - The Stage the application is at. see Aplication defined
* LOGMESSAGE_STAGE_x
* status - The status of that stage. See Application defined
* LOGMESSAGE_RESULT_x
*
* Returned Value:
* None
*
****************************************************************************/
void uavcan_tx_log_message(uavcan_LogMessageConsts_t level, uint8_t stage,
uint8_t status)
{
static uint8_t transfer_id;
uavcan_LogMessage_t message;
uavcan_protocol_t protocol;
protocol.tail.transfer_id = transfer_id++;
const dsdl_t *dsdl = load_dsdl_protocol(DSDLMsgLogMessage, MessageOut, &protocol, 0);
message.level = level;
memcpy(&message.source, debug_log_source, sizeof(message.source));
message.text[0] = stage;
message.text[1] = status;
uint8_t payload[CanPayloadLength];
size_t frame_len = uavcan_pack_LogMessage(payload, &message);
uavcan_tx(&protocol, payload, frame_len, dsdl->mailbox);
}
/****************************************************************************
* Name: uavcan_tx_allocation_message
*
* Description:
* This function sends a uavcan allocation message.
*
* Input Parameters:
* requested_node_id - This node's preferred node id 0 for no preference.
* unique_id_length - This node's length of it's unique identifier.
* unique_id - A pointer to the bytes that represent unique
* identifier.
* unique_id_offset - The offset equal 0 or the number of bytes in the
* the last received message that matched the unique ID
* field.
* random - The value to use as the discriminator of the
* anonymous message
*
* Returned value:
* None
*
****************************************************************************/
void uavcan_tx_allocation_message(uint8_t requested_node_id,
size_t unique_id_length,
const uint8_t *unique_id,
uint8_t unique_id_offset,
uint16_t random)
{
static uint8_t transfer_id;
uavcan_protocol_t protocol;
protocol.tail.transfer_id = transfer_id++;
const dsdl_t *dsdl = load_dsdl_protocol(DSDLMsgAllocation, MessageOut, &protocol, 0);
/* Override defaults */
protocol.ana.discriminator = random;
uint8_t payload[CanPayloadLength];
size_t max_copy = MAX_LENGTH_OF_UNIQUE_ID_IN_REQUEST;
size_t remaining = unique_id_length - unique_id_offset;
if (max_copy > remaining) {
max_copy = remaining;
}
payload[uavcan_byte_offset(Allocation, node_id)] = uavcan_pack(requested_node_id, Allocation, node_id) |
(unique_id_offset ? 0 : uavcan_bit_mask(Allocation, first_part_of_unique_id));
/*
* Copy in the remaining bytes of payload, either filling it
* or on the last chunk partially filling it
*/
memcpy(&payload[uavcan_byte_offset(Allocation, unique_id)], &unique_id[unique_id_offset], max_copy);
/* Account for the payload[0] */
max_copy++;
uavcan_tx(&protocol, payload, max_copy, dsdl->mailbox);
can_cancel_on_error(dsdl->mailbox);
}
/****************************************************************************
* Private Data - This table is positioned here to not mess up the line
* numbers for the debugger.
****************************************************************************/
#define NA 0
#define END_COMPONENTS
#define UAVCAN_DSDL_BIT_DEF(data_typ_name, field_name, lsb_pos, length, payload_offset, payload_length)
#define UAVCAN_DSDL_MESG_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
{ \
{\
.msg = \
{ \
.source_node_id = 0, \
.service_not_message = (false), \
.type_id = (dtid), \
.priority = 0, \
}, \
{ \
.tail_init = \
{ \
.u8 = (outbound), \
} \
} \
}, \
signature, \
inbound, \
outbound, \
mailbox, \
fifo, \
},
#define UAVCAN_DSDL_SREQ_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
{ \
{\
.ser = \
{ \
.source_node_id = 0, \
.service_not_message = (true), \
.dest_node_id = 0, \
.request_not_response = (true), \
.type_id = (dtid), \
.priority = 0, \
}, \
{ \
.tail_init = \
{ \
.u8 = (outbound), \
} \
} \
}, \
signature, \
inbound, \
outbound, \
mailbox, \
fifo, \
},
#define UAVCAN_DSDL_SRSP_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound) \
{ \
{\
.ser = \
{ \
.source_node_id = 0, \
.service_not_message = (true), \
.dest_node_id = 0, \
.request_not_response = (false), \
.type_id = (dtid), \
.priority = 0, \
}, \
{ \
.tail_init = \
{ \
.u8 = (outbound), \
} \
} \
}, \
signature, \
inbound, \
outbound, \
mailbox, \
fifo, \
},
#define UAVCAN_DSDL_TYPE_DEF(name, dtid, signature, packsize, mailbox, fifo, inbound, outbound)
const dsdl_t dsdl_table[sizeDSDLTransfers] = {
#include "uavcan_dsdl_defs.h"
};
#undef UAVCAN_DSDL_TYPE_DEF
#undef UAVCAN_DSDL_SRSP_DEF
#undef UAVCAN_DSDL_SREQ_DEF
#undef UAVCAN_DSDL_MESG_DEF
#undef UAVCAN_DSDL_BIT_DEF
#undef FW_SERVER
#undef REQ_NODE
#undef THIS_NODE
#undef ANY_NODE_ID
#undef END_COMPONENTS
#undef NA

View File

@ -1,491 +0,0 @@
/****************************************************************************
*
* Copyright (c) 2015 PX4 Development Team. All rights reserved.
* Author: Ben Dyer <ben_dyer@mac.com>
* Pavel Kirienko <pavel.kirienko@zubax.com>
* David Sidrane <david_s5@nscdg.com>
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
* are met:
*
* 1. Redistributions of source code must retain the above copyright
* notice, this list of conditions and the following disclaimer.
* 2. Redistributions in binary form must reproduce the above copyright
* notice, this list of conditions and the following disclaimer in
* the documentation and/or other materials provided with the
* distribution.
* 3. Neither the name PX4 nor the names of its contributors may be
* used to endorse or promote products derived from this software
* without specific prior written permission.
*
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
* POSSIBILITY OF SUCH DAMAGE.
*
****************************************************************************/
/****************************************************************************
* Included Files
****************************************************************************/
#include <nuttx/config.h>
// Turn off Probes in this module
#undef CONFIG_BOARD_USE_PROBES
#include <boot_config.h>
#include <sys/types.h>
#include <stdint.h>
#include <string.h>
#include <nuttx/arch.h>
#include <arch/irq.h>
#include <arch/board/board.h>
#include "systemlib/px4_macros.h"
#include "timer.h"
#include "nvic.h"
/****************************************************************************
* Pre-processor Definitions
****************************************************************************/
/****************************************************************************
* Private Types
****************************************************************************/
typedef enum {
OneShot = modeOneShot,
Repeating = modeRepeating,
Timeout = modeTimeout,
modeMsk = 0x3,
running = modeStarted,
inuse = 0x80,
} bl_timer_ctl_t;
typedef struct {
bl_timer_cb_t usr;
time_ms_t count;
time_ms_t reload;
bl_timer_ctl_t ctl;
} bl_timer_t;
/****************************************************************************
* Private Function Prototypes
****************************************************************************/
/****************************************************************************
* Private Data
****************************************************************************/
static time_ms_t sys_tic;
static bl_timer_t timers[OPT_BL_NUMBER_TIMERS];
/****************************************************************************
* Public Data
****************************************************************************/
/* Use to initialize */
const bl_timer_cb_t null_cb = { 0, 0 };
/****************************************************************************
* Private Functions
****************************************************************************/
/****************************************************************************
* Public Function Prototypes
****************************************************************************/
/* We use the linker --wrap ability to wrap the NuttX stm32 call out to
* the sceduler's sched_process_timer and service it here. Thus replacing
* the NuttX scheduler with are timer driven scheduling.
*/
void __wrap_sched_process_timer(void);
/****************************************************************************
* Public Functions
****************************************************************************/
/****************************************************************************
* Name: timer_tic
*
* Description:
* Returns the system tic counter that counts in units of
* (CONFIG_USEC_PER_TICK/1000). By default 10 Ms.
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
time_ms_t timer_tic(void)
{
return sys_tic;
}
/****************************************************************************
* Name: sched_process_timer
*
* Description:
* Called by Nuttx on the ISR of the SysTic. This function run the list of
* timers. It deducts that amount of the time of a system tick from the
* any timers that are in use and running.
*
* Depending on the mode of the timer, the appropriate actions is taken on
* expiration.
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
__EXPORT
void __wrap_sched_process_timer(void)
{
PROBE(1, true);
PROBE(1, false);
/* Increment the per-tick system counter */
sys_tic++;
/* todo:May need a X tick here is threads run long */
time_ms_t ms_elapsed = (CONFIG_USEC_PER_TICK / 1000);
/* Walk the time list from High to low and */
bl_timer_id t;
for (t = arraySize(timers) - 1; (int8_t) t >= 0; t--) {
/* Timer in use and running */
if ((timers[t].ctl & (inuse | running)) == (inuse | running)) {
/* Is it NOT already expired nor about to expire ?*/
if (timers[t].count != 0) {
/* Is it off in future */
if (timers[t].count > ms_elapsed) {
/* Just remove the amount attributed to the tick */
timers[t].count -= ms_elapsed;
continue;
}
/* it has expired now or less than a tick ago */
/* Mark it expired */
timers[t].count = 0;
/* Now perform action based on mode */
switch (timers[t].ctl & ~(inuse | running)) {
case OneShot: {
bl_timer_cb_t user = timers[t].usr;
memset(&timers[t], 0, sizeof(timers[t]));
if (user.cb) {
user.cb(t, user.context);
}
}
break;
case Repeating:
timers[t].count = timers[t].reload;
/* FALLTHROUGH */
/* to callback */
case Timeout:
if (timers[t].usr.cb) {
timers[t].usr.cb(t, timers[t].usr.context);
}
break;
default:
break;
}
}
}
}
}
/****************************************************************************
* Name: timer_allocate
*
* Description:
* Is used to allocate a timer. Allocation does not involve memory
* allocation as the data for the timer are compile time generated.
* See OPT_BL_NUMBER_TIMERS
*
* There is an inherent priority to the timers in that the first timer
* allocated is the first timer run per tick.
*
* There are 3 modes of operation for the timers. All modes support an
* optional call back on expiration.
*
* modeOneShot - Specifies a one-shot timer. After notification timer
* is resource is freed.
* modeRepeating - Specifies a repeating timer that will reload and
* call an optional.
* modeTimeout - Specifies a persistent start / stop timer.
*
* modeStarted - Or'ed in to start the timer when allocated
*
*
* Input Parameters:
* mode - One of bl_timer_modes_t with the Optional modeStarted
* msfromnow - The reload and initial value for the timer in Ms.
* fc - A pointer or NULL (0). If it is non null it can be any
* of the following:
*
* a) A bl_timer_cb_t populated on the users stack or
* in the data segment. The values are copied into the
* internal data structure of the timer and therefore do
* not have to persist after the call to timer_allocate
*
* b) The address of null_cb. This is identical to passing
* null for the value of fc.
*
* Returned Value:
* On success a value from 0 - OPT_BL_NUMBER_TIMERS-1 that is
* the bl_timer_id for subsequent timer operations
* -1 on failure. This indicates there are no free timers.
*
****************************************************************************/
bl_timer_id timer_allocate(bl_timer_modes_t mode, time_ms_t msfromnow,
bl_timer_cb_t *fc)
{
bl_timer_id t;
irqstate_t s = enter_critical_section();
for (t = arraySize(timers) - 1; (int8_t)t >= 0; t--) {
if ((timers[t].ctl & inuse) == 0) {
timers[t].reload = msfromnow;
timers[t].count = msfromnow;
timers[t].usr = fc ? *fc : null_cb;
timers[t].ctl = (mode & (modeMsk | running)) | (inuse);
break;
}
}
leave_critical_section(s);
return t;
}
/****************************************************************************
* Name: timer_free
*
* Description:
* Is used to free a timer. Freeing a timer does not involve memory
* deallocation as the data for the timer are compile time generated.
* See OPT_BL_NUMBER_TIMERS
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_free(bl_timer_id id)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers));
irqstate_t s = enter_critical_section();
memset(&timers[id], 0, sizeof(timers[id]));
leave_critical_section(s);
}
/****************************************************************************
* Name: timer_start
*
* Description:
* Is used to Start a timer. The reload value is copied to the counter.
* And the running bit it set. There is no problem in Starting a running
* timer. But it will restart the timeout.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_start(bl_timer_id id)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers) && (timers[id].ctl & inuse));
irqstate_t s = enter_critical_section();
timers[id].count = timers[id].reload;
timers[id].ctl |= running;
leave_critical_section(s);
}
/****************************************************************************
* Name: timer_stop
*
* Description:
* Is used to stop a timer. It is Ok to stop a stopped timer.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_stop(bl_timer_id id)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers) && (timers[id].ctl & inuse));
irqstate_t s = enter_critical_section();
timers[id].ctl &= ~running;
leave_critical_section(s);
}
/****************************************************************************
* Name: timer_expired
*
* Description:
* Test if a timer that was configured as a modeTimeout timer is expired.
* To be expired the time has to be running and have a count of 0.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* Non Zero if the timer is expired otherwise zero.
*
****************************************************************************/
int timer_expired(bl_timer_id id)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers) && (timers[id].ctl & inuse));
irqstate_t s = enter_critical_section();
int rv = ((timers[id].ctl & running) && timers[id].count == 0);
leave_critical_section(s);
return rv;
}
/****************************************************************************
* Name: timer_restart
*
* Description:
* Is used to re start a timer with a new reload count. The reload value
* is copied to the counter and the running bit it set. There is no
* problem in restarting a running timer.
*
* Input Parameters:
* id - Returned from timer_allocate;
* ms - Is a time_ms_t and the new reload value to use.
*
* Returned Value:
* None.
*
****************************************************************************/
void timer_restart(bl_timer_id id, time_ms_t ms)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers) && (timers[id].ctl & inuse));
irqstate_t s = enter_critical_section();
timers[id].count = timers[id].reload = ms;
timers[id].ctl |= running;
leave_critical_section(s);
}
/****************************************************************************
* Name: timer_ref
*
* Description:
* Returns an time_ref_t that is a reference (ponter) to the internal counter
* of the timer selected by id. It should only be used with calls to
* timer_ref_expired.
*
* Input Parameters:
* id - Returned from timer_allocate;
*
* Returned Value:
* An internal reference that should be treated as opaque by the caller and
* should only be used with calls to timer_ref_expired.
* There is no reference counting on the reference and therefore does not
* require any operation to free it.
*
*************************************************************************/
time_ref_t timer_ref(bl_timer_id id)
{
DEBUGASSERT(id >= 0 && id < arraySize(timers) && (timers[id].ctl & inuse));
return (time_ref_t) &timers[id].count;
}
/****************************************************************************
* Name: timer_init
*
* Description:
* Called early in os_start to initialize the data associated with
* the timers
*
* Input Parameters:
* None
*
* Returned Value:
* None
*
****************************************************************************/
__EXPORT
void timer_init(void)
{
/* For system timing probing see bord.h and
* CONFIG_BOARD_USE_PROBES
*/
PROBE_INIT(7);
PROBE(1, true);
PROBE(2, true);
PROBE(3, true);
PROBE(1, false);
PROBE(2, false);
PROBE(3, false);
/* This is the lowlevel IO if needed to instrument timing
* with the smallest impact
* *((uint32_t *)0x40011010) = 0x100; // PROBE(3,true);
* *((uint32_t *)0x40011014) = 0x100; // PROBE(3,false);
*/
/* Initialize timer data */
sys_tic = 0;
memset(timers, 0, sizeof(timers));
}

File diff suppressed because it is too large Load Diff

Some files were not shown because too many files have changed in this diff Show More