aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Sidrane <david_s5@nscdg.com>2015-04-23 11:11:40 -1000
committerDavid Sidrane <david_s5@nscdg.com>2015-04-23 11:11:40 -1000
commit861687cefd879edf10de50cacc75308afeac67e8 (patch)
treef39c44171465e417380f080f8331565ef03d745e
parent98ac8800b6f6c04f45948cbf41dc13ad562f0617 (diff)
parentf6a937dc5acf4f9a43876293e9181e45f38c8bec (diff)
downloadpx4-firmware-861687cefd879edf10de50cacc75308afeac67e8.tar.gz
px4-firmware-861687cefd879edf10de50cacc75308afeac67e8.tar.bz2
px4-firmware-861687cefd879edf10de50cacc75308afeac67e8.zip
Merge pull request #2070 from PX4/nuttx_next_px4_can_node_uavcannuttx_next
Nuttx next px4 can node uavcan
-rw-r--r--Images/px4cannode-v1.prototype12
-rw-r--r--Makefile23
-rw-r--r--makefiles/board_px4cannode-v1.mk12
-rw-r--r--makefiles/config_px4cannode-v1_bootloader.mk13
-rw-r--r--makefiles/config_px4cannode-v1_default.mk61
-rw-r--r--makefiles/firmware.mk1
-rw-r--r--makefiles/nuttx.mk28
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk6
-rw-r--r--nuttx-configs/px4cannode-v1/Kconfig22
-rw-r--r--nuttx-configs/px4cannode-v1/bootloader/Make.defs176
-rw-r--r--nuttx-configs/px4cannode-v1/bootloader/README.txt179
-rw-r--r--nuttx-configs/px4cannode-v1/bootloader/defconfig870
-rwxr-xr-xnuttx-configs/px4cannode-v1/bootloader/setenv.sh80
-rwxr-xr-xnuttx-configs/px4cannode-v1/include/README.txt5
-rwxr-xr-xnuttx-configs/px4cannode-v1/include/board.h251
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/Make.defs172
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/defconfig1036
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/defconfig.nonsh1036
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/defconfig.nsh1142
-rwxr-xr-xnuttx-configs/px4cannode-v1/nsh/setenv.sh80
-rw-r--r--nuttx-configs/px4cannode-v1/scripts/bootloaderld.script136
-rw-r--r--nuttx-configs/px4cannode-v1/scripts/ld.script140
-rw-r--r--nuttx-configs/px4cannode-v1/src/Makefile96
-rw-r--r--nuttx-configs/px4cannode-v1/src/empty.c4
-rw-r--r--nuttx-configs/px4cannode-v1/src/ostubs.c171
-rwxr-xr-xnuttx-configs/px4fmu-v2/include/board.h4
-rw-r--r--src/drivers/boards/aerocore/board_config.h1
-rw-r--r--src/drivers/boards/mavstation/board_config.h1
-rw-r--r--src/drivers/boards/px4cannode-v1/board_config.h311
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/can/driver.c524
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/can/driver.h219
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/common/bl_macros.h102
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.c268
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.h224
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/module.mk14
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/board_config.h201
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/boot.c205
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/crc.c169
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/crc.h117
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/flash.c165
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/flash.h100
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/timer.c469
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/src/timer.h411
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/uavcan/main.c1207
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.c723
-rw-r--r--src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.h501
-rw-r--r--src/drivers/boards/px4cannode-v1/module.mk15
-rw-r--r--src/drivers/boards/px4cannode-v1/px4cannode_buttons.c154
-rw-r--r--src/drivers/boards/px4cannode-v1/px4cannode_can.c147
-rw-r--r--src/drivers/boards/px4cannode-v1/px4cannode_init.c200
-rw-r--r--src/drivers/boards/px4cannode-v1/px4cannode_led.c175
-rw-r--r--src/drivers/boards/px4cannode-v1/px4cannode_spi.c232
-rw-r--r--src/drivers/boards/px4fmu-v1/board_config.h1
-rw-r--r--src/drivers/boards/px4fmu-v2/board_config.h2
-rw-r--r--src/lib/version/version.h4
-rw-r--r--src/modules/systemlib/board_serial.c2
-rw-r--r--src/modules/systemlib/mcu_version.c45
-rw-r--r--src/modules/uavcan/module.mk6
-rw-r--r--src/modules/uavcannode/.gitignore1
-rw-r--r--src/modules/uavcannode/indication_controller.cpp94
-rw-r--r--src/modules/uavcannode/indication_controller.hpp41
-rw-r--r--src/modules/uavcannode/led.cpp76
-rw-r--r--src/modules/uavcannode/led.hpp38
-rw-r--r--src/modules/uavcannode/module.mk82
-rw-r--r--src/modules/uavcannode/resources.cpp182
-rw-r--r--src/modules/uavcannode/resources.hpp44
-rw-r--r--src/modules/uavcannode/sim_controller.cpp147
-rw-r--r--src/modules/uavcannode/sim_controller.hpp41
-rw-r--r--src/modules/uavcannode/uavcannode_clock.cpp81
-rw-r--r--src/modules/uavcannode/uavcannode_main.cpp467
-rw-r--r--src/modules/uavcannode/uavcannode_main.hpp101
-rw-r--r--src/modules/uavcannode/uavcannode_params.c73
72 files changed, 14106 insertions, 33 deletions
diff --git a/Images/px4cannode-v1.prototype b/Images/px4cannode-v1.prototype
new file mode 100644
index 000000000..fb66cbbe3
--- /dev/null
+++ b/Images/px4cannode-v1.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 22,
+ "magic": "CANNODEFWv1",
+ "description": "Firmware for the PX4CANNODE board",
+ "image": "",
+ "build_time": 0,
+ "summary": "PX4CANNODE",
+ "version": "0.1",
+ "image_size": 0,
+ "git_identity": "",
+ "board_revision": 0
+}
diff --git a/Makefile b/Makefile
index 7c8fa7a4f..76017b606 100644
--- a/Makefile
+++ b/Makefile
@@ -63,6 +63,12 @@ KNOWN_BOARDS := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)boa
BOARDS ?= $(KNOWN_BOARDS)
#
+# Canned firmware configurations for bootloader that we (know how to) build.
+#
+KNOWN_BOARDS_WITH_BOOTLOADERS := $(subst _bootloader,, $(filter %_bootloader, $(CONFIGS)))
+BOARDS_WITH_BOOTLOADERS := $(filter $(BOARDS), $(KNOWN_BOARDS_WITH_BOOTLOADERS))
+
+#
# Debugging
#
MQUIET = --no-print-directory
@@ -123,16 +129,18 @@ $(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
#
.PHONY: $(FIRMWARES)
$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
+$(BUILD_DIR)%.build/firmware.px4: NUTTX_CONFIG = $(if $(findstring bootloader,$@),bootloader,nsh)
$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4: generateuorbtopicheaders checksubmodules
@$(ECHO) %%%%
- @$(ECHO) %%%% Building $(config) in $(work_dir)
+ @$(ECHO) %%%% Building $(config) on $(NUTTX_CONFIG) in $(work_dir)
@$(ECHO) %%%%
$(Q) $(MKDIR) -p $(work_dir)
$(Q) $(MAKE) -r -C $(work_dir) \
-f $(PX4_MK_DIR)firmware.mk \
CONFIG=$(config) \
WORK_DIR=$(work_dir) \
+ NUTTX_CONFIG=$(NUTTX_CONFIG) \
$(FIRMWARE_GOAL)
#
@@ -159,7 +167,8 @@ $(foreach config,$(FMU_CONFIGS),$(eval $(call FMU_DEP,$(config))))
# XXX Should support fetching/unpacking from a separate directory to permit
# downloads of the prebuilt archives as well...
#
-NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
+NUTTX_BOOTLOADER_ARCHIVES = $(foreach board,$(BOARDS_WITH_BOOTLOADERS),$(ARCHIVE_DIR)$(board).bootloader.export)
+NUTTX_ARCHIVES = $(NUTTX_BOOTLOADER_ARCHIVES) $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).nsh.export)
.PHONY: archives
archives: checksubmodules nuttxpatches $(NUTTX_ARCHIVES)
@@ -171,15 +180,15 @@ endif
J?=1
-$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
-$(ARCHIVE_DIR)%.export: configuration = nsh
+$(ARCHIVE_DIR)%.export: board = $(basename $(notdir $(basename $@)))
+$(ARCHIVE_DIR)%.export: configuration = $(lastword $(subst ., ,$(notdir $(basename $@))))
$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC)
- @$(ECHO) %% Configuring NuttX for $(board)
+ @$(ECHO) %% Configuring NuttX for $(board) $(configuration)
$(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) distclean
- $(Q) (cd $(NUTTX_SRC)/configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
+ $(Q) (cd $(NUTTX_SRC)configs && $(COPYDIR) $(PX4_BASE)nuttx-configs/$(board) .)
$(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
- @$(ECHO) %% Exporting NuttX for $(board)
+ @$(ECHO) %% Exporting NuttX for $(board) $(configuration)
$(Q) $(MAKE) -r -j$(J) -C $(NUTTX_SRC) -r $(MQUIET) CONFIG_ARCH_BOARD=$(board) export
$(Q) $(MKDIR) -p $(dir $@)
$(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
diff --git a/makefiles/board_px4cannode-v1.mk b/makefiles/board_px4cannode-v1.mk
new file mode 100644
index 000000000..f39ce6aa3
--- /dev/null
+++ b/makefiles/board_px4cannode-v1.mk
@@ -0,0 +1,12 @@
+#
+# Board-specific definitions for the PX4CANNODE
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM3
+CONFIG_BOARD = PX4CANNODE_V1
+
+WUSEPACKED = -Wno-packed
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_px4cannode-v1_bootloader.mk b/makefiles/config_px4cannode-v1_bootloader.mk
new file mode 100644
index 000000000..3654274b0
--- /dev/null
+++ b/makefiles/config_px4cannode-v1_bootloader.mk
@@ -0,0 +1,13 @@
+#
+# Makefile for the px4cannode_bootloader configuration
+#
+
+#
+# Board support modules
+#
+MODULES += drivers/boards/px4cannode-v1/bootloader
+
+SRC_SEARCH = can src common uavcan
+
+INCLUDE_DIRS += $(addprefix $(PX4_MODULE_SRC)$(MODULES)/,$(SRC_SEARCH))
+
diff --git a/makefiles/config_px4cannode-v1_default.mk b/makefiles/config_px4cannode-v1_default.mk
new file mode 100644
index 000000000..6979c1619
--- /dev/null
+++ b/makefiles/config_px4cannode-v1_default.mk
@@ -0,0 +1,61 @@
+#
+# Makefile for the px4cannode_default configuration
+#
+
+#
+# Board support modules
+#
+MODULES += drivers/stm32
+MODULES += drivers/stm32/adc
+MODULES += drivers/led
+MODULES += drivers/boards/px4cannode-v1
+
+#
+# System commands
+#
+MODULES += systemcmds/reboot
+MODULES += systemcmds/top
+MODULES += systemcmds/config
+MODULES += systemcmds/ver
+
+#
+# General system control
+#
+MODULES += modules/uavcannode
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+
+
+
+#
+# Unit tests
+#
+#MODULES += modules/unit_test
+#MODULES += modules/commander/commander_tests
+
+# Generate parameter XML file
+GEN_PARAM_XML = 1
+
+
+#
+# Demo apps
+#
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+BUILTIN_COMMANDS := \
+ $(call _B, null, , 60, null_main)
+
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
index 4b4823a98..195885143 100644
--- a/makefiles/firmware.mk
+++ b/makefiles/firmware.mk
@@ -145,6 +145,7 @@ endif
export CONFIG
include $(CONFIG_FILE)
$(info % CONFIG = $(CONFIG))
+$(info % NUTTX_CONFIG = $(NUTTX_CONFIG))
#
# Sanity-check the BOARD variable and then get the board config.
diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk
index bf0744140..f57921422 100644
--- a/makefiles/nuttx.mk
+++ b/makefiles/nuttx.mk
@@ -37,9 +37,9 @@
#
# Check that the NuttX archive for the selected board is available.
#
-NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).export)
+NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).$(NUTTX_CONFIG).export)
ifeq ($(NUTTX_ARCHIVE),)
-$(error The NuttX export archive for $(BOARD) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
+$(error The NuttX export archive $(BOARD).$(CONFIG).export for $(BOARD) with configuration $(config) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
endif
#
@@ -52,13 +52,26 @@ NUTTX_CONFIG_HEADER = $(NUTTX_EXPORT_DIR)include/nuttx/config.h
$(info % NUTTX_EXPORT_DIR = $(NUTTX_EXPORT_DIR))
$(info % NUTTX_CONFIG_HEADER = $(NUTTX_CONFIG_HEADER))
+#
+# Are there any start up files not in the nuttx lib
+#
+
+NUTTX_STARTUP := $(wildcard $(NUTTX_EXPORT_DIR)startup/*.o)
+
+
+$(info % NUTTX_STARTUP = $(NUTTX_STARTUP))
+
GLOBAL_DEPS += $(NUTTX_CONFIG_HEADER)
#
# Use the linker script from the NuttX export
#
+ifeq ($(NUTTX_CONFIG),bootloader)
+LDSCRIPT += $(NUTTX_EXPORT_DIR)build/bootloaderld.script
+else
LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
+endif
#
# Add directories from the NuttX export to the relevant search paths
@@ -66,12 +79,15 @@ LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include \
$(NUTTX_EXPORT_DIR)include/cxx \
$(NUTTX_EXPORT_DIR)arch/chip \
- $(NUTTX_EXPORT_DIR)arch/common
+ $(NUTTX_EXPORT_DIR)arch/common \
+ $(NUTTX_EXPORT_DIR)arch/armv7-m
LIB_DIRS += $(NUTTX_EXPORT_DIR)libs
-LIBS += -lapps -lnuttx
-NUTTX_LIBS = $(NUTTX_EXPORT_DIR)libs/libapps.a \
- $(NUTTX_EXPORT_DIR)libs/libnuttx.a
+LIBS += -lapps -lnuttx
+START_OBJ += $(NUTTX_STARTUP)
+NUTTX_LIBS = $(NUTTX_EXPORT_DIR)libs/libapps.a \
+ $(NUTTX_EXPORT_DIR)libs/libnuttx.a
+
LINK_DEPS += $(NUTTX_LIBS)
$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index b1bbc0626..fb04cbc38 100644
--- a/makefiles/toolchain_gnu-arm-eabi.mk
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -141,6 +141,8 @@ INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH))
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics -D__CUSTOM_FILE_IO__
+WUSEPACKED ?= -Wpacked
+
# Generic warnings
#
ARCHWARNINGS = -Wall \
@@ -153,7 +155,7 @@ ARCHWARNINGS = -Wall \
-Wpointer-arith \
-Wlogical-op \
-Wmissing-declarations \
- -Wpacked \
+ $(WUSEPACKED) \
-Wno-unused-parameter \
-Werror=format-security \
-Werror=array-bounds \
@@ -290,7 +292,7 @@ endef
define LINK
@$(ECHO) "LINK: $1"
@$(MKDIR) -p $(dir $1)
- $(Q) $(LD) $(LDFLAGS) -Map $1.map -o $1 --start-group $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
+ $(Q) $(LD) $(LDFLAGS) -Map $1.map -o $1 --start-group $(START_OBJ) $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
endef
# Convert $1 from a linked object to a raw binary in $2
diff --git a/nuttx-configs/px4cannode-v1/Kconfig b/nuttx-configs/px4cannode-v1/Kconfig
new file mode 100644
index 000000000..35fbcdbd6
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/Kconfig
@@ -0,0 +1,22 @@
+#
+# For a description of the syntax of this configuration file,
+# see misc/tools/kconfig-language.txt.
+#
+
+if CONFIG_ARCH_BOARD_PX4CANNODE_V1
+
+config BOARD_HAS_PROBES
+ bool "Board provides GPIO or other Hardware for signaling to timing analyze."
+ default y
+ ---help---
+ This board provides GPIO D0-D2,A0-A3 as PROBE_1-6 to provide timing signals from selected drivers.
+
+config BOARD_USE_PROBES
+ bool "Enable the use provides GPIO D0-D2,A0-A3 as PROBE_1-6 to provide timing signals from selected drivers"
+ default n
+ depends on BOARD_HAS_PROBES
+
+ ---help---
+ Select to use GPIO provides GPIO D0-D2,A0-A3 to provide timing signals from selected drivers.
+
+endif
diff --git a/nuttx-configs/px4cannode-v1/bootloader/Make.defs b/nuttx-configs/px4cannode-v1/bootloader/Make.defs
new file mode 100644
index 000000000..1ce59a3ed
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/bootloader/Make.defs
@@ -0,0 +1,176 @@
+############################################################################
+# 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}/arch/arm/src/armv7-m/Toolchain.defs
+
+CONFIG_BOOTLOADER=y
+#
+# 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
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+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.sh
+ 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}
+
+# optimisation 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 = -Wall \
+ -Wno-sign-compare \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wno-unused-parameter
+# -Wpacked - need to pack structs for uavcan protocol
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+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
+
diff --git a/nuttx-configs/px4cannode-v1/bootloader/README.txt b/nuttx-configs/px4cannode-v1/bootloader/README.txt
new file mode 100644
index 000000000..66a96d804
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/bootloader/README.txt
@@ -0,0 +1,179 @@
+/****************************************************************************
+ *
+ * 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
diff --git a/nuttx-configs/px4cannode-v1/bootloader/defconfig b/nuttx-configs/px4cannode-v1/bootloader/defconfig
new file mode 100644
index 000000000..2a2c48bc1
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/bootloader/defconfig
@@ -0,0 +1,870 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_DEFAULT_SMALL=y
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+CONFIG_BUILD_FLAT=y
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+# CONFIG_UBOOT_UIMAGE is not set
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDINT_H is not set
+# CONFIG_ARCH_STDBOOL_H is not set
+# CONFIG_ARCH_MATH_H is not set
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+# CONFIG_DEBUG is not set
+CONFIG_ARCH_HAVE_HEAPCHECK=y
+CONFIG_ARCH_HAVE_STACKCHECK=y
+# CONFIG_STACK_COLORATION is not set
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_ARCH_HAVE_CUSTOMOPT=y
+# CONFIG_DEBUG_NOOPT is not set
+CONFIG_DEBUG_CUSTOMOPT=y
+# CONFIG_DEBUG_FULLOPT is not set
+CONFIG_DEBUG_OPTLEVEL="-Os"
+
+#
+# System Type
+#
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_A1X is not set
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_EFM32 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_TIVA is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAMA5 is not set
+# CONFIG_ARCH_CHIP_SAMD is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+# CONFIG_ARCH_CHIP_SAMV7 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+# CONFIG_ARCH_ARM7TDMI is not set
+# CONFIG_ARCH_ARM926EJS is not set
+# CONFIG_ARCH_ARM920T is not set
+# CONFIG_ARCH_CORTEXM0 is not set
+CONFIG_ARCH_CORTEXM3=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXM7 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+# CONFIG_ARMV7M_CMNVECTOR is not set
+# CONFIG_ARMV7M_LAZYFPU is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+# CONFIG_ARCH_HAVE_DPFPU is not set
+# CONFIG_ARMV7M_MPU is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_HAVE_ICACHE is not set
+# CONFIG_ARMV7M_HAVE_DCACHE is not set
+# CONFIG_ARMV7M_HAVE_ITCM is not set
+# CONFIG_ARMV7M_HAVE_DTCM is not set
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y
+# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set
+# CONFIG_ARMV7M_STACKCHECK is not set
+# CONFIG_ARMV7M_ITMSYSLOG is not set
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32L162ZD is not set
+# CONFIG_ARCH_CHIP_STM32L162VE is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F102CB is not set
+# CONFIG_ARCH_CHIP_STM32F103T8 is not set
+# CONFIG_ARCH_CHIP_STM32F103TB is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103CB is not set
+# CONFIG_ARCH_CHIP_STM32F103R8 is not set
+CONFIG_ARCH_CHIP_STM32F103RB=y
+# CONFIG_ARCH_CHIP_STM32F103RC is not set
+# CONFIG_ARCH_CHIP_STM32F103RD is not set
+# CONFIG_ARCH_CHIP_STM32F103RE is not set
+# CONFIG_ARCH_CHIP_STM32F103RG is not set
+# CONFIG_ARCH_CHIP_STM32F103V8 is not set
+# CONFIG_ARCH_CHIP_STM32F103VB is not set
+# CONFIG_ARCH_CHIP_STM32F103VC is not set
+# CONFIG_ARCH_CHIP_STM32F103VE is not set
+# CONFIG_ARCH_CHIP_STM32F103ZE is not set
+# CONFIG_ARCH_CHIP_STM32F105VB is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F207ZE is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F372C8 is not set
+# CONFIG_ARCH_CHIP_STM32F372R8 is not set
+# CONFIG_ARCH_CHIP_STM32F372V8 is not set
+# CONFIG_ARCH_CHIP_STM32F372CB is not set
+# CONFIG_ARCH_CHIP_STM32F372RB is not set
+# CONFIG_ARCH_CHIP_STM32F372VB is not set
+# CONFIG_ARCH_CHIP_STM32F372CC is not set
+# CONFIG_ARCH_CHIP_STM32F372RC is not set
+# CONFIG_ARCH_CHIP_STM32F372VC is not set
+# CONFIG_ARCH_CHIP_STM32F373C8 is not set
+# CONFIG_ARCH_CHIP_STM32F373R8 is not set
+# CONFIG_ARCH_CHIP_STM32F373V8 is not set
+# CONFIG_ARCH_CHIP_STM32F373CB is not set
+# CONFIG_ARCH_CHIP_STM32F373RB is not set
+# CONFIG_ARCH_CHIP_STM32F373VB is not set
+# CONFIG_ARCH_CHIP_STM32F373CC is not set
+# CONFIG_ARCH_CHIP_STM32F373RC is not set
+# CONFIG_ARCH_CHIP_STM32F373VC is not set
+# CONFIG_ARCH_CHIP_STM32F401RE is not set
+# CONFIG_ARCH_CHIP_STM32F411RE is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+# CONFIG_ARCH_CHIP_STM32F427V is not set
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_ARCH_CHIP_STM32F429V is not set
+# CONFIG_ARCH_CHIP_STM32F429Z is not set
+# CONFIG_ARCH_CHIP_STM32F429I is not set
+# CONFIG_ARCH_CHIP_STM32F429B is not set
+# CONFIG_ARCH_CHIP_STM32F429N is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_USBACCESSLINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F207 is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F37XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+# CONFIG_STM32_STM32F401 is not set
+# CONFIG_STM32_STM32F411 is not set
+# CONFIG_STM32_STM32F405 is not set
+# CONFIG_STM32_STM32F407 is not set
+# CONFIG_STM32_STM32F427 is not set
+# CONFIG_STM32_STM32F429 is not set
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_HAVE_CCM is not set
+CONFIG_STM32_HAVE_USBDEV=y
+# CONFIG_STM32_HAVE_OTGFS is not set
+# CONFIG_STM32_HAVE_FSMC is not set
+CONFIG_STM32_HAVE_USART3=y
+CONFIG_STM32_HAVE_UART4=y
+CONFIG_STM32_HAVE_UART5=y
+# CONFIG_STM32_HAVE_USART6 is not set
+# CONFIG_STM32_HAVE_UART7 is not set
+# CONFIG_STM32_HAVE_UART8 is not set
+CONFIG_STM32_HAVE_TIM1=y
+CONFIG_STM32_HAVE_TIM5=y
+CONFIG_STM32_HAVE_TIM6=y
+CONFIG_STM32_HAVE_TIM7=y
+CONFIG_STM32_HAVE_TIM8=y
+# CONFIG_STM32_HAVE_TIM9 is not set
+# CONFIG_STM32_HAVE_TIM10 is not set
+# CONFIG_STM32_HAVE_TIM11 is not set
+# CONFIG_STM32_HAVE_TIM12 is not set
+# CONFIG_STM32_HAVE_TIM13 is not set
+# CONFIG_STM32_HAVE_TIM14 is not set
+# CONFIG_STM32_HAVE_TIM15 is not set
+# CONFIG_STM32_HAVE_TIM16 is not set
+# CONFIG_STM32_HAVE_TIM17 is not set
+CONFIG_STM32_HAVE_ADC2=y
+CONFIG_STM32_HAVE_ADC3=y
+# CONFIG_STM32_HAVE_ADC4 is not set
+CONFIG_STM32_HAVE_CAN1=y
+# CONFIG_STM32_HAVE_CAN2 is not set
+# CONFIG_STM32_HAVE_RNG is not set
+# CONFIG_STM32_HAVE_ETHMAC is not set
+CONFIG_STM32_HAVE_SPI2=y
+CONFIG_STM32_HAVE_SPI3=y
+# CONFIG_STM32_HAVE_SPI4 is not set
+# CONFIG_STM32_HAVE_SPI5 is not set
+# CONFIG_STM32_HAVE_SPI6 is not set
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+# CONFIG_STM32_DMA1 is not set
+# CONFIG_STM32_DMA2 is not set
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+# CONFIG_STM32_PWR is not set
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+CONFIG_STM32_TIM1=y
+# CONFIG_STM32_TIM2 is not set
+# CONFIG_STM32_TIM3 is not set
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USB is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+CONFIG_STM32_CAN1_REMAP1=y
+# CONFIG_STM32_TIM1_NO_REMAP is not set
+# CONFIG_STM32_TIM1_FULL_REMAP is not set
+CONFIG_STM32_TIM1_PARTIAL_REMAP=y
+# CONFIG_STM32_USART1_REMAP is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+# CONFIG_STM32_FORCEPOWER is not set
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_TIM1_PWM is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+# CONFIG_SERIAL_DISABLE_REORDERING is not set
+# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+# CONFIG_STM32_HAVE_RTC_COUNTER is not set
+# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
+
+#
+# USB FS Host Configuration
+#
+
+#
+# USB HS Host Configuration
+#
+
+#
+# USB Host Debug Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+# CONFIG_ARCH_DMA is not set
+CONFIG_ARCH_HAVE_IRQPRIO=y
+# CONFIG_ARCH_L2CACHE is not set
+# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
+# CONFIG_ARCH_HAVE_ADDRENV is not set
+# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
+CONFIG_ARCH_HAVE_VFORK=y
+# CONFIG_ARCH_HAVE_MMU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARCH_NAND_HWECC is not set
+# CONFIG_ARCH_HAVE_EXTCLK is not set
+# CONFIG_ARCH_USE_MPU is not set
+# CONFIG_ARCH_IRQPRIO is not set
+# CONFIG_ARCH_STACKDUMP is not set
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_IDLE_CUSTOM is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=5483
+# CONFIG_ARCH_CALIBRATION is not set
+
+#
+# Interrupt options
+#
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=1024
+CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
+# CONFIG_ARCH_HIPRI_INTERRUPT is not set
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Boot Memory Configuration
+#
+CONFIG_RAM_START=0x20000000
+CONFIG_RAM_SIZE=20480
+# CONFIG_ARCH_HAVE_SDRAM is not set
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_MAPLE is not set
+CONFIG_ARCH_BOARD_PX4CANNODE_V1=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="px4cannode-v1"
+
+#
+# Common Board Options
+#
+CONFIG_ARCH_HAVE_LEDS=y
+# CONFIG_ARCH_LEDS is not set
+CONFIG_ARCH_HAVE_BUTTONS=y
+# CONFIG_ARCH_BUTTONS is not set
+CONFIG_ARCH_HAVE_IRQBUTTONS=y
+CONFIG_BOARD_HAS_PROBES=y
+CONFIG_BOARD_USE_PROBES=y
+
+#
+# Board-Specific Options
+#
+# CONFIG_LIB_BOARDCTL is not set
+
+#
+# RTOS Features
+#
+CONFIG_DISABLE_OS_API=y
+CONFIG_DISABLE_POSIX_TIMERS=y
+CONFIG_DISABLE_PTHREAD=y
+CONFIG_DISABLE_SIGNALS=y
+CONFIG_DISABLE_MQUEUE=y
+CONFIG_DISABLE_ENVIRON=y
+
+#
+# Clocks and Timers
+#
+CONFIG_USEC_PER_TICK=10000
+# CONFIG_SYSTEM_TIME64 is not set
+# CONFIG_CLOCK_MONOTONIC is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2014
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=30
+CONFIG_MAX_WDOGPARMS=1
+CONFIG_PREALLOC_WDOGS=1
+CONFIG_WDOG_INTRESERVE=0
+CONFIG_PREALLOC_TIMERS=0
+
+#
+# Tasks and Scheduling
+#
+# CONFIG_INIT_NONE is not set
+CONFIG_INIT_ENTRYPOINT=y
+CONFIG_USER_ENTRYPOINT="main"
+CONFIG_RR_INTERVAL=0
+CONFIG_TASK_NAME_SIZE=0
+CONFIG_MAX_TASKS=0
+# CONFIG_SCHED_HAVE_PARENT is not set
+# CONFIG_SCHED_WAITPID is not set
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+# CONFIG_SCHED_INSTRUMENTATION is not set
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
+CONFIG_FDCLONE_DISABLE=y
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_NFILE_DESCRIPTORS=3
+CONFIG_NFILE_STREAMS=0
+CONFIG_NAME_MAX=8
+# CONFIG_PRIORITY_INHERITANCE is not set
+
+#
+# RTOS hooks
+#
+# CONFIG_BOARD_INITIALIZE is not set
+# CONFIG_BOARD_INITTHREAD is not set
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+
+#
+# Work Queue Support
+#
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=1024
+CONFIG_USERMAIN_STACKSIZE=880
+CONFIG_PTHREAD_STACK_MIN=256
+CONFIG_PTHREAD_STACK_DEFAULT=464
+# CONFIG_LIB_SYSCALL is not set
+
+#
+# Device Drivers
+#
+CONFIG_DISABLE_POLL=y
+# CONFIG_DEV_NULL is not set
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+
+#
+# Buffering
+#
+# CONFIG_DRVR_WRITEBUFFER is not set
+# CONFIG_DRVR_READAHEAD is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
+# CONFIG_PWM is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C is not set
+# CONFIG_SPI is not set
+# CONFIG_I2S is not set
+
+#
+# Timer Driver Support
+#
+# CONFIG_TIMER is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_VIDEO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_EEPROM is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+# CONFIG_SERCOMM_CONSOLE is not set
+CONFIG_SERIAL=y
+CONFIG_DEV_LOWCONSOLE=y
+# CONFIG_16550_UART is not set
+# CONFIG_ARCH_HAVE_UART is not set
+# CONFIG_ARCH_HAVE_UART0 is not set
+# CONFIG_ARCH_HAVE_UART1 is not set
+# CONFIG_ARCH_HAVE_UART2 is not set
+# CONFIG_ARCH_HAVE_UART3 is not set
+# CONFIG_ARCH_HAVE_UART4 is not set
+# CONFIG_ARCH_HAVE_UART5 is not set
+# CONFIG_ARCH_HAVE_UART6 is not set
+# CONFIG_ARCH_HAVE_UART7 is not set
+# CONFIG_ARCH_HAVE_UART8 is not set
+# CONFIG_ARCH_HAVE_SCI0 is not set
+# CONFIG_ARCH_HAVE_SCI1 is not set
+# CONFIG_ARCH_HAVE_USART0 is not set
+CONFIG_ARCH_HAVE_USART1=y
+# CONFIG_ARCH_HAVE_USART2 is not set
+# CONFIG_ARCH_HAVE_USART3 is not set
+# CONFIG_ARCH_HAVE_USART4 is not set
+# CONFIG_ARCH_HAVE_USART5 is not set
+# CONFIG_ARCH_HAVE_USART6 is not set
+# CONFIG_ARCH_HAVE_USART7 is not set
+# CONFIG_ARCH_HAVE_USART8 is not set
+# CONFIG_ARCH_HAVE_OTHER_UART is not set
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
+# CONFIG_SERIAL_TERMIOS is not set
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_OTHER_SERIAL_CONSOLE is not set
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=32
+CONFIG_USART1_TXBUFSIZE=32
+CONFIG_USART1_BAUD=57600
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+# CONFIG_SYSLOG_CONSOLE is not set
+
+#
+# Networking Support
+#
+# CONFIG_ARCH_HAVE_NET is not set
+# CONFIG_ARCH_HAVE_PHY is not set
+# CONFIG_NET is not set
+
+#
+# Crypto API
+#
+# CONFIG_CRYPTO is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+CONFIG_DISABLE_MOUNTPOINT=y
+CONFIG_DISABLE_PSEUDOFS_OPERATIONS=y
+# CONFIG_FS_READABLE is not set
+# CONFIG_FS_WRITABLE is not set
+# CONFIG_FS_NAMED_SEMAPHORES is not set
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_PROCFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG is not set
+# CONFIG_SYSLOG_TIMESTAMP is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+CONFIG_MM_SMALL=y
+CONFIG_MM_REGIONS=1
+# CONFIG_ARCH_HAVE_HEAP2 is not set
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Loader
+#
+CONFIG_BINFMT_DISABLE=y
+# CONFIG_PIC is not set
+CONFIG_SYMTAB_ORDEREDBYNAME=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+# CONFIG_STDIO_LINEBUFFER is not set
+CONFIG_NUNGET_CHARS=0
+# CONFIG_LIBM is not set
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+# CONFIG_LIBC_IOCTL_VARIADIC is not set
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=768
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=768
+# CONFIG_LIBC_STRERROR is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+# CONFIG_TIME_EXTENDED is not set
+CONFIG_LIB_SENDFILE_BUFSIZE=0
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+# CONFIG_EXAMPLES_NSH is not set
+CONFIG_EXAMPLES_NULL=y
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXTERM is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POLL is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_WEBSERVER is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+# CONFIG_GRAPHICS_TRAVELER is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+# CONFIG_INTERPRETERS_MICROPYTHON is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_PPPD is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+# CONFIG_NSH_LIBRARY is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# Platform-specific Support
+#
+# CONFIG_PLATFORM_CONFIGDATA is not set
+
+#
+# System Libraries and NSH Add-Ons
+#
+# CONFIG_SYSTEM_FREE is not set
+# CONFIG_SYSTEM_CLE is not set
+# CONFIG_SYSTEM_CUTERM is not set
+# CONFIG_SYSTEM_INSTALL is not set
+# CONFIG_SYSTEM_HEX2BIN is not set
+# CONFIG_SYSTEM_INIFILE is not set
+# CONFIG_SYSTEM_RAMTEST is not set
+# CONFIG_SYSTEM_READLINE is not set
+# CONFIG_SYSTEM_POWEROFF is not set
+# CONFIG_SYSTEM_RAMTRON is not set
+# CONFIG_SYSTEM_SDCARD is not set
+# CONFIG_SYSTEM_SUDOKU is not set
+# CONFIG_SYSTEM_SYSINFO is not set
+# CONFIG_SYSTEM_VI is not set
+# CONFIG_SYSTEM_STACKMONITOR is not set
+# CONFIG_SYSTEM_ZMODEM is not set
+
+CONFIG_ARM7_NOEXT_VECTORS=y \ No newline at end of file
diff --git a/nuttx-configs/px4cannode-v1/bootloader/setenv.sh b/nuttx-configs/px4cannode-v1/bootloader/setenv.sh
new file mode 100755
index 000000000..f755f3832
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/bootloader/setenv.sh
@@ -0,0 +1,80 @@
+#!/bin/bash
+# configs/olimexino-stm32/tiny/setenv.sh
+#
+# 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.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
+# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2014q4/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4cannode-v1/include/README.txt b/nuttx-configs/px4cannode-v1/include/README.txt
new file mode 100755
index 000000000..9d81f5166
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/include/README.txt
@@ -0,0 +1,5 @@
+This directory contains header files unique to the PX4 Can Node V1 board
+Currently this is a demo on the OLIMEXINO-STM32
+
+https://www.olimex.com/Products/Duino/STM32/OLIMEXINO-STM32/resources/OLIMEXINO-STM32.pdf
+http://www.mouser.com/ProductDetail/Olimex-Ltd/OLIMEXINO-STM32/?qs=sGAEpiMZZMsUcx5t7XFI3Z5HrEKlvGsZ \ No newline at end of file
diff --git a/nuttx-configs/px4cannode-v1/include/board.h b/nuttx-configs/px4cannode-v1/include/board.h
new file mode 100755
index 000000000..1e8bd31e9
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/include/board.h
@@ -0,0 +1,251 @@
+/************************************************************************************
+ * configs/px4cannode-v1/include/board.h
+ *
+ * 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.
+ *
+ ************************************************************************************/
+
+#ifndef __CONFIGS_PX4CANNODE_V1_INCLUDE_BOARD_H
+#define __CONFIGS_PX4CANNODE_V1_INCLUDE_BOARD_H
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#ifndef __ASSEMBLY__
+# include <stdint.h>
+#endif
+#include "stm32_rcc.h"
+#include "stm32_sdio.h"
+#include "stm32.h"
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Clocking *************************************************************************/
+
+/* HSI - 8 MHz RC factory-trimmed
+ * LSI - 40 KHz RC (30-60KHz, uncalibrated)
+ * HSE - On-board crystal frequency is 8MHz
+ * LSE - 32.768 kHz
+ */
+
+#define STM32_BOARD_XTAL 8000000ul
+
+#define STM32_HSI_FREQUENCY 8000000ul
+#define STM32_LSI_FREQUENCY 40000
+#define STM32_HSE_FREQUENCY STM32_BOARD_XTAL
+#define STM32_LSE_FREQUENCY 32768
+
+/* PLL source is HSE/1, PLL multipler is 9: PLL frequency is 8MHz (XTAL) x 9 = 72MHz */
+
+#define STM32_CFGR_PLLSRC RCC_CFGR_PLLSRC
+#define STM32_CFGR_PLLXTPRE 0
+#define STM32_CFGR_PLLMUL RCC_CFGR_PLLMUL_CLKx9
+#define STM32_PLL_FREQUENCY (9*STM32_BOARD_XTAL)
+
+/* Use the PLL and set the SYSCLK source to be the PLL */
+
+#define STM32_SYSCLK_SW RCC_CFGR_SW_PLL
+#define STM32_SYSCLK_SWS RCC_CFGR_SWS_PLL
+#define STM32_SYSCLK_FREQUENCY STM32_PLL_FREQUENCY
+
+/* AHB clock (HCLK) is SYSCLK (72MHz) */
+
+#define STM32_RCC_CFGR_HPRE RCC_CFGR_HPRE_SYSCLK
+#define STM32_HCLK_FREQUENCY STM32_PLL_FREQUENCY
+#define STM32_BOARD_HCLK STM32_HCLK_FREQUENCY /* same as above, to satisfy compiler */
+
+/* APB2 clock (PCLK2) is HCLK (72MHz) */
+
+#define STM32_RCC_CFGR_PPRE2 RCC_CFGR_PPRE2_HCLK
+#define STM32_PCLK2_FREQUENCY STM32_HCLK_FREQUENCY
+
+/* APB2 timers 1 and 8 will receive PCLK2. */
+
+#define STM32_APB2_TIM1_CLKIN (STM32_PCLK2_FREQUENCY)
+#define STM32_APB2_TIM8_CLKIN (STM32_PCLK2_FREQUENCY)
+
+/* APB1 clock (PCLK1) is HCLK/2 (36MHz) */
+
+#define STM32_RCC_CFGR_PPRE1 RCC_CFGR_PPRE1_HCLKd2
+#define STM32_PCLK1_FREQUENCY (STM32_HCLK_FREQUENCY/2)
+
+/* APB1 timers 2-4 will be twice PCLK1 (I presume the remaining will receive PCLK1) */
+
+#define STM32_APB1_TIM2_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM3_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM4_CLKIN (2*STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM5_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM6_CLKIN (STM32_PCLK1_FREQUENCY)
+#define STM32_APB1_TIM7_CLKIN (STM32_PCLK1_FREQUENCY)
+
+/* USB divider -- Divide PLL clock by 1.5 */
+
+#define STM32_CFGR_USBPRE 0
+
+/* Timer Frequencies, if APBx is set to 1, frequency is same to APBx
+ * otherwise frequency is 2xAPBx.
+ * Note: TIM1,8 are on APB2, others on APB1 */
+
+#define STM32_TIM18_FREQUENCY STM32_HCLK_FREQUENCY
+#define STM32_TIM27_FREQUENCY STM32_HCLK_FREQUENCY
+
+/* Buttons *************************************************************************/
+
+#define BUTTON_BOOT0_BIT (0)
+#define BUTTON_BOOT0_MASK (1<<BUTTON_BOOT0_BIT)
+
+/* Leds *************************************************************************/
+
+/* LED index values for use with board_setled() */
+
+#define BOARD_LED1 0
+#define BOARD_LED_GREEN BOARD_LED1
+#define BOARD_LED2 1
+#define BOARD_LED_YELLOW BOARD_LED2
+#define BOARD_NLEDS 2
+
+/* LED bits for use with board_setleds() */
+
+#define BOARD_LED_GREEN_BIT (1 << BOARD_LED_GREEN)
+#define BOARD_LED_YELLOW_BIT (1 << BOARD_LED_YELLOW)
+
+/* These LEDs are not used by the board port unless CONFIG_ARCH_LEDS is
+ * defined. In that case, the usage by the board port is as follows:
+ *
+ * SYMBOL Meaning LED state
+ * Green Yellow
+ * ------------------------ -------------------------- ------ ------ */
+
+#define LED_STARTED 0 /* NuttX has been started OFF OFF */
+#define LED_HEAPALLOCATE 1 /* Heap has been allocated OFF OFF */
+#define LED_IRQSENABLED 2 /* Interrupts enabled OFF OFF */
+#define LED_STACKCREATED 3 /* Idle stack created ON OFF */
+#define LED_INIRQ 4 /* In an interrupt N/C ON */
+#define LED_SIGNAL 5 /* In a signal handler N/C ON */
+#define LED_ASSERTION 6 /* An assertion failed N/C ON */
+#define LED_PANIC 7 /* The system has crashed N/C Blinking */
+#define LED_IDLE 8 /* MCU is is sleep mode OFF N/C */
+
+/* Thus if the Green is statically on, NuttX has successfully booted and is,
+ * apparently, running normally. If the YellowLED is flashing at
+ * approximately 2Hz, then a fatal error has been detected and the system
+ * has halted.
+ *
+ * NOTE: That the Yellow is not used after completion of booting and may
+ * be used by other board-specific logic.
+ */
+
+
+#if defined(CONFIG_BOARD_USE_PROBES)
+# define PROBE_N(n) (1<<((n)-1))
+# define PROBE_1 (GPIO_OUTPUT|GPIO_CNF_OUTPP | GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN6)
+# define PROBE_2 (GPIO_OUTPUT|GPIO_CNF_OUTPP | GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN7)
+# define PROBE_3 (GPIO_OUTPUT|GPIO_CNF_OUTPP | GPIO_MODE_50MHz|GPIO_OUTPUT_CLEAR|GPIO_PORTC|GPIO_PIN8)
+
+# define PROBE_INIT(mask) \
+ do { \
+ if ((mask)& PROBE_N(1)) { stm32_configgpio(PROBE_1); } \
+ if ((mask)& PROBE_N(2)) { stm32_configgpio(PROBE_2); } \
+ if ((mask)& PROBE_N(3)) { stm32_configgpio(PROBE_3); } \
+ } while(0)
+
+# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
+# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
+#else
+# define PROBE_INIT(mask)
+# define PROBE(n,s)
+# define PROBE_MARK(n)
+#endif
+
+/************************************************************************************
+ * Public Data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+#undef EXTERN
+#if defined(__cplusplus)
+#define EXTERN extern "C"
+extern "C"
+{
+#else
+#define EXTERN extern
+#endif
+
+/************************************************************************************
+ * Public Function Prototypes
+ ************************************************************************************/
+/************************************************************************************
+ * 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.
+ *
+ ************************************************************************************/
+
+void stm32_boardinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_ledinit, stm32_setled, and stm32_setleds
+ *
+ * Description:
+ * If CONFIG_ARCH_LEDS is defined, then NuttX will control the on-board LEDs. If
+ * CONFIG_ARCH_LEDS is not defined, then the following interfaces are available to
+ * control the LEDs from user applications.
+ *
+ ************************************************************************************/
+
+#ifndef CONFIG_ARCH_LEDS
+void stm32_led_initialize(void);
+void stm32_setled(int led, bool ledon);
+void stm32_setleds(uint8_t ledset);
+#endif
+
+#if !defined(CONFIG_NSH_LIBRARY)
+int app_archinitialize(void);
+#else
+#define app_archinitialize() (-ENOSYS)
+#endif
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+#endif /* __ASSEMBLY__ */
+#endif /* __CONFIGS_PX4CANNODE_V1_INCLUDE_BOARD_H */
diff --git a/nuttx-configs/px4cannode-v1/nsh/Make.defs b/nuttx-configs/px4cannode-v1/nsh/Make.defs
new file mode 100644
index 000000000..25cb18d6e
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/Make.defs
@@ -0,0 +1,172 @@
+############################################################################
+# configs/px4cannode-v1/smallnsh/Make.defs
+#
+# 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.
+#
+############################################################################
+
+include ${TOPDIR}/.config
+include ${TOPDIR}/tools/Config.mk
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+#
+# 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
+
+include ${TOPDIR}/arch/arm/src/armv7-m/Toolchain.defs
+
+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 = ld.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.sh
+ 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}
+
+# optimisation 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 = -Wall \
+ -Wno-sign-compare \
+ -Wextra \
+ -Wdouble-promotion \
+ -Wshadow \
+ -Wfloat-equal \
+ -Wframe-larger-than=1024 \
+ -Wpointer-arith \
+ -Wlogical-op \
+ -Wmissing-declarations \
+ -Wpacked \
+ -Wno-unused-parameter
+# -Wcast-qual - generates spurious noreturn attribute warnings, try again later
+# -Wconversion - would be nice, but too many "risky-but-safe" conversions in the code
+# -Wcast-align - would help catch bad casts in some cases, but generates too many false positives
+
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+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 =
+
diff --git a/nuttx-configs/px4cannode-v1/nsh/defconfig b/nuttx-configs/px4cannode-v1/nsh/defconfig
new file mode 100644
index 000000000..e09cbd89f
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/defconfig
@@ -0,0 +1,1036 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_DEFAULT_SMALL=y
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+CONFIG_BUILD_FLAT=y
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+# CONFIG_UBOOT_UIMAGE is not set
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDINT_H is not set
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+CONFIG_DEBUG=y
+CONFIG_ARCH_HAVE_HEAPCHECK=y
+CONFIG_DEBUG_VERBOSE=y
+
+#
+# Subsystem Debug Options
+#
+# CONFIG_DEBUG_AUDIO is not set
+# CONFIG_DEBUG_BINFMT is not set
+# CONFIG_DEBUG_FS is not set
+# CONFIG_DEBUG_GRAPHICS is not set
+# CONFIG_DEBUG_LIB is not set
+# CONFIG_DEBUG_MM is not set
+# CONFIG_DEBUG_SCHED is not set
+
+#
+# OS Function Debug Options
+#
+# CONFIG_DEBUG_DMA is not set
+# CONFIG_DEBUG_HEAP is not set
+# CONFIG_DEBUG_IRQ is not set
+
+#
+# Driver Debug Options
+#
+# CONFIG_DEBUG_ANALOG is not set
+# CONFIG_DEBUG_GPIO is not set
+CONFIG_ARCH_HAVE_STACKCHECK=y
+CONFIG_STACK_COLORATION=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_ARCH_HAVE_CUSTOMOPT=y
+# CONFIG_DEBUG_NOOPT is not set
+# CONFIG_DEBUG_CUSTOMOPT is not set
+CONFIG_DEBUG_FULLOPT=y
+
+#
+# System Type
+#
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_A1X is not set
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_EFM32 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_TIVA is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAMA5 is not set
+# CONFIG_ARCH_CHIP_SAMD is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+# CONFIG_ARCH_CHIP_SAMV7 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+# CONFIG_ARCH_ARM7TDMI is not set
+# CONFIG_ARCH_ARM926EJS is not set
+# CONFIG_ARCH_ARM920T is not set
+# CONFIG_ARCH_CORTEXM0 is not set
+CONFIG_ARCH_CORTEXM3=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXM7 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+# CONFIG_ARMV7M_LAZYFPU is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+# CONFIG_ARCH_HAVE_DPFPU is not set
+# CONFIG_ARMV7M_MPU is not set
+# CONFIG_DEBUG_HARDFAULT is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_HAVE_ICACHE is not set
+# CONFIG_ARMV7M_HAVE_DCACHE is not set
+# CONFIG_ARMV7M_HAVE_ITCM is not set
+# CONFIG_ARMV7M_HAVE_DTCM is not set
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y
+# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set
+# CONFIG_ARMV7M_STACKCHECK is not set
+# CONFIG_ARMV7M_ITMSYSLOG is not set
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32L162ZD is not set
+# CONFIG_ARCH_CHIP_STM32L162VE is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F102CB is not set
+# CONFIG_ARCH_CHIP_STM32F103T8 is not set
+# CONFIG_ARCH_CHIP_STM32F103TB is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103CB is not set
+# CONFIG_ARCH_CHIP_STM32F103R8 is not set
+CONFIG_ARCH_CHIP_STM32F103RB=y
+# CONFIG_ARCH_CHIP_STM32F103RC is not set
+# CONFIG_ARCH_CHIP_STM32F103RD is not set
+# CONFIG_ARCH_CHIP_STM32F103RE is not set
+# CONFIG_ARCH_CHIP_STM32F103RG is not set
+# CONFIG_ARCH_CHIP_STM32F103V8 is not set
+# CONFIG_ARCH_CHIP_STM32F103VB is not set
+# CONFIG_ARCH_CHIP_STM32F103VC is not set
+# CONFIG_ARCH_CHIP_STM32F103VE is not set
+# CONFIG_ARCH_CHIP_STM32F103ZE is not set
+# CONFIG_ARCH_CHIP_STM32F105VB is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F207ZE is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F372C8 is not set
+# CONFIG_ARCH_CHIP_STM32F372R8 is not set
+# CONFIG_ARCH_CHIP_STM32F372V8 is not set
+# CONFIG_ARCH_CHIP_STM32F372CB is not set
+# CONFIG_ARCH_CHIP_STM32F372RB is not set
+# CONFIG_ARCH_CHIP_STM32F372VB is not set
+# CONFIG_ARCH_CHIP_STM32F372CC is not set
+# CONFIG_ARCH_CHIP_STM32F372RC is not set
+# CONFIG_ARCH_CHIP_STM32F372VC is not set
+# CONFIG_ARCH_CHIP_STM32F373C8 is not set
+# CONFIG_ARCH_CHIP_STM32F373R8 is not set
+# CONFIG_ARCH_CHIP_STM32F373V8 is not set
+# CONFIG_ARCH_CHIP_STM32F373CB is not set
+# CONFIG_ARCH_CHIP_STM32F373RB is not set
+# CONFIG_ARCH_CHIP_STM32F373VB is not set
+# CONFIG_ARCH_CHIP_STM32F373CC is not set
+# CONFIG_ARCH_CHIP_STM32F373RC is not set
+# CONFIG_ARCH_CHIP_STM32F373VC is not set
+# CONFIG_ARCH_CHIP_STM32F401RE is not set
+# CONFIG_ARCH_CHIP_STM32F411RE is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+# CONFIG_ARCH_CHIP_STM32F427V is not set
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_ARCH_CHIP_STM32F429V is not set
+# CONFIG_ARCH_CHIP_STM32F429Z is not set
+# CONFIG_ARCH_CHIP_STM32F429I is not set
+# CONFIG_ARCH_CHIP_STM32F429B is not set
+# CONFIG_ARCH_CHIP_STM32F429N is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_USBACCESSLINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F207 is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F37XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+# CONFIG_STM32_STM32F401 is not set
+# CONFIG_STM32_STM32F411 is not set
+# CONFIG_STM32_STM32F405 is not set
+# CONFIG_STM32_STM32F407 is not set
+# CONFIG_STM32_STM32F427 is not set
+# CONFIG_STM32_STM32F429 is not set
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_HAVE_CCM is not set
+CONFIG_STM32_HAVE_USBDEV=y
+# CONFIG_STM32_HAVE_OTGFS is not set
+# CONFIG_STM32_HAVE_FSMC is not set
+CONFIG_STM32_HAVE_USART3=y
+CONFIG_STM32_HAVE_UART4=y
+CONFIG_STM32_HAVE_UART5=y
+# CONFIG_STM32_HAVE_USART6 is not set
+# CONFIG_STM32_HAVE_UART7 is not set
+# CONFIG_STM32_HAVE_UART8 is not set
+CONFIG_STM32_HAVE_TIM1=y
+CONFIG_STM32_HAVE_TIM5=y
+CONFIG_STM32_HAVE_TIM6=y
+CONFIG_STM32_HAVE_TIM7=y
+CONFIG_STM32_HAVE_TIM8=y
+# CONFIG_STM32_HAVE_TIM9 is not set
+# CONFIG_STM32_HAVE_TIM10 is not set
+# CONFIG_STM32_HAVE_TIM11 is not set
+# CONFIG_STM32_HAVE_TIM12 is not set
+# CONFIG_STM32_HAVE_TIM13 is not set
+# CONFIG_STM32_HAVE_TIM14 is not set
+# CONFIG_STM32_HAVE_TIM15 is not set
+# CONFIG_STM32_HAVE_TIM16 is not set
+# CONFIG_STM32_HAVE_TIM17 is not set
+CONFIG_STM32_HAVE_ADC2=y
+CONFIG_STM32_HAVE_ADC3=y
+# CONFIG_STM32_HAVE_ADC4 is not set
+CONFIG_STM32_HAVE_CAN1=y
+# CONFIG_STM32_HAVE_CAN2 is not set
+# CONFIG_STM32_HAVE_RNG is not set
+# CONFIG_STM32_HAVE_ETHMAC is not set
+CONFIG_STM32_HAVE_SPI2=y
+CONFIG_STM32_HAVE_SPI3=y
+# CONFIG_STM32_HAVE_SPI4 is not set
+# CONFIG_STM32_HAVE_SPI5 is not set
+# CONFIG_STM32_HAVE_SPI6 is not set
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USB is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_TIM3_NO_REMAP is not set
+CONFIG_STM32_CAN1_REMAP1=y
+CONFIG_STM32_TIM3_FULL_REMAP=y
+# CONFIG_STM32_TIM3_PARTIAL_REMAP is not set
+# CONFIG_STM32_USART1_REMAP is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_FORCEPOWER=y
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_DMACAPABLE is not set
+# CONFIG_STM32_TIM3_PWM is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+CONFIG_USART1_RXDMA=y
+CONFIG_SERIAL_DISABLE_REORDERING=y
+# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
+
+#
+# USB FS Host Configuration
+#
+
+#
+# USB HS Host Configuration
+#
+
+#
+# USB Host Debug Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_HAVE_IRQPRIO=y
+# CONFIG_ARCH_L2CACHE is not set
+# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
+# CONFIG_ARCH_HAVE_ADDRENV is not set
+# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
+CONFIG_ARCH_HAVE_VFORK=y
+# CONFIG_ARCH_HAVE_MMU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARCH_NAND_HWECC is not set
+# CONFIG_ARCH_HAVE_EXTCLK is not set
+# CONFIG_ARCH_USE_MPU is not set
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_IDLE_CUSTOM is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=5483
+# CONFIG_ARCH_CALIBRATION is not set
+
+#
+# Interrupt options
+#
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=360
+CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
+CONFIG_ARCH_HIPRI_INTERRUPT=y
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Boot Memory Configuration
+#
+CONFIG_RAM_START=0x20000000
+CONFIG_RAM_SIZE=20480
+# CONFIG_ARCH_HAVE_SDRAM is not set
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_MAPLE is not set
+CONFIG_ARCH_BOARD_PX4CANNODE_V1=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="px4cannode-v1"
+
+#
+# Common Board Options
+#
+CONFIG_ARCH_HAVE_LEDS=y
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_HAVE_BUTTONS=y
+CONFIG_ARCH_BUTTONS=y
+CONFIG_ARCH_HAVE_IRQBUTTONS=y
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Clocks and Timers
+#
+CONFIG_USEC_PER_TICK=10000
+# CONFIG_SYSTEM_TIME64 is not set
+# CONFIG_CLOCK_MONOTONIC is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2014
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=20
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_WDOG_INTRESERVE=2
+CONFIG_PREALLOC_TIMERS=2
+
+#
+# Tasks and Scheduling
+#
+# CONFIG_INIT_NONE is not set
+CONFIG_INIT_ENTRYPOINT=y
+# CONFIG_INIT_FILEPATH is not set
+CONFIG_USER_ENTRYPOINT="uavcannode_start"
+CONFIG_RR_INTERVAL=0
+CONFIG_TASK_NAME_SIZE=12
+CONFIG_MAX_TASKS=4
+# CONFIG_SCHED_HAVE_PARENT is not set
+CONFIG_SCHED_WAITPID=y
+
+#
+# Pthread Options
+#
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_NPTHREAD_KEYS=0
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+CONFIG_SCHED_INSTRUMENTATION=y
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_NFILE_DESCRIPTORS=5
+CONFIG_NFILE_STREAMS=1
+CONFIG_NAME_MAX=8
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=4
+CONFIG_SEM_NNESTPRIO=4
+
+#
+# RTOS hooks
+#
+CONFIG_BOARD_INITIALIZE=y
+# CONFIG_BOARD_INITTHREAD is not set
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+# CONFIG_SCHED_ONEXIT is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+
+#
+# POSIX Message Queue Options
+#
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=8
+
+#
+# Work Queue Support
+#
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_SCHED_HPWORK is not set
+# CONFIG_SCHED_LPWORK is not set
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=272
+CONFIG_USERMAIN_STACKSIZE=920
+CONFIG_PTHREAD_STACK_MIN=516
+CONFIG_PTHREAD_STACK_DEFAULT=516
+# CONFIG_LIB_SYSCALL is not set
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+# CONFIG_DEV_NULL is not set
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+
+#
+# Buffering
+#
+# CONFIG_DRVR_WRITEBUFFER is not set
+# CONFIG_DRVR_READAHEAD is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
+# CONFIG_PWM is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C is not set
+# CONFIG_SPI is not set
+# CONFIG_I2S is not set
+# CONFIG_TIMER is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_VIDEO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_EEPROM is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+# CONFIG_SERCOMM_CONSOLE is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+# CONFIG_16550_UART is not set
+# CONFIG_ARCH_HAVE_UART is not set
+# CONFIG_ARCH_HAVE_UART0 is not set
+# CONFIG_ARCH_HAVE_UART1 is not set
+# CONFIG_ARCH_HAVE_UART2 is not set
+# CONFIG_ARCH_HAVE_UART3 is not set
+# CONFIG_ARCH_HAVE_UART4 is not set
+# CONFIG_ARCH_HAVE_UART5 is not set
+# CONFIG_ARCH_HAVE_UART6 is not set
+# CONFIG_ARCH_HAVE_UART7 is not set
+# CONFIG_ARCH_HAVE_UART8 is not set
+# CONFIG_ARCH_HAVE_SCI0 is not set
+# CONFIG_ARCH_HAVE_SCI1 is not set
+# CONFIG_ARCH_HAVE_USART0 is not set
+CONFIG_ARCH_HAVE_USART1=y
+# CONFIG_ARCH_HAVE_USART2 is not set
+# CONFIG_ARCH_HAVE_USART3 is not set
+# CONFIG_ARCH_HAVE_USART4 is not set
+# CONFIG_ARCH_HAVE_USART5 is not set
+# CONFIG_ARCH_HAVE_USART6 is not set
+# CONFIG_ARCH_HAVE_USART7 is not set
+# CONFIG_ARCH_HAVE_USART8 is not set
+# CONFIG_ARCH_HAVE_OTHER_UART is not set
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
+CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
+# CONFIG_SERIAL_TERMIOS is not set
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_OTHER_SERIAL_CONSOLE is not set
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=32
+CONFIG_USART1_TXBUFSIZE=32
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+# CONFIG_SYSLOG_CONSOLE is not set
+
+#
+# Networking Support
+#
+# CONFIG_ARCH_HAVE_NET is not set
+# CONFIG_ARCH_HAVE_PHY is not set
+# CONFIG_NET is not set
+
+#
+# Crypto API
+#
+# CONFIG_CRYPTO is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_AUTOMOUNTER is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_FS_READABLE is not set
+# CONFIG_FS_WRITABLE is not set
+# CONFIG_FS_NAMED_SEMAPHORES is not set
+CONFIG_FS_MQUEUE_MPATH="/var/mqueue"
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_FAT is not set
+# CONFIG_FS_NXFFS is not set
+# CONFIG_FS_ROMFS is not set
+# CONFIG_FS_SMARTFS is not set
+# CONFIG_FS_BINFS is not set
+# CONFIG_FS_PROCFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG is not set
+# CONFIG_SYSLOG_TIMESTAMP is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+CONFIG_MM_SMALL=y
+CONFIG_MM_REGIONS=1
+# CONFIG_ARCH_HAVE_HEAP2 is not set
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Loader
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+CONFIG_SYMTAB_ORDEREDBYNAME=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+# CONFIG_LIBC_IOCTL_VARIADIC is not set
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=394
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=394
+# CONFIG_LIBC_STRERROR is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+# CONFIG_LIBC_LOCALTIME is not set
+CONFIG_LIB_SENDFILE_BUFSIZE=0
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=392
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+# CONFIG_EXAMPLES_NSH is not set
+CONFIG_EXAMPLES_NULL=y
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXTERM is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POLL is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_WEBSERVER is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+# CONFIG_GRAPHICS_TRAVELER is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+# CONFIG_INTERPRETERS_MICROPYTHON is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_NETLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+# CONFIG_NETUTILS_PPPD is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+# CONFIG_NSH_LIBRARY is not set
+# CONFIG_NSH_READLINE is not set
+# CONFIG_NSH_CLE is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# Platform-specific Support
+#
+# CONFIG_PLATFORM_CONFIGDATA is not set
+
+#
+# System Libraries and NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# EMACS-like Command Line Editor
+#
+# CONFIG_SYSTEM_CLE is not set
+
+#
+# CU Minimal Terminal
+#
+# CONFIG_SYSTEM_CUTERM is not set
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# Intel HEX to binary conversion
+#
+# CONFIG_SYSTEM_HEX2BIN is not set
+
+#
+# I2C tool
+#
+
+#
+# INI File Parser
+#
+# CONFIG_SYSTEM_INIFILE is not set
+
+#
+# NxPlayer media player library / command Line
+#
+
+#
+# RAM test
+#
+# CONFIG_SYSTEM_RAMTEST is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# P-Code Support
+#
+
+#
+# PHY Tool
+#
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sudoku
+#
+# CONFIG_SYSTEM_SUDOKU is not set
+
+#
+# Sysinfo
+#
+# CONFIG_SYSTEM_SYSINFO is not set
+
+#
+# Temperature
+#
+
+#
+# VI Work-Alike Editor
+#
+# CONFIG_SYSTEM_VI is not set
+
+#
+# Stack Monitor
+#
+# CONFIG_SYSTEM_STACKMONITOR is not set
+
+#
+# USB CDC/ACM Device Commands
+#
+
+#
+# USB Composite Device Commands
+#
+
+#
+# USB Mass Storage Device Commands
+#
+
+#
+# USB Monitor
+#
+
+#
+# Zmodem Commands
+#
+# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx-configs/px4cannode-v1/nsh/defconfig.nonsh b/nuttx-configs/px4cannode-v1/nsh/defconfig.nonsh
new file mode 100644
index 000000000..722cfb3f4
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/defconfig.nonsh
@@ -0,0 +1,1036 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_DEFAULT_SMALL=y
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+CONFIG_BUILD_FLAT=y
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+# CONFIG_UBOOT_UIMAGE is not set
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDINT_H is not set
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+CONFIG_DEBUG=y
+CONFIG_ARCH_HAVE_HEAPCHECK=y
+CONFIG_DEBUG_VERBOSE=y
+
+#
+# Subsystem Debug Options
+#
+# CONFIG_DEBUG_AUDIO is not set
+# CONFIG_DEBUG_BINFMT is not set
+# CONFIG_DEBUG_FS is not set
+# CONFIG_DEBUG_GRAPHICS is not set
+# CONFIG_DEBUG_LIB is not set
+# CONFIG_DEBUG_MM is not set
+# CONFIG_DEBUG_SCHED is not set
+
+#
+# OS Function Debug Options
+#
+# CONFIG_DEBUG_DMA is not set
+# CONFIG_DEBUG_HEAP is not set
+# CONFIG_DEBUG_IRQ is not set
+
+#
+# Driver Debug Options
+#
+# CONFIG_DEBUG_ANALOG is not set
+# CONFIG_DEBUG_GPIO is not set
+CONFIG_ARCH_HAVE_STACKCHECK=y
+CONFIG_STACK_COLORATION=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_ARCH_HAVE_CUSTOMOPT=y
+# CONFIG_DEBUG_NOOPT is not set
+# CONFIG_DEBUG_CUSTOMOPT is not set
+CONFIG_DEBUG_FULLOPT=y
+
+#
+# System Type
+#
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_A1X is not set
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_EFM32 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_TIVA is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAMA5 is not set
+# CONFIG_ARCH_CHIP_SAMD is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+# CONFIG_ARCH_CHIP_SAMV7 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+# CONFIG_ARCH_ARM7TDMI is not set
+# CONFIG_ARCH_ARM926EJS is not set
+# CONFIG_ARCH_ARM920T is not set
+# CONFIG_ARCH_CORTEXM0 is not set
+CONFIG_ARCH_CORTEXM3=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXM7 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+# CONFIG_ARMV7M_LAZYFPU is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+# CONFIG_ARCH_HAVE_DPFPU is not set
+# CONFIG_ARMV7M_MPU is not set
+# CONFIG_DEBUG_HARDFAULT is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_HAVE_ICACHE is not set
+# CONFIG_ARMV7M_HAVE_DCACHE is not set
+# CONFIG_ARMV7M_HAVE_ITCM is not set
+# CONFIG_ARMV7M_HAVE_DTCM is not set
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y
+# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set
+# CONFIG_ARMV7M_STACKCHECK is not set
+# CONFIG_ARMV7M_ITMSYSLOG is not set
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32L162ZD is not set
+# CONFIG_ARCH_CHIP_STM32L162VE is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F102CB is not set
+# CONFIG_ARCH_CHIP_STM32F103T8 is not set
+# CONFIG_ARCH_CHIP_STM32F103TB is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103CB is not set
+# CONFIG_ARCH_CHIP_STM32F103R8 is not set
+CONFIG_ARCH_CHIP_STM32F103RB=y
+# CONFIG_ARCH_CHIP_STM32F103RC is not set
+# CONFIG_ARCH_CHIP_STM32F103RD is not set
+# CONFIG_ARCH_CHIP_STM32F103RE is not set
+# CONFIG_ARCH_CHIP_STM32F103RG is not set
+# CONFIG_ARCH_CHIP_STM32F103V8 is not set
+# CONFIG_ARCH_CHIP_STM32F103VB is not set
+# CONFIG_ARCH_CHIP_STM32F103VC is not set
+# CONFIG_ARCH_CHIP_STM32F103VE is not set
+# CONFIG_ARCH_CHIP_STM32F103ZE is not set
+# CONFIG_ARCH_CHIP_STM32F105VB is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F207ZE is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F372C8 is not set
+# CONFIG_ARCH_CHIP_STM32F372R8 is not set
+# CONFIG_ARCH_CHIP_STM32F372V8 is not set
+# CONFIG_ARCH_CHIP_STM32F372CB is not set
+# CONFIG_ARCH_CHIP_STM32F372RB is not set
+# CONFIG_ARCH_CHIP_STM32F372VB is not set
+# CONFIG_ARCH_CHIP_STM32F372CC is not set
+# CONFIG_ARCH_CHIP_STM32F372RC is not set
+# CONFIG_ARCH_CHIP_STM32F372VC is not set
+# CONFIG_ARCH_CHIP_STM32F373C8 is not set
+# CONFIG_ARCH_CHIP_STM32F373R8 is not set
+# CONFIG_ARCH_CHIP_STM32F373V8 is not set
+# CONFIG_ARCH_CHIP_STM32F373CB is not set
+# CONFIG_ARCH_CHIP_STM32F373RB is not set
+# CONFIG_ARCH_CHIP_STM32F373VB is not set
+# CONFIG_ARCH_CHIP_STM32F373CC is not set
+# CONFIG_ARCH_CHIP_STM32F373RC is not set
+# CONFIG_ARCH_CHIP_STM32F373VC is not set
+# CONFIG_ARCH_CHIP_STM32F401RE is not set
+# CONFIG_ARCH_CHIP_STM32F411RE is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+# CONFIG_ARCH_CHIP_STM32F427V is not set
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_ARCH_CHIP_STM32F429V is not set
+# CONFIG_ARCH_CHIP_STM32F429Z is not set
+# CONFIG_ARCH_CHIP_STM32F429I is not set
+# CONFIG_ARCH_CHIP_STM32F429B is not set
+# CONFIG_ARCH_CHIP_STM32F429N is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_USBACCESSLINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F207 is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F37XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+# CONFIG_STM32_STM32F401 is not set
+# CONFIG_STM32_STM32F411 is not set
+# CONFIG_STM32_STM32F405 is not set
+# CONFIG_STM32_STM32F407 is not set
+# CONFIG_STM32_STM32F427 is not set
+# CONFIG_STM32_STM32F429 is not set
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_HAVE_CCM is not set
+CONFIG_STM32_HAVE_USBDEV=y
+# CONFIG_STM32_HAVE_OTGFS is not set
+# CONFIG_STM32_HAVE_FSMC is not set
+CONFIG_STM32_HAVE_USART3=y
+CONFIG_STM32_HAVE_UART4=y
+CONFIG_STM32_HAVE_UART5=y
+# CONFIG_STM32_HAVE_USART6 is not set
+# CONFIG_STM32_HAVE_UART7 is not set
+# CONFIG_STM32_HAVE_UART8 is not set
+CONFIG_STM32_HAVE_TIM1=y
+CONFIG_STM32_HAVE_TIM5=y
+CONFIG_STM32_HAVE_TIM6=y
+CONFIG_STM32_HAVE_TIM7=y
+CONFIG_STM32_HAVE_TIM8=y
+# CONFIG_STM32_HAVE_TIM9 is not set
+# CONFIG_STM32_HAVE_TIM10 is not set
+# CONFIG_STM32_HAVE_TIM11 is not set
+# CONFIG_STM32_HAVE_TIM12 is not set
+# CONFIG_STM32_HAVE_TIM13 is not set
+# CONFIG_STM32_HAVE_TIM14 is not set
+# CONFIG_STM32_HAVE_TIM15 is not set
+# CONFIG_STM32_HAVE_TIM16 is not set
+# CONFIG_STM32_HAVE_TIM17 is not set
+CONFIG_STM32_HAVE_ADC2=y
+CONFIG_STM32_HAVE_ADC3=y
+# CONFIG_STM32_HAVE_ADC4 is not set
+CONFIG_STM32_HAVE_CAN1=y
+# CONFIG_STM32_HAVE_CAN2 is not set
+# CONFIG_STM32_HAVE_RNG is not set
+# CONFIG_STM32_HAVE_ETHMAC is not set
+CONFIG_STM32_HAVE_SPI2=y
+CONFIG_STM32_HAVE_SPI3=y
+# CONFIG_STM32_HAVE_SPI4 is not set
+# CONFIG_STM32_HAVE_SPI5 is not set
+# CONFIG_STM32_HAVE_SPI6 is not set
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+# CONFIG_STM32_SPI2 is not set
+# CONFIG_STM32_SPI3 is not set
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USB is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_TIM3_NO_REMAP is not set
+CONFIG_STM32_TIM3_FULL_REMAP=y
+# CONFIG_STM32_TIM3_PARTIAL_REMAP is not set
+# CONFIG_STM32_USART1_REMAP is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_FORCEPOWER=y
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_DMACAPABLE is not set
+# CONFIG_STM32_TIM3_PWM is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+CONFIG_USART1_RXDMA=y
+CONFIG_SERIAL_DISABLE_REORDERING=y
+# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
+
+#
+# USB FS Host Configuration
+#
+
+#
+# USB HS Host Configuration
+#
+
+#
+# USB Host Debug Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_HAVE_IRQPRIO=y
+# CONFIG_ARCH_L2CACHE is not set
+# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
+# CONFIG_ARCH_HAVE_ADDRENV is not set
+# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
+CONFIG_ARCH_HAVE_VFORK=y
+# CONFIG_ARCH_HAVE_MMU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARCH_NAND_HWECC is not set
+# CONFIG_ARCH_HAVE_EXTCLK is not set
+# CONFIG_ARCH_USE_MPU is not set
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_IDLE_CUSTOM is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=5483
+# CONFIG_ARCH_CALIBRATION is not set
+
+#
+# Interrupt options
+#
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=360
+CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
+CONFIG_ARCH_HIPRI_INTERRUPT=y
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Boot Memory Configuration
+#
+CONFIG_RAM_START=0x20000000
+CONFIG_RAM_SIZE=20480
+# CONFIG_ARCH_HAVE_SDRAM is not set
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_MAPLE is not set
+# CONFIG_ARCH_BOARD_OLIMEXINO_STM32 is not set
+CONFIG_ARCH_BOARD_CUSTOM=y
+
+#
+# Custom Board Configuration
+#
+CONFIG_ARCH_BOARD_CUSTOM_DIR=""
+# CONFIG_BOARD_CRASHDUMP is not set
+# CONFIG_BOARD_CUSTOM_LEDS is not set
+# CONFIG_BOARD_CUSTOM_BUTTONS is not set
+
+#
+# Common Board Options
+#
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Clocks and Timers
+#
+CONFIG_USEC_PER_TICK=10000
+# CONFIG_SYSTEM_TIME64 is not set
+# CONFIG_CLOCK_MONOTONIC is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2014
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=20
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_WDOG_INTRESERVE=2
+CONFIG_PREALLOC_TIMERS=2
+
+#
+# Tasks and Scheduling
+#
+# CONFIG_INIT_NONE is not set
+CONFIG_INIT_ENTRYPOINT=y
+# CONFIG_INIT_FILEPATH is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_RR_INTERVAL=0
+CONFIG_TASK_NAME_SIZE=12
+CONFIG_MAX_TASKS=4
+# CONFIG_SCHED_HAVE_PARENT is not set
+CONFIG_SCHED_WAITPID=y
+
+#
+# Pthread Options
+#
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_NPTHREAD_KEYS=0
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+CONFIG_SCHED_INSTRUMENTATION=y
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_NFILE_DESCRIPTORS=5
+CONFIG_NFILE_STREAMS=1
+CONFIG_NAME_MAX=8
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=4
+CONFIG_SEM_NNESTPRIO=4
+
+#
+# RTOS hooks
+#
+CONFIG_BOARD_INITIALIZE=y
+# CONFIG_BOARD_INITTHREAD is not set
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+# CONFIG_SCHED_ONEXIT is not set
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+
+#
+# POSIX Message Queue Options
+#
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=8
+
+#
+# Work Queue Support
+#
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_SCHED_HPWORK is not set
+# CONFIG_SCHED_LPWORK is not set
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=272
+CONFIG_USERMAIN_STACKSIZE=680
+CONFIG_PTHREAD_STACK_MIN=516
+CONFIG_PTHREAD_STACK_DEFAULT=516
+# CONFIG_LIB_SYSCALL is not set
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+# CONFIG_DEV_NULL is not set
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+
+#
+# Buffering
+#
+# CONFIG_DRVR_WRITEBUFFER is not set
+# CONFIG_DRVR_READAHEAD is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
+# CONFIG_PWM is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C is not set
+# CONFIG_SPI is not set
+# CONFIG_I2S is not set
+# CONFIG_TIMER is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_VIDEO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_EEPROM is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+# CONFIG_SERCOMM_CONSOLE is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+# CONFIG_16550_UART is not set
+# CONFIG_ARCH_HAVE_UART is not set
+# CONFIG_ARCH_HAVE_UART0 is not set
+# CONFIG_ARCH_HAVE_UART1 is not set
+# CONFIG_ARCH_HAVE_UART2 is not set
+# CONFIG_ARCH_HAVE_UART3 is not set
+# CONFIG_ARCH_HAVE_UART4 is not set
+# CONFIG_ARCH_HAVE_UART5 is not set
+# CONFIG_ARCH_HAVE_UART6 is not set
+# CONFIG_ARCH_HAVE_UART7 is not set
+# CONFIG_ARCH_HAVE_UART8 is not set
+# CONFIG_ARCH_HAVE_SCI0 is not set
+# CONFIG_ARCH_HAVE_SCI1 is not set
+# CONFIG_ARCH_HAVE_USART0 is not set
+CONFIG_ARCH_HAVE_USART1=y
+# CONFIG_ARCH_HAVE_USART2 is not set
+# CONFIG_ARCH_HAVE_USART3 is not set
+# CONFIG_ARCH_HAVE_USART4 is not set
+# CONFIG_ARCH_HAVE_USART5 is not set
+# CONFIG_ARCH_HAVE_USART6 is not set
+# CONFIG_ARCH_HAVE_USART7 is not set
+# CONFIG_ARCH_HAVE_USART8 is not set
+# CONFIG_ARCH_HAVE_OTHER_UART is not set
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
+CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
+# CONFIG_SERIAL_TERMIOS is not set
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_OTHER_SERIAL_CONSOLE is not set
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=32
+CONFIG_USART1_TXBUFSIZE=32
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+# CONFIG_SYSLOG_CONSOLE is not set
+
+#
+# Networking Support
+#
+# CONFIG_ARCH_HAVE_NET is not set
+# CONFIG_ARCH_HAVE_PHY is not set
+# CONFIG_NET is not set
+
+#
+# Crypto API
+#
+# CONFIG_CRYPTO is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_AUTOMOUNTER is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_FS_READABLE is not set
+# CONFIG_FS_WRITABLE is not set
+# CONFIG_FS_NAMED_SEMAPHORES is not set
+CONFIG_FS_MQUEUE_MPATH="/var/mqueue"
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_FAT is not set
+# CONFIG_FS_NXFFS is not set
+# CONFIG_FS_ROMFS is not set
+# CONFIG_FS_SMARTFS is not set
+# CONFIG_FS_BINFS is not set
+# CONFIG_FS_PROCFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG is not set
+# CONFIG_SYSLOG_TIMESTAMP is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+CONFIG_MM_SMALL=y
+CONFIG_MM_REGIONS=1
+# CONFIG_ARCH_HAVE_HEAP2 is not set
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Loader
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+CONFIG_SYMTAB_ORDEREDBYNAME=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+# CONFIG_LIBC_IOCTL_VARIADIC is not set
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=394
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=394
+# CONFIG_LIBC_STRERROR is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+# CONFIG_LIBC_LOCALTIME is not set
+CONFIG_LIB_SENDFILE_BUFSIZE=0
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=392
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+# CONFIG_EXAMPLES_NSH is not set
+CONFIG_EXAMPLES_NULL=y
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXTERM is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POLL is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_WEBSERVER is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+# CONFIG_GRAPHICS_TRAVELER is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+# CONFIG_INTERPRETERS_MICROPYTHON is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_NETLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+# CONFIG_NETUTILS_PPPD is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+# CONFIG_NSH_LIBRARY is not set
+# CONFIG_NSH_READLINE is not set
+# CONFIG_NSH_CLE is not set
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# Platform-specific Support
+#
+# CONFIG_PLATFORM_CONFIGDATA is not set
+
+#
+# System Libraries and NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# EMACS-like Command Line Editor
+#
+# CONFIG_SYSTEM_CLE is not set
+
+#
+# CU Minimal Terminal
+#
+# CONFIG_SYSTEM_CUTERM is not set
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# Intel HEX to binary conversion
+#
+# CONFIG_SYSTEM_HEX2BIN is not set
+
+#
+# I2C tool
+#
+
+#
+# INI File Parser
+#
+# CONFIG_SYSTEM_INIFILE is not set
+
+#
+# NxPlayer media player library / command Line
+#
+
+#
+# RAM test
+#
+# CONFIG_SYSTEM_RAMTEST is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# P-Code Support
+#
+
+#
+# PHY Tool
+#
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sudoku
+#
+# CONFIG_SYSTEM_SUDOKU is not set
+
+#
+# Sysinfo
+#
+# CONFIG_SYSTEM_SYSINFO is not set
+
+#
+# Temperature
+#
+
+#
+# VI Work-Alike Editor
+#
+# CONFIG_SYSTEM_VI is not set
+
+#
+# Stack Monitor
+#
+# CONFIG_SYSTEM_STACKMONITOR is not set
+
+#
+# USB CDC/ACM Device Commands
+#
+
+#
+# USB Composite Device Commands
+#
+
+#
+# USB Mass Storage Device Commands
+#
+
+#
+# USB Monitor
+#
+
+#
+# Zmodem Commands
+#
+# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx-configs/px4cannode-v1/nsh/defconfig.nsh b/nuttx-configs/px4cannode-v1/nsh/defconfig.nsh
new file mode 100644
index 000000000..13a22d4fd
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/defconfig.nsh
@@ -0,0 +1,1142 @@
+#
+# Automatically generated file; DO NOT EDIT.
+# Nuttx/ Configuration
+#
+
+#
+# Build Setup
+#
+# CONFIG_EXPERIMENTAL is not set
+CONFIG_DEFAULT_SMALL=y
+CONFIG_HOST_LINUX=y
+# CONFIG_HOST_OSX is not set
+# CONFIG_HOST_WINDOWS is not set
+# CONFIG_HOST_OTHER is not set
+
+#
+# Build Configuration
+#
+CONFIG_APPS_DIR="../apps"
+CONFIG_BUILD_FLAT=y
+# CONFIG_BUILD_2PASS is not set
+
+#
+# Binary Output Formats
+#
+# CONFIG_RRLOAD_BINARY is not set
+# CONFIG_INTELHEX_BINARY is not set
+# CONFIG_MOTOROLA_SREC is not set
+CONFIG_RAW_BINARY=y
+# CONFIG_UBOOT_UIMAGE is not set
+
+#
+# Customize Header Files
+#
+# CONFIG_ARCH_STDINT_H is not set
+# CONFIG_ARCH_STDBOOL_H is not set
+CONFIG_ARCH_MATH_H=y
+# CONFIG_ARCH_FLOAT_H is not set
+# CONFIG_ARCH_STDARG_H is not set
+
+#
+# Debug Options
+#
+CONFIG_DEBUG=y
+CONFIG_DEBUG_VERBOSE=y
+CONFIG_ARCH_HAVE_HEAPCHECK=y
+CONFIG_DEBUG_VERBOSE=y
+
+#
+# Subsystem Debug Options
+#
+# CONFIG_DEBUG_AUDIO is not set
+# CONFIG_DEBUG_BINFMT is not set
+# CONFIG_DEBUG_FS is not set
+# CONFIG_DEBUG_GRAPHICS is not set
+# CONFIG_DEBUG_LIB is not set
+# CONFIG_DEBUG_MM is not set
+# CONFIG_DEBUG_SCHED is not set
+
+#
+# OS Function Debug Options
+#
+# CONFIG_DEBUG_DMA is not set
+# CONFIG_DEBUG_HEAP is not set
+# CONFIG_DEBUG_IRQ is not set
+
+#
+# Driver Debug Options
+#
+# CONFIG_DEBUG_ANALOG is not set
+# CONFIG_DEBUG_CAN is not set
+# CONFIG_DEBUG_GPIO is not set
+# CONFIG_DEBUG_SPI is not set
+CONFIG_ARCH_HAVE_STACKCHECK=y
+CONFIG_STACK_COLORATION=y
+CONFIG_DEBUG_SYMBOLS=y
+CONFIG_ARCH_HAVE_CUSTOMOPT=y
+# CONFIG_DEBUG_NOOPT is not set
+# CONFIG_DEBUG_CUSTOMOPT is not set
+CONFIG_DEBUG_FULLOPT=y
+
+#
+# System Type
+#
+CONFIG_ARCH_ARM=y
+# CONFIG_ARCH_AVR is not set
+# CONFIG_ARCH_HC is not set
+# CONFIG_ARCH_MIPS is not set
+# CONFIG_ARCH_RGMP is not set
+# CONFIG_ARCH_SH is not set
+# CONFIG_ARCH_SIM is not set
+# CONFIG_ARCH_X86 is not set
+# CONFIG_ARCH_Z16 is not set
+# CONFIG_ARCH_Z80 is not set
+CONFIG_ARCH="arm"
+
+#
+# ARM Options
+#
+# CONFIG_ARCH_CHIP_A1X is not set
+# CONFIG_ARCH_CHIP_C5471 is not set
+# CONFIG_ARCH_CHIP_CALYPSO is not set
+# CONFIG_ARCH_CHIP_DM320 is not set
+# CONFIG_ARCH_CHIP_EFM32 is not set
+# CONFIG_ARCH_CHIP_IMX is not set
+# CONFIG_ARCH_CHIP_KINETIS is not set
+# CONFIG_ARCH_CHIP_KL is not set
+# CONFIG_ARCH_CHIP_LM is not set
+# CONFIG_ARCH_CHIP_TIVA is not set
+# CONFIG_ARCH_CHIP_LPC17XX is not set
+# CONFIG_ARCH_CHIP_LPC214X is not set
+# CONFIG_ARCH_CHIP_LPC2378 is not set
+# CONFIG_ARCH_CHIP_LPC31XX is not set
+# CONFIG_ARCH_CHIP_LPC43XX is not set
+# CONFIG_ARCH_CHIP_NUC1XX is not set
+# CONFIG_ARCH_CHIP_SAMA5 is not set
+# CONFIG_ARCH_CHIP_SAMD is not set
+# CONFIG_ARCH_CHIP_SAM34 is not set
+# CONFIG_ARCH_CHIP_SAMV7 is not set
+CONFIG_ARCH_CHIP_STM32=y
+# CONFIG_ARCH_CHIP_STR71X is not set
+# CONFIG_ARCH_ARM7TDMI is not set
+# CONFIG_ARCH_ARM926EJS is not set
+# CONFIG_ARCH_ARM920T is not set
+# CONFIG_ARCH_CORTEXM0 is not set
+CONFIG_ARCH_CORTEXM3=y
+# CONFIG_ARCH_CORTEXM4 is not set
+# CONFIG_ARCH_CORTEXM7 is not set
+# CONFIG_ARCH_CORTEXA5 is not set
+# CONFIG_ARCH_CORTEXA8 is not set
+CONFIG_ARCH_FAMILY="armv7-m"
+CONFIG_ARCH_CHIP="stm32"
+CONFIG_ARMV7M_USEBASEPRI=y
+CONFIG_ARCH_HAVE_CMNVECTOR=y
+CONFIG_ARMV7M_CMNVECTOR=y
+# CONFIG_ARMV7M_LAZYFPU is not set
+# CONFIG_ARCH_HAVE_FPU is not set
+# CONFIG_ARCH_HAVE_DPFPU is not set
+# CONFIG_ARMV7M_MPU is not set
+# CONFIG_DEBUG_HARDFAULT is not set
+
+#
+# ARMV7M Configuration Options
+#
+# CONFIG_ARMV7M_HAVE_ICACHE is not set
+# CONFIG_ARMV7M_HAVE_DCACHE is not set
+# CONFIG_ARMV7M_HAVE_ITCM is not set
+# CONFIG_ARMV7M_HAVE_DTCM is not set
+# CONFIG_ARMV7M_TOOLCHAIN_BUILDROOT is not set
+# CONFIG_ARMV7M_TOOLCHAIN_CODEREDL is not set
+CONFIG_ARMV7M_TOOLCHAIN_CODESOURCERYL=y
+# CONFIG_ARMV7M_TOOLCHAIN_GNU_EABIL is not set
+# CONFIG_ARMV7M_STACKCHECK is not set
+# CONFIG_ARMV7M_ITMSYSLOG is not set
+
+#
+# STM32 Configuration Options
+#
+# CONFIG_ARCH_CHIP_STM32L151C6 is not set
+# CONFIG_ARCH_CHIP_STM32L151C8 is not set
+# CONFIG_ARCH_CHIP_STM32L151CB is not set
+# CONFIG_ARCH_CHIP_STM32L151R6 is not set
+# CONFIG_ARCH_CHIP_STM32L151R8 is not set
+# CONFIG_ARCH_CHIP_STM32L151RB is not set
+# CONFIG_ARCH_CHIP_STM32L151V6 is not set
+# CONFIG_ARCH_CHIP_STM32L151V8 is not set
+# CONFIG_ARCH_CHIP_STM32L151VB is not set
+# CONFIG_ARCH_CHIP_STM32L152C6 is not set
+# CONFIG_ARCH_CHIP_STM32L152C8 is not set
+# CONFIG_ARCH_CHIP_STM32L152CB is not set
+# CONFIG_ARCH_CHIP_STM32L152R6 is not set
+# CONFIG_ARCH_CHIP_STM32L152R8 is not set
+# CONFIG_ARCH_CHIP_STM32L152RB is not set
+# CONFIG_ARCH_CHIP_STM32L152V6 is not set
+# CONFIG_ARCH_CHIP_STM32L152V8 is not set
+# CONFIG_ARCH_CHIP_STM32L152VB is not set
+# CONFIG_ARCH_CHIP_STM32L162ZD is not set
+# CONFIG_ARCH_CHIP_STM32L162VE is not set
+# CONFIG_ARCH_CHIP_STM32F100C8 is not set
+# CONFIG_ARCH_CHIP_STM32F100CB is not set
+# CONFIG_ARCH_CHIP_STM32F100R8 is not set
+# CONFIG_ARCH_CHIP_STM32F100RB is not set
+# CONFIG_ARCH_CHIP_STM32F100RC is not set
+# CONFIG_ARCH_CHIP_STM32F100RD is not set
+# CONFIG_ARCH_CHIP_STM32F100RE is not set
+# CONFIG_ARCH_CHIP_STM32F100V8 is not set
+# CONFIG_ARCH_CHIP_STM32F100VB is not set
+# CONFIG_ARCH_CHIP_STM32F100VC is not set
+# CONFIG_ARCH_CHIP_STM32F100VD is not set
+# CONFIG_ARCH_CHIP_STM32F100VE is not set
+# CONFIG_ARCH_CHIP_STM32F102CB is not set
+# CONFIG_ARCH_CHIP_STM32F103T8 is not set
+# CONFIG_ARCH_CHIP_STM32F103TB is not set
+# CONFIG_ARCH_CHIP_STM32F103C4 is not set
+# CONFIG_ARCH_CHIP_STM32F103C8 is not set
+# CONFIG_ARCH_CHIP_STM32F103CB is not set
+# CONFIG_ARCH_CHIP_STM32F103R8 is not set
+CONFIG_ARCH_CHIP_STM32F103RB=y
+# CONFIG_ARCH_CHIP_STM32F103RC is not set
+# CONFIG_ARCH_CHIP_STM32F103RD is not set
+# CONFIG_ARCH_CHIP_STM32F103RE is not set
+# CONFIG_ARCH_CHIP_STM32F103RG is not set
+# CONFIG_ARCH_CHIP_STM32F103V8 is not set
+# CONFIG_ARCH_CHIP_STM32F103VB is not set
+# CONFIG_ARCH_CHIP_STM32F103VC is not set
+# CONFIG_ARCH_CHIP_STM32F103VE is not set
+# CONFIG_ARCH_CHIP_STM32F103ZE is not set
+# CONFIG_ARCH_CHIP_STM32F105VB is not set
+# CONFIG_ARCH_CHIP_STM32F107VC is not set
+# CONFIG_ARCH_CHIP_STM32F207IG is not set
+# CONFIG_ARCH_CHIP_STM32F207ZE is not set
+# CONFIG_ARCH_CHIP_STM32F302CB is not set
+# CONFIG_ARCH_CHIP_STM32F302CC is not set
+# CONFIG_ARCH_CHIP_STM32F302RB is not set
+# CONFIG_ARCH_CHIP_STM32F302RC is not set
+# CONFIG_ARCH_CHIP_STM32F302VB is not set
+# CONFIG_ARCH_CHIP_STM32F302VC is not set
+# CONFIG_ARCH_CHIP_STM32F303CB is not set
+# CONFIG_ARCH_CHIP_STM32F303CC is not set
+# CONFIG_ARCH_CHIP_STM32F303RB is not set
+# CONFIG_ARCH_CHIP_STM32F303RC is not set
+# CONFIG_ARCH_CHIP_STM32F303VB is not set
+# CONFIG_ARCH_CHIP_STM32F303VC is not set
+# CONFIG_ARCH_CHIP_STM32F372C8 is not set
+# CONFIG_ARCH_CHIP_STM32F372R8 is not set
+# CONFIG_ARCH_CHIP_STM32F372V8 is not set
+# CONFIG_ARCH_CHIP_STM32F372CB is not set
+# CONFIG_ARCH_CHIP_STM32F372RB is not set
+# CONFIG_ARCH_CHIP_STM32F372VB is not set
+# CONFIG_ARCH_CHIP_STM32F372CC is not set
+# CONFIG_ARCH_CHIP_STM32F372RC is not set
+# CONFIG_ARCH_CHIP_STM32F372VC is not set
+# CONFIG_ARCH_CHIP_STM32F373C8 is not set
+# CONFIG_ARCH_CHIP_STM32F373R8 is not set
+# CONFIG_ARCH_CHIP_STM32F373V8 is not set
+# CONFIG_ARCH_CHIP_STM32F373CB is not set
+# CONFIG_ARCH_CHIP_STM32F373RB is not set
+# CONFIG_ARCH_CHIP_STM32F373VB is not set
+# CONFIG_ARCH_CHIP_STM32F373CC is not set
+# CONFIG_ARCH_CHIP_STM32F373RC is not set
+# CONFIG_ARCH_CHIP_STM32F373VC is not set
+# CONFIG_ARCH_CHIP_STM32F401RE is not set
+# CONFIG_ARCH_CHIP_STM32F411RE is not set
+# CONFIG_ARCH_CHIP_STM32F405RG is not set
+# CONFIG_ARCH_CHIP_STM32F405VG is not set
+# CONFIG_ARCH_CHIP_STM32F405ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407VE is not set
+# CONFIG_ARCH_CHIP_STM32F407VG is not set
+# CONFIG_ARCH_CHIP_STM32F407ZE is not set
+# CONFIG_ARCH_CHIP_STM32F407ZG is not set
+# CONFIG_ARCH_CHIP_STM32F407IE is not set
+# CONFIG_ARCH_CHIP_STM32F407IG is not set
+# CONFIG_ARCH_CHIP_STM32F427V is not set
+# CONFIG_ARCH_CHIP_STM32F427Z is not set
+# CONFIG_ARCH_CHIP_STM32F427I is not set
+# CONFIG_ARCH_CHIP_STM32F429V is not set
+# CONFIG_ARCH_CHIP_STM32F429Z is not set
+# CONFIG_ARCH_CHIP_STM32F429I is not set
+# CONFIG_ARCH_CHIP_STM32F429B is not set
+# CONFIG_ARCH_CHIP_STM32F429N is not set
+# CONFIG_STM32_STM32L15XX is not set
+# CONFIG_STM32_ENERGYLITE is not set
+CONFIG_STM32_STM32F10XX=y
+# CONFIG_STM32_VALUELINE is not set
+# CONFIG_STM32_CONNECTIVITYLINE is not set
+CONFIG_STM32_PERFORMANCELINE=y
+# CONFIG_STM32_USBACCESSLINE is not set
+# CONFIG_STM32_HIGHDENSITY is not set
+CONFIG_STM32_MEDIUMDENSITY=y
+# CONFIG_STM32_LOWDENSITY is not set
+# CONFIG_STM32_STM32F20XX is not set
+# CONFIG_STM32_STM32F207 is not set
+# CONFIG_STM32_STM32F30XX is not set
+# CONFIG_STM32_STM32F37XX is not set
+# CONFIG_STM32_STM32F40XX is not set
+# CONFIG_STM32_STM32F401 is not set
+# CONFIG_STM32_STM32F411 is not set
+# CONFIG_STM32_STM32F405 is not set
+# CONFIG_STM32_STM32F407 is not set
+# CONFIG_STM32_STM32F427 is not set
+# CONFIG_STM32_STM32F429 is not set
+# CONFIG_STM32_DFU is not set
+
+#
+# STM32 Peripheral Support
+#
+# CONFIG_STM32_HAVE_CCM is not set
+CONFIG_STM32_HAVE_USBDEV=y
+# CONFIG_STM32_HAVE_OTGFS is not set
+# CONFIG_STM32_HAVE_FSMC is not set
+CONFIG_STM32_HAVE_USART3=y
+CONFIG_STM32_HAVE_UART4=y
+CONFIG_STM32_HAVE_UART5=y
+# CONFIG_STM32_HAVE_USART6 is not set
+# CONFIG_STM32_HAVE_UART7 is not set
+# CONFIG_STM32_HAVE_UART8 is not set
+CONFIG_STM32_HAVE_TIM1=y
+CONFIG_STM32_HAVE_TIM5=y
+CONFIG_STM32_HAVE_TIM6=y
+CONFIG_STM32_HAVE_TIM7=y
+CONFIG_STM32_HAVE_TIM8=y
+# CONFIG_STM32_HAVE_TIM9 is not set
+# CONFIG_STM32_HAVE_TIM10 is not set
+# CONFIG_STM32_HAVE_TIM11 is not set
+# CONFIG_STM32_HAVE_TIM12 is not set
+# CONFIG_STM32_HAVE_TIM13 is not set
+# CONFIG_STM32_HAVE_TIM14 is not set
+# CONFIG_STM32_HAVE_TIM15 is not set
+# CONFIG_STM32_HAVE_TIM16 is not set
+# CONFIG_STM32_HAVE_TIM17 is not set
+CONFIG_STM32_HAVE_ADC2=y
+CONFIG_STM32_HAVE_ADC3=y
+# CONFIG_STM32_HAVE_ADC4 is not set
+CONFIG_STM32_HAVE_CAN1=y
+# CONFIG_STM32_HAVE_CAN2 is not set
+# CONFIG_STM32_HAVE_RNG is not set
+# CONFIG_STM32_HAVE_ETHMAC is not set
+CONFIG_STM32_HAVE_SPI2=y
+CONFIG_STM32_HAVE_SPI3=y
+# CONFIG_STM32_HAVE_SPI4 is not set
+# CONFIG_STM32_HAVE_SPI5 is not set
+# CONFIG_STM32_HAVE_SPI6 is not set
+# CONFIG_STM32_ADC1 is not set
+# CONFIG_STM32_ADC2 is not set
+# CONFIG_STM32_ADC3 is not set
+# CONFIG_STM32_BKP is not set
+# CONFIG_STM32_CAN1 is not set
+# CONFIG_STM32_CRC is not set
+CONFIG_STM32_DMA1=y
+CONFIG_STM32_DMA2=y
+# CONFIG_STM32_DAC1 is not set
+# CONFIG_STM32_DAC2 is not set
+# CONFIG_STM32_I2C1 is not set
+# CONFIG_STM32_I2C2 is not set
+CONFIG_STM32_PWR=y
+# CONFIG_STM32_SDIO is not set
+# CONFIG_STM32_SPI1 is not set
+CONFIG_STM32_SPI2=y
+# CONFIG_STM32_SPI3 is not set
+# CONFIG_STM32_TIM1 is not set
+# CONFIG_STM32_TIM2 is not set
+CONFIG_STM32_TIM3=y
+# CONFIG_STM32_TIM4 is not set
+# CONFIG_STM32_TIM5 is not set
+# CONFIG_STM32_TIM6 is not set
+# CONFIG_STM32_TIM7 is not set
+# CONFIG_STM32_TIM8 is not set
+CONFIG_STM32_USART1=y
+# CONFIG_STM32_USART2 is not set
+# CONFIG_STM32_USART3 is not set
+# CONFIG_STM32_UART4 is not set
+# CONFIG_STM32_UART5 is not set
+# CONFIG_STM32_USB is not set
+# CONFIG_STM32_IWDG is not set
+# CONFIG_STM32_WWDG is not set
+CONFIG_STM32_SPI=y
+# CONFIG_STM32_CAN is not set
+
+#
+# Alternate Pin Mapping
+#
+# CONFIG_STM32_CAN1_NO_REMAP is not set
+CONFIG_STM32_CAN1_REMAP1=y
+# CONFIG_STM32_CAN1_REMAP2 is not set
+# CONFIG_STM32_TIM1_NO_REMAP is not set
+# CONFIG_STM32_TIM1_FULL_REMAP is not set
+CONFIG_STM32_TIM1_PARTIAL_REMAP=y
+# CONFIG_STM32_TIM3_NO_REMAP is not set
+# CONFIG_STM32_TIM3_FULL_REMAP is not set
+CONFIG_STM32_TIM3_PARTIAL_REMAP=y
+# CONFIG_STM32_USART1_REMAP is not set
+# CONFIG_STM32_JTAG_DISABLE is not set
+CONFIG_STM32_JTAG_FULL_ENABLE=y
+# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
+# CONFIG_STM32_JTAG_SW_ENABLE is not set
+CONFIG_STM32_DISABLE_IDLE_SLEEP_DURING_DEBUG=y
+CONFIG_STM32_FORCEPOWER=y
+# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
+# CONFIG_STM32_DMACAPABLE is not set
+# CONFIG_STM32_TIM1_PWM is not set
+# CONFIG_STM32_TIM3_PWM is not set
+CONFIG_STM32_USART=y
+
+#
+# U[S]ART Configuration
+#
+# CONFIG_USART1_RS485 is not set
+CONFIG_USART1_RXDMA=y
+CONFIG_SERIAL_DISABLE_REORDERING=y
+# CONFIG_STM32_FLOWCONTROL_BROKEN is not set
+# CONFIG_STM32_USART_SINGLEWIRE is not set
+
+#
+# SPI Configuration
+#
+# CONFIG_STM32_SPI_INTERRUPTS is not set
+CONFIG_STM32_SPI_DMA=y
+# CONFIG_STM32_HAVE_RTC_SUBSECONDS is not set
+
+#
+# USB FS Host Configuration
+#
+
+#
+# USB HS Host Configuration
+#
+
+#
+# USB Host Debug Configuration
+#
+
+#
+# USB Device Configuration
+#
+
+#
+# CAN driver configuration
+#
+
+#
+# Architecture Options
+#
+# CONFIG_ARCH_NOINTC is not set
+# CONFIG_ARCH_VECNOTIRQ is not set
+CONFIG_ARCH_DMA=y
+CONFIG_ARCH_HAVE_IRQPRIO=y
+# CONFIG_ARCH_L2CACHE is not set
+# CONFIG_ARCH_HAVE_COHERENT_DCACHE is not set
+# CONFIG_ARCH_HAVE_ADDRENV is not set
+# CONFIG_ARCH_NEED_ADDRENV_MAPPING is not set
+CONFIG_ARCH_HAVE_VFORK=y
+# CONFIG_ARCH_HAVE_MMU is not set
+CONFIG_ARCH_HAVE_MPU=y
+# CONFIG_ARCH_NAND_HWECC is not set
+# CONFIG_ARCH_HAVE_EXTCLK is not set
+# CONFIG_ARCH_USE_MPU is not set
+CONFIG_ARCH_IRQPRIO=y
+CONFIG_ARCH_STACKDUMP=y
+# CONFIG_ENDIAN_BIG is not set
+# CONFIG_ARCH_IDLE_CUSTOM is not set
+# CONFIG_ARCH_HAVE_RAMFUNCS is not set
+CONFIG_ARCH_HAVE_RAMVECTORS=y
+# CONFIG_ARCH_RAMVECTORS is not set
+
+#
+# Board Settings
+#
+CONFIG_BOARD_LOOPSPERMSEC=5483
+# CONFIG_ARCH_CALIBRATION is not set
+
+#
+# Interrupt options
+#
+CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
+CONFIG_ARCH_INTERRUPTSTACK=360
+CONFIG_ARCH_HAVE_HIPRI_INTERRUPT=y
+CONFIG_ARCH_HIPRI_INTERRUPT=y
+
+#
+# Boot options
+#
+# CONFIG_BOOT_RUNFROMEXTSRAM is not set
+CONFIG_BOOT_RUNFROMFLASH=y
+# CONFIG_BOOT_RUNFROMISRAM is not set
+# CONFIG_BOOT_RUNFROMSDRAM is not set
+# CONFIG_BOOT_COPYTORAM is not set
+
+#
+# Boot Memory Configuration
+#
+CONFIG_RAM_START=0x20000000
+CONFIG_RAM_SIZE=20480
+# CONFIG_ARCH_HAVE_SDRAM is not set
+
+#
+# Board Selection
+#
+# CONFIG_ARCH_BOARD_MAPLE is not set
+CONFIG_ARCH_BOARD_PX4CANNODE_V1=y
+# CONFIG_ARCH_BOARD_CUSTOM is not set
+CONFIG_ARCH_BOARD="px4cannode-v1"
+
+#
+# Common Board Options
+#
+CONFIG_ARCH_HAVE_LEDS=y
+CONFIG_ARCH_LEDS=y
+CONFIG_ARCH_HAVE_BUTTONS=y
+CONFIG_ARCH_BUTTONS=y
+CONFIG_ARCH_HAVE_IRQBUTTONS=y
+CONFIG_NSH_MMCSDMINOR=0
+
+#
+# Board-Specific Options
+#
+
+#
+# RTOS Features
+#
+# CONFIG_DISABLE_OS_API is not set
+
+#
+# Clocks and Timers
+#
+CONFIG_USEC_PER_TICK=10000
+# CONFIG_SYSTEM_TIME64 is not set
+# CONFIG_CLOCK_MONOTONIC is not set
+# CONFIG_JULIAN_TIME is not set
+CONFIG_START_YEAR=2014
+CONFIG_START_MONTH=11
+CONFIG_START_DAY=20
+CONFIG_MAX_WDOGPARMS=2
+CONFIG_PREALLOC_WDOGS=4
+CONFIG_WDOG_INTRESERVE=2
+CONFIG_PREALLOC_TIMERS=2
+
+#
+# Tasks and Scheduling
+#
+# CONFIG_INIT_NONE is not set
+CONFIG_INIT_ENTRYPOINT=y
+# CONFIG_INIT_FILEPATH is not set
+CONFIG_USER_ENTRYPOINT="nsh_main"
+CONFIG_RR_INTERVAL=0
+CONFIG_TASK_NAME_SIZE=12
+CONFIG_MAX_TASKS=4
+# CONFIG_SCHED_HAVE_PARENT is not set
+CONFIG_SCHED_WAITPID=y
+
+#
+# Pthread Options
+#
+# CONFIG_MUTEX_TYPES is not set
+CONFIG_NPTHREAD_KEYS=0
+
+#
+# Performance Monitoring
+#
+# CONFIG_SCHED_CPULOAD is not set
+CONFIG_SCHED_INSTRUMENTATION=y
+
+#
+# Files and I/O
+#
+CONFIG_DEV_CONSOLE=y
+# CONFIG_FDCLONE_DISABLE is not set
+CONFIG_FDCLONE_STDIO=y
+CONFIG_SDCLONE_DISABLE=y
+CONFIG_NFILE_DESCRIPTORS=5
+CONFIG_NFILE_STREAMS=1
+CONFIG_NAME_MAX=8
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=4
+CONFIG_SEM_NNESTPRIO=4
+
+#
+# RTOS hooks
+#
+CONFIG_BOARD_INITIALIZE=y
+# CONFIG_BOARD_INITTHREAD is not set
+# CONFIG_SCHED_STARTHOOK is not set
+CONFIG_SCHED_ATEXIT=y
+CONFIG_SCHED_ATEXIT_MAX=1
+
+#
+# Signal Numbers
+#
+CONFIG_SIG_SIGUSR1=1
+CONFIG_SIG_SIGUSR2=2
+CONFIG_SIG_SIGALARM=3
+CONFIG_SIG_SIGCONDTIMEDOUT=16
+CONFIG_SIG_SIGWORK=17
+
+#
+# POSIX Message Queue Options
+#
+CONFIG_PREALLOC_MQ_MSGS=4
+CONFIG_MQ_MAXMSGSIZE=8
+
+#
+# Work Queue Support
+#
+# CONFIG_SCHED_WORKQUEUE is not set
+# CONFIG_SCHED_HPWORK is not set
+# CONFIG_SCHED_HPWORKPRIORITY is not set
+# CONFIG_SCHED_HPWORKPERIOD is not set
+# CONFIG_SCHED_HPWORKSTACKSIZE is not set
+# CONFIG_SCHED_LPWORK is not set
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=272
+CONFIG_USERMAIN_STACKSIZE=680
+CONFIG_PTHREAD_STACK_MIN=516
+CONFIG_PTHREAD_STACK_DEFAULT=516
+# CONFIG_LIB_SYSCALL is not set
+
+#
+# Device Drivers
+#
+# CONFIG_DISABLE_POLL is not set
+# CONFIG_DEV_NULL is not set
+# CONFIG_DEV_ZERO is not set
+# CONFIG_LOOP is not set
+
+#
+# Buffering
+#
+# CONFIG_DRVR_WRITEBUFFER is not set
+# CONFIG_DRVR_READAHEAD is not set
+# CONFIG_RAMDISK is not set
+# CONFIG_CAN is not set
+# CONFIG_ARCH_HAVE_PWM_PULSECOUNT is not set
+# CONFIG_PWM is not set
+CONFIG_ARCH_HAVE_I2CRESET=y
+# CONFIG_I2C is not set
+CONFIG_SPI=y
+# CONFIG_SPI_OWNBUS is not set
+CONFIG_SPI_EXCHANGE=y
+# CONFIG_SPI_CMDDATA is not set
+# CONFIG_SPI_CALLBACK is not set
+# CONFIG_SPI_BITBANG is not set
+# CONFIG_I2S is not set
+# CONFIG_TIMER is not set
+# CONFIG_RTC is not set
+# CONFIG_WATCHDOG is not set
+# CONFIG_ANALOG is not set
+# CONFIG_AUDIO_DEVICES is not set
+# CONFIG_VIDEO_DEVICES is not set
+# CONFIG_BCH is not set
+# CONFIG_INPUT is not set
+# CONFIG_LCD is not set
+# CONFIG_MMCSD is not set
+# CONFIG_MTD is not set
+# CONFIG_EEPROM is not set
+# CONFIG_PIPES is not set
+# CONFIG_PM is not set
+# CONFIG_POWER is not set
+# CONFIG_SENSORS is not set
+# CONFIG_SERCOMM_CONSOLE is not set
+CONFIG_SERIAL=y
+# CONFIG_DEV_LOWCONSOLE is not set
+# CONFIG_16550_UART is not set
+# CONFIG_ARCH_HAVE_UART is not set
+# CONFIG_ARCH_HAVE_UART0 is not set
+# CONFIG_ARCH_HAVE_UART1 is not set
+# CONFIG_ARCH_HAVE_UART2 is not set
+# CONFIG_ARCH_HAVE_UART3 is not set
+# CONFIG_ARCH_HAVE_UART4 is not set
+# CONFIG_ARCH_HAVE_UART5 is not set
+# CONFIG_ARCH_HAVE_UART6 is not set
+# CONFIG_ARCH_HAVE_UART7 is not set
+# CONFIG_ARCH_HAVE_UART8 is not set
+# CONFIG_ARCH_HAVE_SCI0 is not set
+# CONFIG_ARCH_HAVE_SCI1 is not set
+# CONFIG_ARCH_HAVE_USART0 is not set
+CONFIG_ARCH_HAVE_USART1=y
+# CONFIG_ARCH_HAVE_USART2 is not set
+# CONFIG_ARCH_HAVE_USART3 is not set
+# CONFIG_ARCH_HAVE_USART4 is not set
+# CONFIG_ARCH_HAVE_USART5 is not set
+# CONFIG_ARCH_HAVE_USART6 is not set
+# CONFIG_ARCH_HAVE_USART7 is not set
+# CONFIG_ARCH_HAVE_USART8 is not set
+# CONFIG_ARCH_HAVE_OTHER_UART is not set
+
+#
+# USART Configuration
+#
+CONFIG_USART1_ISUART=y
+CONFIG_MCU_SERIAL=y
+CONFIG_STANDARD_SERIAL=y
+CONFIG_SERIAL_NPOLLWAITERS=2
+# CONFIG_SERIAL_IFLOWCONTROL is not set
+# CONFIG_SERIAL_OFLOWCONTROL is not set
+# CONFIG_SERIAL_TIOCSERGSTRUCT is not set
+CONFIG_ARCH_HAVE_SERIAL_TERMIOS=y
+# CONFIG_SERIAL_TERMIOS is not set
+CONFIG_USART1_SERIAL_CONSOLE=y
+# CONFIG_OTHER_SERIAL_CONSOLE is not set
+# CONFIG_NO_SERIAL_CONSOLE is not set
+
+#
+# USART1 Configuration
+#
+CONFIG_USART1_RXBUFSIZE=32
+CONFIG_USART1_TXBUFSIZE=32
+CONFIG_USART1_BAUD=115200
+CONFIG_USART1_BITS=8
+CONFIG_USART1_PARITY=0
+CONFIG_USART1_2STOP=0
+# CONFIG_USART1_IFLOWCONTROL is not set
+# CONFIG_USART1_OFLOWCONTROL is not set
+# CONFIG_USBDEV is not set
+# CONFIG_USBHOST is not set
+# CONFIG_WIRELESS is not set
+
+#
+# System Logging Device Options
+#
+
+#
+# System Logging
+#
+# CONFIG_RAMLOG is not set
+# CONFIG_SYSLOG_CONSOLE is not set
+
+#
+# Networking Support
+#
+# CONFIG_ARCH_HAVE_NET is not set
+# CONFIG_ARCH_HAVE_PHY is not set
+# CONFIG_NET is not set
+
+#
+# Crypto API
+#
+# CONFIG_CRYPTO is not set
+
+#
+# File Systems
+#
+
+#
+# File system configuration
+#
+# CONFIG_DISABLE_MOUNTPOINT is not set
+# CONFIG_FS_AUTOMOUNTER is not set
+# CONFIG_DISABLE_PSEUDOFS_OPERATIONS is not set
+# CONFIG_FS_READABLE is not set
+# CONFIG_FS_WRITABLE is not set
+# CONFIG_FS_NAMED_SEMAPHORES is not set
+CONFIG_FS_MQUEUE_MPATH="/var/mqueue"
+# CONFIG_FS_RAMMAP is not set
+# CONFIG_FS_FAT is not set
+# CONFIG_FS_NXFFS is not set
+# CONFIG_FS_ROMFS is not set
+# CONFIG_FS_SMARTFS is not set
+# CONFIG_FS_BINFS is not set
+# CONFIG_FS_PROCFS is not set
+
+#
+# System Logging
+#
+# CONFIG_SYSLOG is not set
+# CONFIG_SYSLOG_TIMESTAMP is not set
+
+#
+# Graphics Support
+#
+# CONFIG_NX is not set
+
+#
+# Memory Management
+#
+CONFIG_MM_SMALL=y
+CONFIG_MM_REGIONS=1
+# CONFIG_ARCH_HAVE_HEAP2 is not set
+# CONFIG_GRAN is not set
+
+#
+# Audio Support
+#
+# CONFIG_AUDIO is not set
+
+#
+# Binary Loader
+#
+# CONFIG_BINFMT_DISABLE is not set
+# CONFIG_BINFMT_EXEPATH is not set
+# CONFIG_NXFLAT is not set
+# CONFIG_ELF is not set
+CONFIG_BUILTIN=y
+# CONFIG_PIC is not set
+CONFIG_SYMTAB_ORDEREDBYNAME=y
+
+#
+# Library Routines
+#
+
+#
+# Standard C Library Options
+#
+CONFIG_STDIO_BUFFER_SIZE=64
+CONFIG_STDIO_LINEBUFFER=y
+CONFIG_NUNGET_CHARS=2
+CONFIG_LIB_HOMEDIR="/"
+# CONFIG_NOPRINTF_FIELDWIDTH is not set
+# CONFIG_LIBC_FLOATINGPOINT is not set
+# CONFIG_LIBC_IOCTL_VARIADIC is not set
+CONFIG_LIB_RAND_ORDER=1
+# CONFIG_EOL_IS_CR is not set
+# CONFIG_EOL_IS_LF is not set
+# CONFIG_EOL_IS_BOTH_CRLF is not set
+CONFIG_EOL_IS_EITHER_CRLF=y
+# CONFIG_LIBC_EXECFUNCS is not set
+CONFIG_POSIX_SPAWN_PROXY_STACKSIZE=394
+CONFIG_TASK_SPAWN_DEFAULT_STACKSIZE=394
+# CONFIG_LIBC_STRERROR is not set
+# CONFIG_LIBC_PERROR_STDOUT is not set
+CONFIG_ARCH_LOWPUTC=y
+# CONFIG_LIBC_LOCALTIME is not set
+CONFIG_LIB_SENDFILE_BUFSIZE=0
+# CONFIG_ARCH_ROMGETC is not set
+# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
+
+#
+# Non-standard Library Support
+#
+# CONFIG_LIB_KBDCODEC is not set
+# CONFIG_LIB_SLCDCODEC is not set
+
+#
+# Basic CXX Support
+#
+CONFIG_C99_BOOL8=y
+CONFIG_HAVE_CXX=y
+CONFIG_HAVE_CXXINITIALIZE=y
+# CONFIG_CXX_NEWLONG is not set
+
+#
+# uClibc++ Standard C++ Library
+#
+# CONFIG_UCLIBCXX is not set
+
+#
+# Application Configuration
+#
+
+#
+# Built-In Applications
+#
+CONFIG_BUILTIN_PROXY_STACKSIZE=392
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+# CONFIG_EXAMPLES_CAN is not set
+# CONFIG_EXAMPLES_CONFIGDATA is not set
+# CONFIG_EXAMPLES_CPUHOG is not set
+# CONFIG_EXAMPLES_CXXTEST is not set
+# CONFIG_EXAMPLES_DHCPD is not set
+# CONFIG_EXAMPLES_ELF is not set
+# CONFIG_EXAMPLES_FTPC is not set
+# CONFIG_EXAMPLES_FTPD is not set
+# CONFIG_EXAMPLES_HELLO is not set
+# CONFIG_EXAMPLES_HELLOXX is not set
+# CONFIG_EXAMPLES_JSON is not set
+# CONFIG_EXAMPLES_HIDKBD is not set
+# CONFIG_EXAMPLES_KEYPADTEST is not set
+# CONFIG_EXAMPLES_IGMP is not set
+# CONFIG_EXAMPLES_MM is not set
+# CONFIG_EXAMPLES_MODBUS is not set
+# CONFIG_EXAMPLES_MOUNT is not set
+# CONFIG_EXAMPLES_NRF24L01TERM is not set
+CONFIG_EXAMPLES_NSH=y
+# CONFIG_EXAMPLES_NSH_CXXINITIALIZE is not set
+CONFIG_EXAMPLES_NULL=y
+# CONFIG_EXAMPLES_NX is not set
+# CONFIG_EXAMPLES_NXTERM is not set
+# CONFIG_EXAMPLES_NXFFS is not set
+# CONFIG_EXAMPLES_NXFLAT is not set
+# CONFIG_EXAMPLES_NXHELLO is not set
+# CONFIG_EXAMPLES_NXIMAGE is not set
+# CONFIG_EXAMPLES_NXLINES is not set
+# CONFIG_EXAMPLES_NXTEXT is not set
+# CONFIG_EXAMPLES_OSTEST is not set
+# CONFIG_EXAMPLES_PIPE is not set
+# CONFIG_EXAMPLES_POSIXSPAWN is not set
+# CONFIG_EXAMPLES_QENCODER is not set
+# CONFIG_EXAMPLES_RGMP is not set
+# CONFIG_EXAMPLES_ROMFS is not set
+# CONFIG_EXAMPLES_SENDMAIL is not set
+# CONFIG_EXAMPLES_SERIALBLASTER is not set
+# CONFIG_EXAMPLES_SERIALRX is not set
+# CONFIG_EXAMPLES_SERLOOP is not set
+# CONFIG_EXAMPLES_SLCD is not set
+# CONFIG_EXAMPLES_SMART_TEST is not set
+# CONFIG_EXAMPLES_SMART is not set
+# CONFIG_EXAMPLES_TCPECHO is not set
+# CONFIG_EXAMPLES_TELNETD is not set
+# CONFIG_EXAMPLES_THTTPD is not set
+# CONFIG_EXAMPLES_TIFF is not set
+# CONFIG_EXAMPLES_TOUCHSCREEN is not set
+# CONFIG_EXAMPLES_WEBSERVER is not set
+# CONFIG_EXAMPLES_USBSERIAL is not set
+# CONFIG_EXAMPLES_USBTERM is not set
+# CONFIG_EXAMPLES_WATCHDOG is not set
+
+#
+# Graphics Support
+#
+# CONFIG_TIFF is not set
+# CONFIG_GRAPHICS_TRAVELER is not set
+
+#
+# Interpreters
+#
+# CONFIG_INTERPRETERS_FICL is not set
+# CONFIG_INTERPRETERS_PCODE is not set
+# CONFIG_INTERPRETERS_MICROPYTHON is not set
+
+#
+# Network Utilities
+#
+
+#
+# Networking Utilities
+#
+# CONFIG_NETUTILS_CODECS is not set
+# CONFIG_NETUTILS_FTPC is not set
+# CONFIG_NETUTILS_JSON is not set
+# CONFIG_NETUTILS_SMTP is not set
+# CONFIG_NETUTILS_TFTPC is not set
+# CONFIG_NETUTILS_THTTPD is not set
+# CONFIG_NETUTILS_NETLIB is not set
+# CONFIG_NETUTILS_WEBCLIENT is not set
+# CONFIG_NETUTILS_PPPD is not set
+
+#
+# FreeModBus
+#
+# CONFIG_MODBUS is not set
+
+#
+# NSH Library
+#
+CONFIG_NSH_LIBRARY=y
+
+#
+# Command Line Configuration
+#
+CONFIG_NSH_READLINE=y
+# CONFIG_NSH_CLE is not set
+CONFIG_NSH_LINELEN=25
+CONFIG_NSH_DISABLE_SEMICOLON=y
+# CONFIG_NSH_CMDPARMS is not set
+CONFIG_NSH_MAXARGUMENTS=4
+# CONFIG_NSH_ARGCAT is not set
+CONFIG_NSH_NESTDEPTH=0
+CONFIG_NSH_DISABLEBG=y
+CONFIG_NSH_BUILTIN_APPS=y
+
+#
+# Disable Individual commands
+#
+CONFIG_NSH_DISABLE_ADDROUTE=y
+# CONFIG_NSH_DISABLE_CAT is not set
+CONFIG_NSH_DISABLE_CD=y
+CONFIG_NSH_DISABLE_CP=y
+CONFIG_NSH_DISABLE_CMP=y
+CONFIG_NSH_DISABLE_DD=y
+CONFIG_NSH_DISABLE_DF=y
+CONFIG_NSH_DISABLE_DELROUTE=y
+# CONFIG_NSH_DISABLE_ECHO is not set
+CONFIG_NSH_DISABLE_EXEC=y
+CONFIG_NSH_DISABLE_EXIT=y
+# CONFIG_NSH_DISABLE_FREE is not set
+CONFIG_NSH_DISABLE_GET=y
+# CONFIG_NSH_DISABLE_HELP is not set
+CONFIG_NSH_DISABLE_HEXDUMP=y
+CONFIG_NSH_DISABLE_IFCONFIG=y
+CONFIG_NSH_DISABLE_KILL=y
+CONFIG_NSH_DISABLE_LOSETUP=y
+# CONFIG_NSH_DISABLE_LS is not set
+CONFIG_NSH_DISABLE_MB=y
+CONFIG_NSH_DISABLE_MKDIR=y
+CONFIG_NSH_DISABLE_MKFIFO=y
+CONFIG_NSH_DISABLE_MKRD=y
+CONFIG_NSH_DISABLE_MH=y
+CONFIG_NSH_DISABLE_MOUNT=y
+CONFIG_NSH_DISABLE_MV=y
+CONFIG_NSH_DISABLE_MW=y
+CONFIG_NSH_DISABLE_PS=y
+CONFIG_NSH_DISABLE_PUT=y
+CONFIG_NSH_DISABLE_PWD=y
+CONFIG_NSH_DISABLE_RM=y
+CONFIG_NSH_DISABLE_RMDIR=y
+CONFIG_NSH_DISABLE_SET=y
+CONFIG_NSH_DISABLE_SH=y
+CONFIG_NSH_DISABLE_SLEEP=y
+CONFIG_NSH_DISABLE_TEST=y
+CONFIG_NSH_DISABLE_UMOUNT=y
+CONFIG_NSH_DISABLE_UNSET=y
+CONFIG_NSH_DISABLE_USLEEP=y
+CONFIG_NSH_DISABLE_WGET=y
+CONFIG_NSH_DISABLE_XD=y
+
+#
+# Configure Command Options
+#
+CONFIG_NSH_CODECS_BUFSIZE=0
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+CONFIG_NSH_FILEIOSIZE=64
+
+#
+# Scripting Support
+#
+CONFIG_NSH_DISABLESCRIPT=y
+
+#
+# Console Configuration
+#
+CONFIG_NSH_CONSOLE=y
+# CONFIG_NSH_ALTCONDEV is not set
+CONFIG_NSH_ARCHINIT=y
+
+#
+# NxWidgets/NxWM
+#
+
+#
+# Platform-specific Support
+#
+# CONFIG_PLATFORM_CONFIGDATA is not set
+
+#
+# System Libraries and NSH Add-Ons
+#
+
+#
+# Custom Free Memory Command
+#
+# CONFIG_SYSTEM_FREE is not set
+
+#
+# EMACS-like Command Line Editor
+#
+# CONFIG_SYSTEM_CLE is not set
+
+#
+# CU Minimal Terminal
+#
+# CONFIG_SYSTEM_CUTERM is not set
+
+#
+# FLASH Program Installation
+#
+# CONFIG_SYSTEM_INSTALL is not set
+
+#
+# FLASH Erase-all Command
+#
+
+#
+# Intel HEX to binary conversion
+#
+# CONFIG_SYSTEM_HEX2BIN is not set
+
+#
+# I2C tool
+#
+
+#
+# INI File Parser
+#
+# CONFIG_SYSTEM_INIFILE is not set
+
+#
+# NxPlayer media player library / command Line
+#
+
+#
+# RAM test
+#
+# CONFIG_SYSTEM_RAMTEST is not set
+
+#
+# readline()
+#
+CONFIG_SYSTEM_READLINE=y
+CONFIG_READLINE_ECHO=y
+
+#
+# P-Code Support
+#
+
+#
+# PHY Tool
+#
+
+#
+# Power Off
+#
+# CONFIG_SYSTEM_POWEROFF is not set
+
+#
+# RAMTRON
+#
+# CONFIG_SYSTEM_RAMTRON is not set
+
+#
+# SD Card
+#
+# CONFIG_SYSTEM_SDCARD is not set
+
+#
+# Sudoku
+#
+# CONFIG_SYSTEM_SUDOKU is not set
+
+#
+# Sysinfo
+#
+# CONFIG_SYSTEM_SYSINFO is not set
+
+#
+# Temperature
+#
+
+#
+# VI Work-Alike Editor
+#
+# CONFIG_SYSTEM_VI is not set
+
+#
+# Stack Monitor
+#
+# CONFIG_SYSTEM_STACKMONITOR is not set
+
+#
+# USB CDC/ACM Device Commands
+#
+
+#
+# USB Composite Device Commands
+#
+
+#
+# USB Mass Storage Device Commands
+#
+
+#
+# USB Monitor
+#
+
+#
+# Zmodem Commands
+#
+# CONFIG_SYSTEM_ZMODEM is not set
diff --git a/nuttx-configs/px4cannode-v1/nsh/setenv.sh b/nuttx-configs/px4cannode-v1/nsh/setenv.sh
new file mode 100755
index 000000000..a64b25537
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/setenv.sh
@@ -0,0 +1,80 @@
+#!/bin/bash
+# configs/px4cannode-v1/smallnsh/setenv.sh
+#
+# 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.
+#
+
+if [ "$_" = "$0" ] ; then
+ echo "You must source this script, not run it!" 1>&2
+ exit 1
+fi
+
+WD=`pwd`
+if [ ! -x "setenv.sh" ]; then
+ echo "This script must be executed from the top-level NuttX build directory"
+ exit 1
+fi
+
+if [ -z "${PATH_ORIG}" ]; then
+ export PATH_ORIG="${PATH}"
+fi
+
+# This is the Cygwin path to the location where I installed the RIDE
+# toolchain under windows. You will also have to edit this if you install
+# the RIDE toolchain in any other location
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/Raisonance/Ride/arm-gcc/bin"
+#export TOOLCHAIN_BIN="/cygdrive/c/Users/MyName/MentorGraphics/Sourcery_CodeBench_Lite_for_ARM_EABI/bin"
+
+# This is the Cygwin path to the location where I installed the CodeSourcery
+# toolchain under windows. You will also have to edit this if you install
+# the CodeSourcery toolchain in any other location
+export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/CodeSourcery/Sourcery G++ Lite/bin"
+
+# These are the Cygwin paths to the locations where I installed the Atollic
+# toolchain under windows. You will also have to edit this if you install
+# the Atollic toolchain in any other location. /usr/bin is added before
+# the Atollic bin path because there is are binaries named gcc.exe and g++.exe
+# at those locations as well.
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for ARM Pro 2.3.0/ARMTools/bin"
+#export TOOLCHAIN_BIN="/usr/bin:/cygdrive/c/Program Files (x86)/Atollic/TrueSTUDIO for STMicroelectronics STM32 Lite 2.3.0/ARMTools/bin"
+
+# This is the location where I installed the ARM "GNU Tools for ARM Embedded Processors"
+# You can this free toolchain here https://launchpad.net/gcc-arm-embedded
+#export TOOLCHAIN_BIN="/cygdrive/c/Program Files (x86)/GNU Tools ARM Embedded/4.9 2014q4/bin"
+
+# This is the Cygwin path to the location where I build the buildroot
+# toolchain.
+#export TOOLCHAIN_BIN="${WD}/../misc/buildroot/build_arm_nofpu/staging_dir/bin"
+
+# Add the path to the toolchain to the PATH varialble
+export PATH="${TOOLCHAIN_BIN}:/sbin:/usr/sbin:${PATH_ORIG}"
+
+echo "PATH : ${PATH}"
diff --git a/nuttx-configs/px4cannode-v1/scripts/bootloaderld.script b/nuttx-configs/px4cannode-v1/scripts/bootloaderld.script
new file mode 100644
index 000000000..f787aa3d6
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/scripts/bootloaderld.script
@@ -0,0 +1,136 @@
+/****************************************************************************
+ * configs/px4cannode-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 STM32F103RB has 128Kb of FLASH beginning at address 0x0800:0000 and
+ * 20Kb 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 Bootloade uses the first 8K
+ */
+
+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
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param))
+ __param_end = 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) }
+}
diff --git a/nuttx-configs/px4cannode-v1/scripts/ld.script b/nuttx-configs/px4cannode-v1/scripts/ld.script
new file mode 100644
index 000000000..f058f647c
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/scripts/ld.script
@@ -0,0 +1,140 @@
+/****************************************************************************
+ * configs/px4cannode-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 STM32F103RB has 128Kb of FLASH beginning at address 0x0800:0000 and
+ * 20Kb 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.
+ */
+
+MEMORY
+{
+ flash (rx) : ORIGIN = 0x08000000, LENGTH = 128K
+ 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(.);
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
+ } > flash
+
+/*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param))
+ __param_end = 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) }
+}
diff --git a/nuttx-configs/px4cannode-v1/src/Makefile b/nuttx-configs/px4cannode-v1/src/Makefile
new file mode 100644
index 000000000..f3365d3f1
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/src/Makefile
@@ -0,0 +1,96 @@
+############################################################################
+#
+# 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)/Make.defs
+
+CFLAGS += -I$(TOPDIR)/sched
+
+ASRCS =
+AOBJS = $(ASRCS:.S=$(OBJEXT))
+
+ifeq ($(CONFIG_BOOTLOADER),)
+CSRCS = empty.c
+endif
+ifeq ($(CONFIG_BOOTLOADER),y)
+
+SRC_SEARCH = bootloader/can bootloader/src bootloader/common bootloader/uavcan
+
+CSRCS = ostubs.c
+
+CFLAGS += $(addprefix -I,$(SRC_SEARCH))
+DEPOPTS = $(addprefix --dep-path ,$(SRC_SEARCH))
+VPATH= $(SRC_SEARCH)
+endif
+
+COBJS = $(CSRCS:.c=$(OBJEXT))
+
+SRCS = $(ASRCS) $(CSRCS)
+OBJS = $(AOBJS) $(COBJS)
+
+ARCH_SRCDIR = $(TOPDIR)/arch/$(CONFIG_ARCH)/src
+ifeq ($(WINTOOL),y)
+ CFLAGS += -I "${shell cygpath -w $(ARCH_SRCDIR)/chip}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/common}" \
+ -I "${shell cygpath -w $(ARCH_SRCDIR)/armv7-m}"
+else
+ CFLAGS += -I$(ARCH_SRCDIR)/chip -I$(ARCH_SRCDIR)/common -I$(ARCH_SRCDIR)/armv7-m
+endif
+
+all: libboard$(LIBEXT)
+
+$(AOBJS): %$(OBJEXT): %.S
+ $(call ASSEMBLE, $<, $@)
+
+$(COBJS) $(LINKOBJS): %$(OBJEXT): %.c
+ $(call COMPILE, $<, $@)
+
+libboard$(LIBEXT): $(OBJS)
+ $(call ARCHIVE, $@, $(OBJS))
+
+.depend: Makefile $(SRCS)
+ @$(MKDEP) $(CC) -- $(CFLAGS) -- $(SRCS) >Make.dep
+ @touch $@
+
+depend: .depend
+
+clean:
+ $(call DELFILE, libboard$(LIBEXT))
+ $(call CLEAN)
+
+distclean: clean
+ $(call DELFILE, Make.dep)
+ $(call DELFILE, .depend)
+
+-include Make.dep
diff --git a/nuttx-configs/px4cannode-v1/src/empty.c b/nuttx-configs/px4cannode-v1/src/empty.c
new file mode 100644
index 000000000..5de10699f
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/src/empty.c
@@ -0,0 +1,4 @@
+/*
+ * There are no source files here, but libboard.a can't be empty, so
+ * we have this empty source file to keep it company.
+ */
diff --git a/nuttx-configs/px4cannode-v1/src/ostubs.c b/nuttx-configs/px4cannode-v1/src/ostubs.c
new file mode 100644
index 000000000..cb5b77881
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/src/ostubs.c
@@ -0,0 +1,171 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <nuttx/init.h>
+#include <nuttx/arch.h>
+#include <nuttx/kmalloc.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <syslog.h>
+#include <errno.h>
+
+#include <nuttx/board.h>
+
+#include "up_internal.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+volatile dq_queue_t g_readytorun;
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+void timer_init(void);
+int __wrap_up_svcall(int irq, FAR void *context);
+
+/****************************************************************************
+ * Name: os_start
+ *
+ * Description:
+ * This function hijacks the entry point of the OS. Normally called by the
+ * statup code for a given architecture
+ *
+ ****************************************************************************/
+
+void os_start(void)
+{
+ /* Intalize the timer software subsystem */
+
+ timer_init();
+
+ /* Initialize the interrupt subsystem */
+
+ up_irqinitialize();
+
+ /* Initialize the OS's timer subsystem */
+#if !defined(CONFIG_SUPPRESS_INTERRUPTS) && !defined(CONFIG_SUPPRESS_TIMER_INTS) && \
+ !defined(CONFIG_SYSTEMTICK_EXTCLK)
+ up_timer_initialize();
+#endif
+
+ /* Keep the compiler happy for a no return function */
+
+ while (1)
+ {
+ main(0, 0);
+ }
+}
+
+/****************************************************************************
+ * Name: malloc
+ *
+ * Description:
+ * This function hijacks the OS's malloc and provides no allocation
+ *
+ ****************************************************************************/
+
+FAR void *malloc(size_t size)
+{
+ return NULL;
+}
+
+/****************************************************************************
+ * Name: malloc
+ *
+ * Description:
+ * This function hijacks the systems exit
+ *
+ ****************************************************************************/
+void exit(int status)
+{
+ while (1);
+}
+
+/****************************************************************************
+ * Name: sched_ufree
+ *
+ * Description:
+ * This function hijacks the systems sched_ufree that my be called during
+ * exception processing.
+ *
+ ****************************************************************************/
+
+void sched_ufree(FAR void *address)
+{
+
+}
+
+/****************************************************************************
+ * Name: up_svcall
+ *
+ * Description:
+ * This function hijacks by the way of a compile time wrapper the systems
+ * up_svcall
+ *
+ ****************************************************************************/
+
+int __wrap_up_svcall(int irq, FAR void *context)
+{
+ return 0;
+}
diff --git a/nuttx-configs/px4fmu-v2/include/board.h b/nuttx-configs/px4fmu-v2/include/board.h
index d61cd1631..7fe791662 100755
--- a/nuttx-configs/px4fmu-v2/include/board.h
+++ b/nuttx-configs/px4fmu-v2/include/board.h
@@ -310,6 +310,10 @@
# define PROBE(n,s) do {stm32_gpiowrite(PROBE_##n,(s));}while(0)
# define PROBE_MARK(n) PROBE(n,false);PROBE(n,true)
+#else
+# define PROBE_INIT(mask)
+# define PROBE(n,s)
+# define PROBE_MARK(n)
#endif
diff --git a/src/drivers/boards/aerocore/board_config.h b/src/drivers/boards/aerocore/board_config.h
index 85de14c28..5a65dc3b6 100644
--- a/src/drivers/boards/aerocore/board_config.h
+++ b/src/drivers/boards/aerocore/board_config.h
@@ -53,7 +53,6 @@ __BEGIN_DECLS
#include <stm32.h>
#include <arch/board/board.h>
-#define UDID_START 0x1FFF7A10
/****************************************************************************************************
* Definitions
diff --git a/src/drivers/boards/mavstation/board_config.h b/src/drivers/boards/mavstation/board_config.h
index 8aeeac83c..c47fce749 100644
--- a/src/drivers/boards/mavstation/board_config.h
+++ b/src/drivers/boards/mavstation/board_config.h
@@ -54,7 +54,6 @@
/************************************************************************************
* Definitions
************************************************************************************/
-#define UDID_START 0x1FFFF7E8
/* PX4IO GPIOs **********************************************************************/
/* LEDs */
diff --git a/src/drivers/boards/px4cannode-v1/board_config.h b/src/drivers/boards/px4cannode-v1/board_config.h
new file mode 100644
index 000000000..42b73a7e9
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/board_config.h
@@ -0,0 +1,311 @@
+/****************************************************************************
+ *
+ * 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_config.h
+ *
+ * PX4CANNODEv1 internal definitions
+ */
+
+#pragma once
+
+/****************************************************************************************************
+ * Included Files
+ ****************************************************************************************************/
+
+#include <nuttx/config.h>
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+__BEGIN_DECLS
+
+/* these headers are not C++ safe */
+#include <stm32.h>
+#include <arch/board/board.h>
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+#if STM32_NSPI < 1
+# undef CONFIG_STM32_SPI1
+# undef CONFIG_STM32_SPI2
+#elif STM32_NSPI < 2
+# undef CONFIG_STM32_SPI2
+#endif
+
+/* High-resolution timer
+ */
+#define HRT_TIMER 1 /* use timer1 for the HRT */
+#define HRT_TIMER_CHANNEL 1 /* use capture/compare channel */
+#define HRT_PPM_CHANNEL 3 /* use capture/compare channel 3 */
+#define GPIO_PPM_IN (GPIO_ALT|GPIO_CNF_INPULLUP|GPIO_PORTB|GPIO_PIN12)
+
+/* LEDs *****************************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ *
+ * PA[05] PA5/SPI1_SCK/ADC5 21 D13(SCK1/LED1)
+ * PA[01] PA1/USART2_RTS/ADC1/TIM2_CH2 15 D3(LED2)
+ */
+
+#define GPIO_LED1 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTA | GPIO_PIN5 | GPIO_OUTPUT_CLEAR)
+#define GPIO_LED_GREEN GPIO_LED1
+#define LED_GREEN 0
+#define GPIO_LED2 (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTA | GPIO_PIN1 | GPIO_OUTPUT_CLEAR)
+#define GPIO_LED_YELLOW GPIO_LED2
+#define LED_YELLOW 1
+
+/* BUTTON ***************************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ *
+ * PC[09] PC9/TIM3_CH4 40 BOOT0
+ *
+ */
+
+#define BUTTON_BOOT0n (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_PORTC | GPIO_PIN9 | \
+ GPIO_EXTI)
+#define IRQBUTTON BUTTON_BOOT0_BIT
+
+/* USBs *****************************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ *
+ * PC[11] PC11/USART3_RX 52 USB_P
+ * PC[12] PC12/USART3_CK 53 DISC
+ *
+ */
+
+#define GPIO_USB_VBUS (GPIO_INPUT | GPIO_CNF_INFLOAT | GPIO_PORTC | GPIO_PIN11)
+#define GPIO_USB_PULLUPn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTC | GPIO_PIN12 | GPIO_OUTPUT_SET)
+
+/* SPI ***************************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ *
+ * PC[09] PA4/SPI1_NSS/USART2_CK/ADC4 20 D10(#SS1)
+ * PD[02] PD2/TIM3_ETR 54 D25(MMC_CS)
+ */
+
+#define GPIO_SPI1_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTC | GPIO_PIN9 | GPIO_OUTPUT_SET)
+#define USER_CSn GPIO_SPI1_SSn
+
+#define GPIO_SPI2_SSn (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTD | GPIO_PIN2 | GPIO_OUTPUT_SET)
+#define MMCSD_CSn GPIO_SPI2_SSn
+
+/* CAN ***************************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ *
+ * PB[08] PB8/TIM4_CH3/I2C1_SCL/CANRX 61 D14(CANRX)
+ * PB[09] PB9/TIM4_CH4/I2C1_SDA/CANTX 62 D24(CANTX)
+ * PC[13] PC13/ANTI_TAMP 2 D21(CAN_CTRL)
+ */
+
+#define GPIO_CAN_CTRL (GPIO_OUTPUT | GPIO_CNF_OUTPP | GPIO_MODE_50MHz | \
+ GPIO_PORTC | GPIO_PIN13 | GPIO_OUTPUT_CLEAR)
+
+/************************************************************************************
+ * Public Types
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public data
+ ************************************************************************************/
+
+#ifndef __ASSEMBLY__
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins.
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || \
+ defined(CONFIG_STM32_SPI3)
+void weak_function board_spiinitialize(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_usbinitialize
+ *
+ * Description:
+ * Called to setup USB-related GPIO pins.
+ *
+ ************************************************************************************/
+
+void stm32_usbinitialize(void);
+
+/************************************************************************************
+ * Name: stm32_usb_set_pwr_callback()
+ *
+ * Description:
+ * Called to setup set a call back for USB power state changes.
+ *
+ * Inputs:
+ * pwr_changed_handler: An interrupt handler that will be called on VBUS power
+ * state changes.
+ *
+ ************************************************************************************/
+
+void stm32_usb_set_pwr_callback(xcpt_t pwr_changed_handler);
+
+/************************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization for NSH.
+ *
+ * CONFIG_NSH_ARCHINIT=y :
+ * Called from the NSH library
+ *
+ * CONFIG_BOARD_INITIALIZE=y, CONFIG_NSH_LIBRARY=y, &&
+ * CONFIG_NSH_ARCHINIT=n :
+ * Called from board_initialize().
+ *
+ ************************************************************************************/
+
+#ifdef CONFIG_NSH_LIBRARY
+int nsh_archinitialize(void);
+#endif
+
+/****************************************************************************
+ * Name: stm32_led_initialize
+ *
+ * Description:
+ * This functions is called very early in initialization to perform board-
+ * specific initialization of LED-related resources. This includes such
+ * things as, for example, configure GPIO pins to drive the LEDs and also
+ * putting the LEDs in their correct initial state.
+ *
+ * NOTE: In most architectures, LED initialization() is called from
+ * board-specific initialization and should, therefore, have the name
+ * <arch>_led_intialize(). But there are a few architectures where the
+ * LED initialization function is still called from common chip
+ * architecture logic. This interface is not, however, a common board
+ * interface in any event and the name board_led_initialization is
+ * deprecated.
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_LEDS
+void board_led_initialize(void);
+#endif
+
+/************************************************************************************
+ * Name: stm32_can_initialize
+ *
+ * Description:
+ * Called at application startup time to initialize the CAN functionality.
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_CAN) && (defined(CONFIG_STM32_CAN1) || defined(CONFIG_STM32_CAN2))
+int board_can_initialize(void);
+#endif
+
+/************************************************************************************
+ * Name: board_button_initialize
+ *
+ * Description:
+ * Called at application startup time to initialize the Buttons functionality.
+ *
+ ************************************************************************************/
+
+#if defined(CONFIG_ARCH_BUTTONS)
+void board_button_initialize(void);
+#endif
+
+/****************************************************************************
+ * Name: usbmsc_archinitialize
+ *
+ * Description:
+ * Called from the application system/usbmc or the boards_nsh if the
+ * application is not included.
+ * Perform architecture specific initialization. This function must
+ * configure the block device to export via USB. This function must be
+ * provided by architecture-specific logic in order to use this add-on.
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_NSH_BUILTIN_APPS) && !defined(CONFIG_SYSTEM_USBMSC)
+int usbmsc_archinitialize(void);
+#endif
+
+/****************************************************************************
+ * Name: composite_archinitialize
+ *
+ * Description:
+ * Called from the application system/composite or the boards_nsh if the
+ * application is not included.
+ * Perform architecture specific initialization. This function must
+ * configure the block device to export via USB. This function must be
+ * provided by architecture-specific logic in order to use this add-on.
+ *
+ ****************************************************************************/
+
+#if !defined(CONFIG_NSH_BUILTIN_APPS) && !defined(CONFIG_SYSTEM_COMPOSITE)
+extern int composite_archinitialize(void);
+#endif
+///
+#endif /* __ASSEMBLY__ */
+
+__END_DECLS
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/can/driver.c b/src/drivers/boards/px4cannode-v1/bootloader/can/driver.c
new file mode 100644
index 000000000..5cd524e35
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/can/driver.c
@@ -0,0 +1,524 @@
+/****************************************************************************
+ *
+ * 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 "board_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 "bl_macros.h"
+#include "driver.h"
+#include "crc.h"
+#include "timer.h"
+
+#include <arch/board/board.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define INAK_TIMEOUT 65535
+
+#define CAN_1MBAUD_SJW 0
+#define CAN_1MBAUD_BS1 6u
+#define CAN_1MBAUD_BS2 0
+#define CAN_1MBAUD_PRESCALER 4u
+
+#define CAN_500KBAUD_SJW 0
+#define CAN_500KBAUD_BS1 6u
+#define CAN_500KBAUD_BS2 0
+#define CAN_500KBAUD_PRESCALER 8u
+
+#define CAN_250KBAUD_SJW 0
+#define CAN_250KBAUD_BS1 6u
+#define CAN_250KBAUD_BS2 0
+#define CAN_250KBAUD_PRESCALER 16u
+
+#define CAN_125KBAUD_SJW 0
+#define CAN_125KBAUD_BS1 6u
+#define CAN_125KBAUD_BS2 0
+#define CAN_125KBAUD_PRESCALER 32u
+
+#define CAN_BTR_LBK_SHIFT 30
+
+#define WAIT_TX_READY_MS ((TIMER_HRT_CYCLES_PER_MS-(TIMER_HRT_CYCLES_PER_MS/4))
+
+/* Number of CPU cycles for a single bit time at the supported speeds
+
+#define CAN_1MBAUD_BIT_CYCLES (1*(TIMER_HRT_CYCLES_PER_US))
+#define CAN_500KBAUD_BIT_CYCLES (2*(TIMER_HRT_CYCLES_PER_US))
+#define CAN_250KBAUD_BIT_CYCLES (4*(TIMER_HRT_CYCLES_PER_US))
+
+*/
+
+#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:
+ * None
+ *
+ ****************************************************************************/
+
+void 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. Give it an extra 0.75 ms per
+ * frame to avoid an issue Ben was seeing with packets going missing on a USBtin. */
+
+ uint32_t mask = CAN_TSR_TME0 << mailbox;
+ time_hrt_cycles_t begin = timer_hrt_read();
+
+ while (((getreg32(STM32_CAN1_TSR) & mask) == 0) ||
+ timer_hrt_elapsed(begin, timer_hrt_read()) < WAIT_TX_READY_MS));
+
+ 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));
+ }
+
+/****************************************************************************
+ * 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 << 24) |
+ (CAN_125KBAUD_BS1 << 16) |
+ (CAN_125KBAUD_BS2 << 20) | (CAN_125KBAUD_PRESCALER - 1),
+
+ (CAN_250KBAUD_SJW << 24) |
+ (CAN_250KBAUD_BS1 << 16) |
+ (CAN_250KBAUD_BS2 << 20) | (CAN_250KBAUD_PRESCALER - 1),
+
+ (CAN_500KBAUD_SJW << 24) |
+ (CAN_500KBAUD_BS1 << 16) |
+ (CAN_500KBAUD_BS2 << 20) | (CAN_500KBAUD_PRESCALER - 1),
+
+ (CAN_1MBAUD_SJW << 24) |
+ (CAN_1MBAUD_BS1 << 16) |
+ (CAN_1MBAUD_BS2 << 20) | (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, 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. */
+ putreg32(CAN_FMR_FINIT, STM32_CAN1_FMR);
+ putreg32(0, STM32_CAN1_FA1R); /* Disable all filters */
+ putreg32(3, STM32_CAN1_FS1R); /* Enable 32-bit mode for filters 0 and 1 */
+
+ /* Filter 0 masks -- data type ID 551 only */
+ putreg32(UAVCAN_GETNODEINFO_DTID << 22, STM32_CAN1_FIR(0, 1));
+ /* Top 10 bits of ID */
+ putreg32(0xFFC00000, STM32_CAN1_FIR(0, 2));
+
+ /* Filter 1 masks -- everything is don't-care */
+ putreg32(0, STM32_CAN1_FIR(1, 1));
+ putreg32(0, STM32_CAN1_FIR(1, 2));
+
+ 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 */
+
+ putreg32(0, STM32_CAN1_FMR); /* Leave init Mode */
+
+ return OK;
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/can/driver.h b/src/drivers/boards/px4cannode-v1/bootloader/can/driver.h
new file mode 100644
index 000000000..a149b44e6
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/can/driver.h
@@ -0,0 +1,219 @@
+/****************************************************************************
+ *
+ * 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
+{
+ 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
+{
+ fifoAll = 0,
+ MBAll = 0,
+
+ fifoGetNodeInfo = 1,
+ MBGetNodeInfo = 1,
+ MBNodeStatus = 1,
+
+} 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:
+ * None
+ *
+ ****************************************************************************/
+
+void 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);
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/common/bl_macros.h b/src/drivers/boards/px4cannode-v1/bootloader/common/bl_macros.h
new file mode 100644
index 000000000..648dc890a
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/common/bl_macros.h
@@ -0,0 +1,102 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file bl_macros.h
+ *
+ * A set of useful macros for enhanced runtime and compile time
+ * error detection and warning suppression.
+ *
+ * Define NO_BLOAT to reduce bloat from file name inclusion.
+ *
+ * The arraySize() will compute the size of an array regardless
+ * it's type
+ *
+ * INVALID_CASE(c) should be used is case statements to ferret out
+ * unintended behavior
+ *
+ * UNUSED(var) will suppress compile time warnings of unused
+ * variables
+ *
+ * CCASSERT(predicate) Will generate a compile time error it the
+ * predicate is false
+ */
+#include <assert.h>
+
+#ifndef _BL_MACROS_H
+#define _BL_MACROS_H
+
+
+#if !defined(arraySize)
+#define arraySize(a) (sizeof((a))/sizeof((a[0])))
+#endif
+
+#if !defined(NO_BLOAT)
+#if defined(__BASE_FILE__)
+#define _FILE_NAME_ __BASE_FILE__
+#else
+#define _FILE_NAME_ __FILE__
+#endif
+#else
+#define _FILE_NAME_ ""
+#endif
+
+#if !defined(INVALID_CASE)
+#define INVALID_CASE(c) printf("Invalid Case %d, %s:%d",(c),__BASE_FILE__,__LINE__) /* todo use PANIC */
+#endif
+
+#if !defined(UNUSED)
+#define UNUSED(var) (void)(var)
+#endif
+
+#if !defined(CAT)
+#if !defined(_CAT)
+#define _CAT(a, b) a ## b
+#endif
+#define CAT(a, b) _CAT(a, b)
+#endif
+
+#if !defined(CCASSERT)
+#if defined(static_assert)
+# define CCASSERT(predicate) static_assert(predicate)
+# else
+# define CCASSERT(predicate) _x_CCASSERT_LINE(predicate, __LINE__)
+# if !defined(_x_CCASSERT_LINE)
+# define _x_CCASSERT_LINE(predicate, line) typedef char CAT(constraint_violated_on_line_,line)[2*((predicate)!=0)-1] __attribute__ ((unused)) ;
+# endif
+# endif
+#endif
+
+
+#endif /* _BL_MACROS_H */
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.c b/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.c
new file mode 100644
index 000000000..bcf8178d0
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.c
@@ -0,0 +1,268 @@
+/****************************************************************************
+ *
+ * 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 <stdint.h>
+#include <string.h>
+
+#include "chip.h"
+#include "stm32.h"
+
+#include <errno.h>
+#include "boot_app_shared.h"
+#include "crc.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define BOOTLOADER_COMMON_APP_SIGNATURE 0xB0A04150u
+#define BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE 0xB0A0424Cu
+
+
+/* CAN_FiRx where (i=0..27|13, x=1, 2)
+ * STM32_CAN1_FIR(i,x)
+ * Using i = 2 does not requier there block
+ * to be enabled nor FINIT in CAN_FMR to be set.
+ * todo:Validate this claim on F2, F3
+ */
+
+#define crc_HiLOC STM32_CAN1_FIR(2,1)
+#define crc_LoLOC STM32_CAN1_FIR(2,2)
+#define signature_LOC STM32_CAN1_FIR(3,1)
+#define bus_speed_LOC STM32_CAN1_FIR(3,2)
+#define node_id_LOC STM32_CAN1_FIR(4,1)
+#define CRC_H 1
+#define CRC_L 0
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: read
+ ****************************************************************************/
+
+inline static void read(bootloader_app_shared_t * pshared)
+{
+ pshared->signature = getreg32(signature_LOC);
+ pshared->bus_speed = getreg32(bus_speed_LOC);
+ pshared->node_id = getreg32(node_id_LOC);
+ pshared->crc.ul[CRC_L] = getreg32(crc_LoLOC);
+ pshared->crc.ul[CRC_H] = getreg32(crc_HiLOC);
+
+}
+
+/****************************************************************************
+ * Name: write
+ ****************************************************************************/
+
+inline static void write(bootloader_app_shared_t * pshared)
+{
+ putreg32(pshared->signature, signature_LOC);
+ putreg32(pshared->bus_speed, bus_speed_LOC);
+ putreg32(pshared->node_id, node_id_LOC);
+ putreg32(pshared->crc.ul[CRC_L], crc_LoLOC);
+ putreg32(pshared->crc.ul[CRC_H], crc_HiLOC);
+
+}
+
+/****************************************************************************
+ * Name: calulate_signature
+ ****************************************************************************/
+
+static uint64_t calulate_signature(bootloader_app_shared_t * pshared)
+{
+ size_t size = sizeof(bootloader_app_shared_t) - sizeof(pshared->crc);
+ uint64_t crc = CRC64_INITIAL;
+ uint8_t *protected = (uint8_t *) & pshared->signature;
+
+ while (size--)
+ {
+ crc = crc64_add(crc, *protected++);
+ }
+ crc ^= CRC64_OUTPUT_XOR;
+ return crc;
+}
+
+
+/****************************************************************************
+ * Name: bootloader_app_shared_init
+ ****************************************************************************/
+static void bootloader_app_shared_init(bootloader_app_shared_t * pshared, eRole_t role)
+{
+ memset(pshared, 0, sizeof(bootloader_app_shared_t));
+ if (role != Invalid)
+ {
+ pshared->signature =
+ (role ==
+ App ? BOOTLOADER_COMMON_APP_SIGNATURE :
+ BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE);
+ }
+
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: bootloader_app_shared_read
+ *
+ * Description:
+ * Based on the role requested, this function will conditionally populate
+ * a bootloader_app_shared_t structure from the physical locations used
+ * to transfer the shared data to/from an application (internal data) .
+ *
+ * The functions will only populate the structure and return a status
+ * indicating success, if the internal data has the correct signature as
+ * requested by the Role AND has a valid crc.
+ *
+ * Input Parameters:
+ * shared - A pointer to a bootloader_app_shared_t return the data in if
+ * the internal data is valid for the requested Role
+ * role - An eRole_t of App or BootLoader to validate the internal data
+ * against. For a Bootloader this would be the value of App to
+ * read the application passed data.
+ *
+ * Returned value:
+ * OK - Indicates that the internal data has been copied to callers
+ * bootloader_app_shared_t structure.
+ *
+ * -EBADR - The Role or crc of the internal data was not valid. The copy
+ * did not occur.
+ *
+ ****************************************************************************/
+
+int bootloader_app_shared_read(bootloader_app_shared_t * shared,
+ eRole_t role)
+{
+ int rv = -EBADR;
+ bootloader_app_shared_t working;
+
+ read(&working);
+
+ if ((role == App ? working.signature == BOOTLOADER_COMMON_APP_SIGNATURE
+ : working.signature == BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE)
+ && (working.crc.ull == calulate_signature(&working)))
+ {
+ *shared = working;
+ rv = OK;
+ }
+ return rv;
+}
+
+/****************************************************************************
+ * Name: bootloader_app_shared_write
+ *
+ * Description:
+ * Based on the role, this function will commit the data passed
+ * into the physical locations used to transfer the shared data to/from
+ * an application (internal data) .
+ *
+ * The functions will populate the signature and crc the data
+ * based on the provided Role.
+ *
+ * Input Parameters:
+ * shared - A pointer to a bootloader_app_shared_t data to commit to
+ * the internal data for passing to/from an application.
+ * role - An eRole_t of App or BootLoader to use in the internal data
+ * to be passed to/from an application. For a Bootloader this
+ * would be the value of Bootloader to write to the passed data.
+ * to the application via the internal data.
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void bootloader_app_shared_write(bootloader_app_shared_t * shared,
+ eRole_t role)
+{
+ bootloader_app_shared_t working = *shared;
+ working.signature =
+ (role ==
+ App ? BOOTLOADER_COMMON_APP_SIGNATURE :
+ BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE);
+ working.crc.ull = calulate_signature(&working);
+ write(&working);
+
+}
+
+/****************************************************************************
+ * Name: bootloader_app_shared_invalidate
+ *
+ * Description:
+ * Invalidates the data passed the physical locations used to transfer
+ * the shared data to/from an application (internal data) .
+ *
+ * The functions will invalidate the signature and crc and shoulf be used
+ * to prevent deja vu.
+ *
+ * Input Parameters:
+ * None.
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void bootloader_app_shared_invalidate(void)
+{
+ bootloader_app_shared_t working;
+ bootloader_app_shared_init(&working, Invalid);
+ write(&working);
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.h b/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.h
new file mode 100644
index 000000000..937282894
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/common/boot_app_shared.h
@@ -0,0 +1,224 @@
+/****************************************************************************
+ *
+ * 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 <nuttx/compiler.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/* Define the signature for the Application descriptor as 'APDesc' and a
+ * revision number of 00 used in app_descriptor_t
+ */
+
+#define APP_DESCRIPTOR_SIGNATURE_ID 'A','P','D','e','s','c'
+#define APP_DESCRIPTOR_SIGNATURE_REV '0','0'
+#define APP_DESCRIPTOR_SIGNATURE APP_DESCRIPTOR_SIGNATURE_ID, APP_DESCRIPTOR_SIGNATURE_REV
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+/* eRole defines the role of the bootloader_app_shared_t structure */
+
+typedef enum eRole {
+ Invalid,
+ App,
+ BootLoader
+} eRole_t;
+
+/****************************************************************************
+ *
+ * Bootloader and Application shared structure.
+ *
+ * The data in this structure is passed in SRAM or the the CAN filter
+ * registers from bootloader to application and application to bootloader.
+ *
+ * Do not assume any mapping or location for the passing of this data
+ * that is done in the read and write routines and is abstracted by design.
+ *
+ * For reference, the following is performed based on eRole in API calls
+ * defined below:
+ *
+ * The application must write BOOTLOADER_COMMON_APP_SIGNATURE to the
+ * signature field when passing data to the bootloader; when the
+ * bootloader passes data to the application, it must write
+ * BOOTLOADER_COMMON_BOOTLOADER_SIGNATURE to the signature field.
+ *
+ * The CRC is calculated over the structure from signature to the
+ * last byte. The resulting values are then copied to the CAN filter
+ * registers by bootloader_app_shared_read and
+ * bootloader_app_shared_write.
+ *
+****************************************************************************/
+
+typedef struct packed_struct bootloader_app_shared_t {
+ union
+ {
+ uint64_t ull;
+ uint32_t ul[2];
+ } crc;
+ uint32_t signature;
+ uint32_t bus_speed;
+ uint32_t node_id;
+} bootloader_app_shared_t ;
+
+/****************************************************************************
+ *
+ * Application firmware descriptor.
+ *
+ * This structure located by the linker script somewhere after the vector table.
+ * (within the first several kilobytes of the beginning address of the
+ * application);
+ *
+ * This structure must be aligned on an 8-byte boundary.
+ *
+ * The bootloader will scan through the application FLASH image until it
+ * finds the signature.
+ *
+ * The image_crc is calculated as follows:
+ * 1) All fields of this structure must be initialized with the correct
+ * information about the firmware image bin file
+ * (Here after refereed to as image)
+ * 2) image_crc set to 0;
+ * 3) The CRC 64 is calculated over the image from offset 0 up to and including the
+ * last byte of the image file.
+ * 4) The calculated CRC 64 is stored in image_crc
+ * 5) The new image file is then written to a file a ".img" extension.
+ *
+****************************************************************************/
+
+typedef struct packed_struct app_descriptor_t
+{
+ uint64_t signature;
+ uint64_t image_crc;
+ uint32_t image_size;
+ uint32_t vcs_commit;
+ uint8_t major_version;
+ uint8_t minor_version;
+ uint8_t reserved[6];
+} app_descriptor_t;
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/****************************************************************************
+ * Name: bootloader_app_shared_read
+ *
+ * Description:
+ * Based on the role requested, this function will conditionally populate
+ * a bootloader_app_shared_t structure from the physical locations used
+ * to transfer the shared data to/from an application (internal data) .
+ *
+ * The functions will only populate the structure and return a status
+ * indicating success, if the internal data has the correct signature as
+ * requested by the Role AND has a valid crc.
+ *
+ * Input Parameters:
+ * shared - A pointer to a bootloader_app_shared_t return the data in if
+ * the internal data is valid for the requested Role
+ * role - An eRole_t of App or BootLoader to validate the internal data
+ * against. For a Bootloader this would be the value of App to
+ * read the application passed data.
+ *
+ * Returned value:
+ * OK - Indicates that the internal data has been copied to callers
+ * bootloader_app_shared_t structure.
+ *
+ * -EBADR - The Role or crc of the internal data was not valid. The copy
+ * did not occur.
+ *
+ ****************************************************************************/
+
+int bootloader_app_shared_read(bootloader_app_shared_t * shared,
+ eRole_t role);
+
+/****************************************************************************
+ * Name: bootloader_app_shared_write
+ *
+ * Description:
+ * Based on the role, this function will commit the data passed
+ * into the physical locations used to transfer the shared data to/from
+ * an application (internal data) .
+ *
+ * The functions will populate the signature and crc the data
+ * based on the provided Role.
+ *
+ * Input Parameters:
+ * shared - A pointer to a bootloader_app_shared_t data to commit to
+ * the internal data for passing to/from an application.
+ * role - An eRole_t of App or BootLoader to use in the internal data
+ * to be passed to/from an application. For a Bootloader this
+ * would be the value of Bootloader to write to the passed data.
+ * to the application via the internal data.
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void bootloader_app_shared_write(bootloader_app_shared_t * shared,
+ eRole_t role);
+
+/****************************************************************************
+ * Name: bootloader_app_shared_invalidate
+ *
+ * Description:
+ * Invalidates the data passed the physical locations used to transfer
+ * the shared data to/from an application (internal data) .
+ *
+ * The functions will invalidate the signature and crc and should be used
+ * to prevent deja vu.
+ *
+ * Input Parameters:
+ * None.
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void bootloader_app_shared_invalidate(void);
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/module.mk b/src/drivers/boards/px4cannode-v1/bootloader/module.mk
new file mode 100644
index 000000000..f826bbb31
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/module.mk
@@ -0,0 +1,14 @@
+#
+# Board-specific Bootloader code for the PX4CANNODE
+#
+
+SRCS = src/boot.c \
+ src/timer.c \
+ src/flash.c \
+ src/crc.c \
+ can/driver.c \
+ uavcan/protocol.c \
+ uavcan/main.c \
+ common/boot_app_shared.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/board_config.h b/src/drivers/boards/px4cannode-v1/bootloader/src/board_config.h
new file mode 100644
index 000000000..0f8657274
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/board_config.h
@@ -0,0 +1,201 @@
+/****************************************************************************
+ *
+ * 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_config.h
+ *
+ * PX4CANNODEv1 for the bootloader internal definitions
+ * This file is related to the parrent folder version but defines
+ * differnet 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 "protocol.h"
+#include <nuttx/compiler.h>
+#include <stdint.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+//todo:wrap OPT_x in in ifdefs for command line definitions
+#define OPT_TBOOT_MS 2000
+#define OPT_NODE_STATUS_RATE_MS 800
+#define OPT_NODE_INFO_RATE_MS 200
+#define OPT_BL_NUMBER_TIMERS 6
+
+#define OPT_WAIT_FOR_GETNODEINFO 0
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO 1
+#define OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT 1
+
+#define OPT_ENABLE_WD 1
+
+#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 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_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)))
+
+
+
+/* Bootloader Option*****************************************************************
+ *
+ * GPIO Function MPU Board
+ * Pin # Name
+ * -- ----- -------------------------------- ----------------------------
+ * * PC[09] PC9/TIM3_CH4 40 BOOT0
+ */
+#define GPIO_GETNODEINFO_JUMPER (BUTTON_BOOT0n&~(GPIO_EXTI))
+
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+typedef enum {
+
+ 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 retrive the hardware version information.
+ *
+ * Input Parameters:
+ * hw_version - A pointer to a uavcan_hardwareversion_t.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void 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__ */
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/boot.c b/src/drivers/boards/px4cannode-v1/bootloader/src/boot.c
new file mode 100644
index 000000000..079b2fa3f
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/boot.c
@@ -0,0 +1,205 @@
+/****************************************************************************
+ *
+ * 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 "board_config.h"
+
+#include <debug.h>
+#include <arch/board/board.h>
+
+#include <nuttx/board.h>
+
+#include "board_config.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 priore 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 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)
+{
+ DEBUGASSERT(maxlen > 3);
+ product_name[0] = 'h';
+ product_name[1] = 'i';
+ product_name[2] = '!';
+ return 3u;
+}
+
+/****************************************************************************
+ * Name: board_get_hardware_version
+ *
+ * Description:
+ * Called to retrive the hardware version information.
+ *
+ * Input Parameters:
+ * hw_version - A pointer to a uavcan_hardwareversion_t.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+void board_get_hardware_version(uavcan_hardwareversion_t * hw_version)
+{
+ uint32_t i;
+ volatile uint8_t *stm32f_uid = (volatile uint8_t *)STM32_SYSMEM_UID;
+
+ hw_version->major = 1u;
+ hw_version->minor = 0u;
+
+ for (i = 0u; i < 12u; i++)
+ {
+ hw_version->unique_id[i] = stm32f_uid[i];
+ }
+ for (; i < 16u; i++)
+ {
+ hw_version->unique_id[i] = 0u;
+ }
+
+ for (i = 0u; i < 255u; i++)
+ {
+ hw_version->certificate_of_authenticity[i] = 0;
+ }
+
+ hw_version->certificate_of_authenticity_length = 0u;
+}
+
+/****************************************************************************
+ * 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)
+{
+//todo:Indicate state on Led
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/crc.c b/src/drivers/boards/px4cannode-v1/bootloader/src/crc.c
new file mode 100644
index 000000000..34d852bc5
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/crc.c
@@ -0,0 +1,169 @@
+/****************************************************************************
+ *
+ * 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 <stdint.h>
+#include <stdlib.h>
+#include "crc.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: crc16_add
+ *
+ * Description:
+ * Use to caculates a CRC-16-CCITT using the polynomial of
+ * 0x1021 by adding a value successive values.
+ *
+ * Input Parameters:
+ * crc - The running total of the crc 16
+ * value - The value to add
+ *
+ * Returned Value:
+ * The current crc16 with the value processed.
+ *
+ ****************************************************************************/
+
+uint16_t crc16_add(uint16_t crc, uint8_t value)
+{
+ uint32_t i;
+ const uint16_t poly = 0x1021u;
+ crc ^= (uint16_t) ((uint16_t) value << 8u);
+ for (i = 0; i < 8; i++)
+ {
+ if (crc & (1u << 15u))
+ {
+ crc = (uint16_t) ((crc << 1u) ^ poly);
+ }
+ else
+ {
+ crc = (uint16_t) (crc << 1u);
+ }
+ }
+ return crc;
+}
+
+/****************************************************************************
+ * Name: crc16_signature
+ *
+ * Description:
+ * Caculates a CRC-16-CCITT using the crc16_add
+ * function
+ *
+ * Input Parameters:
+ * initial - The Inital value to uses as the crc's statrting point
+ * length - The number of bytes to add to the crc
+ * bytes - A pointer to any array of length bytes
+ *
+ * Returned Value:
+ * The crc16 of the array of bytes
+ *
+ ****************************************************************************/
+
+uint16_t crc16_signature(uint16_t initial, size_t length,
+ const uint8_t *bytes)
+{
+ size_t i;
+ for (i = 0u; i < length; i++) {
+ initial = crc16_add(initial, bytes[i]);
+ }
+ return initial ^ CRC16_OUTPUT_XOR;
+}
+
+/****************************************************************************
+ * Name: crc64_add
+ *
+ * Description:
+ * Caculates a CRC-64-WE usinsg the polynomial of 0x42F0E1EBA9EA3693
+ * See http://reveng.sourceforge.net/crc-catalogue/17plus.htm#crc.cat-bits.64
+ * Check: 0x62EC59E3F1A4F00A
+ *
+ * Input Parameters:
+ * crc - The running total of the crc 64
+ * value - The value to add
+ *
+ * Returned Value:
+ * The current crc64 with the value processed.
+ *
+ ****************************************************************************/
+
+uint64_t crc64_add(uint64_t crc, uint8_t value)
+{
+ uint32_t i;
+ const uint64_t poly = 0x42F0E1EBA9EA3693ull;
+ crc ^= (uint64_t) value << 56u;
+ for (i = 0; i < 8; i++)
+ {
+ if (crc & (1ull << 63u))
+ {
+ crc = (uint64_t) (crc << 1u) ^ poly;
+ }
+ else
+ {
+ crc = (uint64_t) (crc << 1u);
+ }
+ }
+ return crc;
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/crc.h b/src/drivers/boards/px4cannode-v1/bootloader/src/crc.h
new file mode 100644
index 000000000..2ca756b9c
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/crc.h
@@ -0,0 +1,117 @@
+/****************************************************************************
+ *
+ * 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: crc16_add
+ *
+ * Description:
+ * Use to caculates a CRC-16-CCITT using the polynomial of
+ * 0x1021 by adding a value successive values.
+ *
+ * Input Parameters:
+ * crc - The running total of the crc 16
+ * value - The value to add
+ *
+ * Returned Value:
+ * The current crc16 with the value processed.
+ *
+ ****************************************************************************/
+
+uint16_t crc16_add(uint16_t crc, uint8_t value);
+
+/****************************************************************************
+ * Name: crc16_signature
+ *
+ * Description:
+ * Caculates a CRC-16-CCITT using the crc16_add
+ * function
+ *
+ * Input Parameters:
+ * initial - The Inital value to uses as the crc's statrting point
+ * length - The number of bytes to add to the crc
+ * bytes - A pointer to any array of length bytes
+ *
+ * Returned Value:
+ * The crc16 of the array of bytes
+ *
+ ****************************************************************************/
+
+uint16_t crc16_signature(uint16_t initial, size_t length,
+ const uint8_t *bytes);
+
+/****************************************************************************
+ * Name: crc64_add
+ *
+ * Description:
+ * Caculates a CRC-64-WE usinsg the polynomial of 0x42F0E1EBA9EA3693
+ * See http://reveng.sourceforge.net/crc-catalogue/17plus.htm#crc.cat-bits.64
+ * Check: 0x62EC59E3F1A4F00A
+ *
+ * Input Parameters:
+ * crc - The running total of the crc 64
+ * value - The value to add
+ *
+ * Returned Value:
+ * The current crc64 with the value processed.
+ *
+ ****************************************************************************/
+
+uint64_t crc64_add(uint64_t crc, uint8_t value);
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c
new file mode 100644
index 000000000..bab054e26
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.c
@@ -0,0 +1,165 @@
+/****************************************************************************
+ *
+ * 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 "board_config.h"
+
+#include <stdint.h>
+#include <stdlib.h>
+
+#include <nuttx/progmem.h>
+
+#include "chip.h"
+#include "stm32.h"
+
+#include "flash.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 the given address
+ *
+ * Input Parameters:
+ * address - The address of the flash to erase
+ *
+ * Returned value:
+ * On success FLASH_OK On Error one of the flash_error_t
+ *
+ ****************************************************************************/
+
+flash_error_t bl_flash_erase(size_t address)
+{
+ /*
+ * 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)
+ {
+
+ status = FLASH_ERROR_SUICIDE;
+ ssize_t appfirstpage = up_progmem_getpage(address);
+
+ if (appfirstpage > bllastpage)
+ {
+
+ size_t pagecnt = up_progmem_npages() - (bllastpage + 1);
+
+ /* Erase the whole application flash region */
+ status = FLASH_OK;
+
+ while (status == FLASH_OK && pagecnt--)
+ {
+
+ ssize_t ps = up_progmem_erasepage(appfirstpage);
+ if (ps <= 0)
+ {
+ status = FLASH_ERASE_ERROR;
+ }
+ }
+ }
+ }
+ return status;
+}
+
+/****************************************************************************
+ * Name: bl_flash_write_word
+ *
+ * Description:
+ * This function erases the flash starting at the given address
+ *
+ * Input Parameters:
+ * flash_address - The address of the flash to write
+ * data - A pointer to a buffer of 4 bytes to be written
+ * to the flash.
+ *
+ * Returned value:
+ * On success FLASH_OK On Error one of the flash_error_t
+ *
+ ****************************************************************************/
+
+flash_error_t bl_flash_write_word(uint32_t flash_address, const uint8_t data[4])
+{
+
+ flash_error_t status = FLASH_ERROR;
+ if (flash_address >= APPLICATION_LOAD_ADDRESS &&
+ (flash_address + sizeof(data)) <= (uint32_t) APPLICATION_LAST_32BIT_ADDRRESS)
+ {
+ if (sizeof(data) ==
+ up_progmem_write((size_t) flash_address, (void *)data, sizeof(data)))
+ {
+ status = FLASH_OK;
+ }
+ }
+ return status;
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h
new file mode 100644
index 000000000..39af66942
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/flash.h
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * 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 the given address
+ *
+ * Input Parameters:
+ * address - The word aligned address of the flash to erase
+ *
+ * Returned value:
+ * On success FLASH_OK On Error one of the flash_error_t
+ *
+ ****************************************************************************/
+
+flash_error_t bl_flash_erase(size_t address);
+
+/****************************************************************************
+ * Name: bl_flash_write_word
+ *
+ * Description:
+ * This function erases the flash starting at the given address
+ *
+ * Input Parameters:
+ * flash_address - The address of the flash to write
+ * data - A pointer to a buffer of 4 bytes to be written
+ * to the flash.
+ *
+ * Returned value:
+ * On success FLASH_OK On Error one of the flash_error_t
+ *
+ ****************************************************************************/
+
+flash_error_t bl_flash_write_word(uint32_t flash_address, const uint8_t * word);
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c
new file mode 100644
index 000000000..e53d3ba9b
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.c
@@ -0,0 +1,469 @@
+/****************************************************************************
+ *
+ * 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 "board_config.h"
+
+#include <systemlib/visibility.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 "bl_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 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
+ *
+ ****************************************************************************/
+
+void 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 && timers[t].count > ms_elapsed) {
+
+ /* So just remove the amount attributed to the tick */
+
+ timers[t].count -= ms_elapsed;
+
+ } else {
+
+ /* 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:
+ case Timeout:
+ timers[t].count = timers[t].reload;
+ 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 = irqsave();
+
+ 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;
+ }
+ }
+
+ irqrestore(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 = irqsave();
+ memset(&timers[id], 0, sizeof(timers[id]));
+ irqrestore(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 = irqsave();
+ timers[id].count = timers[id].reload;
+ timers[id].ctl |= running;
+ irqrestore(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 = irqsave();
+ timers[id].ctl &= ~running;
+ irqrestore(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 = irqsave();
+ int rv = ((timers[id].ctl & running) && timers[id].count == 0);
+ irqrestore(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 = irqsave();
+ timers[id].count = timers[id].reload = ms;
+ timers[id].ctl |= running;
+ irqrestore(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));
+}
+
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h
new file mode 100644
index 000000000..247659836
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/src/timer.h
@@ -0,0 +1,411 @@
+/****************************************************************************
+ *
+ * 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 "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_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;
+}
+
+
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/uavcan/main.c b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/main.c
new file mode 100644
index 000000000..3f890474d
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/main.c
@@ -0,0 +1,1207 @@
+/****************************************************************************
+ *
+ * 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 "board_config.h"
+
+#include <nuttx/arch.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <stdlib.h>
+#include <string.h>
+
+#include "chip.h"
+#include "stm32.h"
+#include "nvic.h"
+
+#include "flash.h"
+#include "timer.h"
+#include "driver.h"
+#include "protocol.h"
+#include "crc.h"
+#include "boot_app_shared.h"
+
+#include "board_config.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+typedef volatile struct bootloader_t {
+ can_speed_t bus_speed;
+ volatile uint8_t node_id;
+ volatile uint8_t status_code;
+ volatile bool app_valid;
+ volatile uint32_t uptime;
+ volatile app_descriptor_t *fw_image_descriptor;
+ volatile uint32_t *fw_image;
+ bool wait_for_getnodeinfo;
+ bool app_bl_request;
+ bool sent_node_info_response;
+
+} bootloader_t;
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+bootloader_t bootloader;
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uptime_process
+ *
+ * Description:
+ * Run as a timer callback off the system tick ISR. This function counts
+ * Seconds of up time.
+ *
+ * Input Parameters:
+ * Not Used.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void uptime_process(bl_timer_id id, void *context)
+{
+ bootloader.uptime++;
+}
+
+
+/****************************************************************************
+ * Name: node_info_process
+ *
+ * Description:
+ * Run as a timer callback off the system tick ISR.
+ * Once we have a node id, this process is started and handles the
+ * GetNodeInfo replies. This function uses the fifoGetNodeInfo and
+ * MBGetNodeInfo of the CAN so it can coexist regardless of
+ * application state and what is it doing.
+ *
+ * Input Parameters:
+ * Not Used.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void node_info_process(bl_timer_id id, void *context)
+{
+
+ uavcan_getnodeinfo_response_t response;
+ uavcan_nodestatus_t node_status;
+ uavcan_frame_id_t frame_id;
+ size_t frame_len;
+ uint32_t rx_message_id;
+ uint8_t frame_payload[8];
+
+ node_status.uptime_sec = bootloader.uptime;
+ node_status.status_code = bootloader.status_code;
+ node_status.vendor_specific_status_code = 0u;
+ uavcan_pack_nodestatus(response.nodestatus, &node_status);
+
+ board_get_hardware_version(&response.hardware_version);
+ response.name_length = board_get_product_name(response.name, sizeof(response.name));
+ memset(&response.software_version,0, sizeof(response.software_version));
+
+ if (bootloader.app_valid) {
+ response.software_version.major =
+ bootloader.fw_image_descriptor->major_version;
+ response.software_version.minor =
+ bootloader.fw_image_descriptor->minor_version;
+ response.software_version.optional_field_mask = 3u;
+ bootloader.fw_image_descriptor->minor_version;
+ response.software_version.vcs_commit =
+ bootloader.fw_image_descriptor->vcs_commit;
+ response.software_version.image_crc =
+ bootloader.fw_image_descriptor->image_crc;
+ }
+
+ rx_message_id = 0u;
+ if (can_rx(&rx_message_id, &frame_len, frame_payload, fifoGetNodeInfo) &&
+ uavcan_parse_message_id(&frame_id, rx_message_id, UAVCAN_GETNODEINFO_DTID) &&
+ frame_payload[0] == bootloader.node_id &&
+ frame_id.last_frame) {
+ uavcan_tx_getnodeinfo_response(bootloader.node_id, &response,
+ frame_id.source_node_id,
+ frame_id.transfer_id);
+
+ bootloader.sent_node_info_response = true;
+ }
+}
+
+/****************************************************************************
+ * Name: node_status_process
+ *
+ * Description:
+ * Run as a timer callback off the system tick ISR.
+ * Once we have a node id, this process is started and sends the
+ * NodeStatus messages. This function uses the MBNodeStatus
+ * of the CAN so it can coexist regardless of application state ant
+ * what is it doing.
+ *
+ * Input Parameters:
+ * Not Used.
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+static void node_status_process(bl_timer_id id, void *context)
+{
+ uavcan_tx_nodestatus(bootloader.node_id, bootloader.uptime, bootloader.status_code);
+}
+
+/****************************************************************************
+ * Name: send_log_message
+ *
+ * Description:
+ * This functions sends uavcan logmessage type data. See uavcan/protocol.h
+ * UAVCAN_LOGMESSAGE_xxx defines.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * level - Log Level of the logmessage DEBUG, INFO, WARN, ERROR
+ * stage - The Stage the application is at. see UAVCAN_LOGMESSAGE_STAGE_x
+ * status - The status of that stage. Start, Fail OK
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+static void send_log_message(uint8_t node_id, uint8_t level, uint8_t stage,
+ uint8_t status)
+{
+ uavcan_logmessage_t message;
+ uavcan_frame_id_t frame_id;
+ uint8_t payload[8];
+ size_t frame_len;
+
+ frame_id.transfer_id = 0;
+ frame_id.last_frame = 1u;
+ frame_id.frame_index = 0;
+ frame_id.source_node_id = node_id;
+ frame_id.transfer_type = MESSAGE_BROADCAST;
+ frame_id.data_type_id = UAVCAN_LOGMESSAGE_DTID;
+
+ message.level = level;
+ message.message[0] = stage;
+ message.message[1] = status;
+ frame_len = uavcan_pack_logmessage(payload, &message);
+ can_tx(uavcan_make_message_id(&frame_id), frame_len, payload, MBAll);
+}
+
+/****************************************************************************
+ * Name: find_descriptor
+ *
+ * Description:
+ * This functions looks through the application image in flash on 8 byte
+ * aligned boundaries to find the Application firmware descriptor.
+ * Once it is found the bootloader.fw_image_descriptor is set to point to
+ * it.
+ *
+ *
+ * Input Parameters:
+ * None
+ *
+ * Returned State:
+ * If found bootloader.fw_image_descriptor points to the app_descriptor_t
+ * of the application firmware image.
+ * If not found bootloader.fw_image_descriptor = NULL
+ *
+ ****************************************************************************/
+
+static void find_descriptor(void)
+{
+ bootloader.fw_image_descriptor = NULL;
+ uint64_t *p = (uint64_t *) APPLICATION_LOAD_ADDRESS;
+ union
+ {
+ uint64_t ull;
+ char text[sizeof(uint64_t)];
+ } sig = {
+ .text = {APP_DESCRIPTOR_SIGNATURE}
+ };
+ do {
+ if (*p == sig.ull) {
+ bootloader.fw_image_descriptor = (volatile app_descriptor_t *) p;
+ }
+ } while(bootloader.fw_image_descriptor == NULL && ++p < APPLICATION_LAST_64BIT_ADDRRESS);
+}
+
+/****************************************************************************
+ * Name: is_app_valid
+ *
+ * Description:
+ * This functions validates the applications image based on the validity of
+ * the Application firmware descriptor's crc and the value of the first word
+ * in the FLASH image.
+ *
+ *
+ * Input Parameters:
+ * first_word - the value read from the first word of the Application's
+ * in FLASH image.
+ *
+ * Returned Value:
+ * true if the application in flash is valid., false otherwise.
+ *
+ ****************************************************************************/
+
+static bool is_app_valid(uint32_t first_word)
+{
+ uint64_t crc;
+ size_t i, length, crc_offset;
+ uint8_t byte;
+
+ find_descriptor();
+
+ if (!bootloader.fw_image_descriptor || first_word == 0xFFFFFFFFu)
+ {
+ return false;
+ }
+
+ length = bootloader.fw_image_descriptor->image_size;
+ crc_offset = (size_t) (&bootloader.fw_image_descriptor->image_crc) -
+ (size_t) bootloader.fw_image;
+
+ crc = CRC64_INITIAL;
+ for (i = 0u; i < 4u; i++)
+ {
+ crc = crc64_add(crc, (uint8_t) (first_word >> (i << 3u)));
+ }
+ for (i = 4u; i < length; i++)
+ {
+ if (crc_offset <= i && i < crc_offset + 8u)
+ {
+ /* Zero out the CRC field while computing the CRC */
+ byte = 0u;
+ }
+ else
+ {
+ byte = ((volatile uint8_t *)bootloader.fw_image)[i];
+ }
+ crc = crc64_add(crc, byte);
+ }
+ crc ^= CRC64_OUTPUT_XOR;
+
+ return crc == bootloader.fw_image_descriptor->image_crc;
+}
+
+/****************************************************************************
+ * Name: get_dynamic_node_id
+ *
+ * Description:
+ * This functions performs the client side of the uavcan specification
+ * for dynamic node allocation.
+ *
+ * Input Parameters:
+ * tboot - The id of the timer to use at the tBoot timeout.
+ * allocated_node_id - A pointer to the location that should receive the
+ * allocated node id.
+ * Returned Value:
+ * CAN_OK - Indicates the a node id has been allocated to this
+ * node.
+ * CAN_BOOT_TIMEOUT - Indicates that tboot expired before an allocation
+ * was done.
+ *
+ ****************************************************************************/
+
+static int get_dynamic_node_id(bl_timer_id tboot, uint32_t *allocated_node_id)
+{
+ uavcan_hardwareversion_t hw_version;
+ uavcan_frame_id_t rx_frame_id;
+
+ uint32_t rx_message_id;
+ uint8_t rx_payload[8];
+ size_t rx_len;
+ uint16_t rx_crc;
+
+ struct {
+ uint8_t node_id;
+ uint8_t transfer_id;
+ uint8_t allocated_node_id;
+ uint8_t frame_index;
+ } server;
+
+ *allocated_node_id = 0;
+
+ uint8_t transfer_id = 0;
+
+ size_t i;
+ size_t offset;
+ uint16_t expected_crc;
+
+ bool unique_id_matched = false;
+
+
+ board_get_hardware_version(&hw_version);
+
+ memset(&server,0 , sizeof(server));
+ rx_crc = 0u;
+
+ /*
+ Rule A: on initialization, the client subscribes to
+ uavcan.protocol.dynamic_node_id.Allocation and starts a Request Timer with
+ interval of Trequestinterval = 1 second
+ */
+
+ bl_timer_id trequest = timer_allocate(modeTimeout|modeStarted, 1000, 0);
+
+ do {
+ /*
+ Rule B. On expiration of Request Timer:
+ 1) Request Timer restarts.
+ 2) The client broadcasts a first-stage Allocation request message,
+ where the fields are assigned following values:
+ node_id - preferred node ID, or zero if the
+ client doesn't have any preference
+ first_part_of_unique_id - true
+ unique_id - first 7 bytes of unique ID
+ */
+ if (timer_expired(trequest)) {
+ uavcan_tx_allocation_message(*allocated_node_id, 16u, hw_version.unique_id,
+ 0u, transfer_id++);
+ timer_start(trequest);
+ }
+
+ if (can_rx(&rx_message_id, &rx_len, rx_payload, fifoAll) &&
+ uavcan_parse_message_id(&rx_frame_id, rx_message_id, UAVCAN_DYNAMICNODEIDALLOCATION_DTID)) {
+
+ /*
+ Rule C. On any Allocation message, even if other rules also match:
+ 1) Request Timer restarts.
+ */
+
+ timer_start(trequest);
+
+ /*
+ Skip this message if it's anonymous (from another client), or if it's
+ from a different server to the one we're listening to at the moment
+ */
+ if (!rx_frame_id.source_node_id || (server.node_id &&
+ rx_frame_id.source_node_id != server.node_id)) {
+ continue;
+ } else if (!server.node_id ||
+ rx_frame_id.transfer_id != server.transfer_id ||
+ rx_frame_id.frame_index == 0) {
+ /* First (only?) frame of the transfer */
+ if (rx_frame_id.last_frame) {
+ offset = 1u;
+ } else {
+ rx_crc = (uint16_t)(rx_payload[0] | (rx_payload[1] << 8u));
+ server.allocated_node_id = rx_payload[2];
+ offset = 3u;
+ }
+ server.node_id = rx_frame_id.source_node_id;
+ server.transfer_id = rx_frame_id.transfer_id;
+ unique_id_matched = 0u;
+ server.frame_index = 1u;
+ } else if (rx_frame_id.frame_index != server.frame_index) {
+ /* Abort if the frame index is wrong */
+ server.node_id = 0u;
+ continue;
+ } else {
+ offset = 0u;
+ server.frame_index++;
+ }
+
+ /*
+ Rule D. On an Allocation message WHERE (source node ID is
+ non-anonymous) AND (client's unique ID starts with the bytes available
+ in the field unique_id) AND (unique_id is less than 16 bytes long):
+ 1) The client broadcasts a second-stage Allocation request message,
+ where the fields are assigned following values:
+ node_id - same value as in the first-stage
+ first_part_of_unique_id - false
+ unique_id - at most 7 bytes of local unique ID
+ with an offset equal to number of
+ bytes in the received unique ID
+
+ Rule E. On an Allocation message WHERE (source node ID is
+ non-anonymous) AND (unique_id fully matches client's unique ID) AND
+ (node_id in the received message is not zero):
+ 1) Request Timer stops.
+ 2) The client initializes its node_id with the received value.
+ 3) The client terminates subscription to Allocation messages.
+ 4) Exit.
+ */
+
+ /* Count the number of unique ID bytes matched */
+ for (i = offset; i < rx_len && unique_id_matched < 16u &&
+ hw_version.unique_id[unique_id_matched] == rx_payload[i];
+ unique_id_matched++, i++);
+
+ if (i < rx_len) {
+ /* Abort if we didn't match the whole unique ID */
+ server.node_id = 0u;
+ } else if (rx_frame_id.last_frame && unique_id_matched < 16u) {
+ /* Case D */
+ uavcan_tx_allocation_message(*allocated_node_id, 16u, hw_version.unique_id,
+ unique_id_matched, transfer_id++);
+ } else if (rx_frame_id.last_frame) {
+ /* Validate CRC */
+ expected_crc = UAVCAN_ALLOCATION_CRC;
+ expected_crc = crc16_add(expected_crc, server.allocated_node_id);
+ expected_crc = crc16_signature(expected_crc, 16u,
+ hw_version.unique_id);
+
+ /* Case E */
+ if (rx_crc == expected_crc) {
+ *allocated_node_id = server.allocated_node_id >> 1u;
+ break;
+ }
+ }
+ }
+ } while (!timer_expired(tboot));
+
+ timer_free(trequest);
+ return *allocated_node_id == 0 ? CAN_BOOT_TIMEOUT : CAN_OK;
+}
+
+/****************************************************************************
+ * Name: wait_for_beginfirmwareupdate
+ *
+ * Description:
+ * This functions performs the client side of the uavcan specification
+ * for begin firmware update.
+ *
+ * Input Parameters:
+ * tboot - The id of the timer to use at the tBoot timeout.
+ * fw_path - A pointer to the location that should receive the
+ * path of the firmware file to read.
+ * fw_path_length - A pointer to return the path length in.
+ * fw_source_node_id - A pointer to return the node id of the node to
+ * read the file from.
+ * Returned Value:
+ * CAN_OK - Indicates the a beginfirmwareupdate was received and
+ * processed successful.
+ * CAN_BOOT_TIMEOUT - Indicates that tboot expired before a
+ * beginfirmwareupdate was received.
+ *
+ ****************************************************************************/
+
+static int wait_for_beginfirmwareupdate(bl_timer_id tboot, uint8_t * fw_path,
+ uint8_t * fw_path_length,
+ uint8_t * fw_source_node_id)
+{
+ uavcan_beginfirmwareupdate_request_t request;
+ uavcan_frame_id_t frame_id;
+ size_t i;
+ uint8_t frame_payload[8];
+ can_error_t status;
+
+ status = CAN_ERROR;
+ fw_path[0] = 0;
+ *fw_source_node_id = 0;
+
+ while (status != CAN_OK)
+ {
+ if (timer_expired(tboot)) {
+ return CAN_BOOT_TIMEOUT;
+ }
+ status = uavcan_rx_beginfirmwareupdate_request(bootloader.node_id,
+ &request, &frame_id);
+ }
+
+ if (status == CAN_OK)
+ {
+ /* UAVCANBootloader_v0.3 #22.2: Resp580.BeginFirmwareUpdate.uavcan */
+
+ /* Send an ERROR_OK response */
+ frame_payload[0] = frame_id.source_node_id;
+ frame_payload[1] = 0u;
+
+ frame_id.last_frame = 1u;
+ frame_id.frame_index = 0u;
+ frame_id.source_node_id = bootloader.node_id;
+ frame_id.transfer_type = SERVICE_RESPONSE;
+
+ can_tx(uavcan_make_message_id(&frame_id), 2u, frame_payload, MBAll);
+
+ /* UAVCANBootloader_v0.3 #22.3: fwPath = image_file_remote_path */
+ for (i = 0u; i < request.path_length; i++)
+ {
+ fw_path[i] = request.path[i];
+ }
+ *fw_path_length = request.path_length;
+ /* UAVCANBootloader_v0.3 #22.4: fwSourceNodeID = source_node_id */
+ *fw_source_node_id = request.source_node_id;
+ }
+ return status;
+}
+
+/****************************************************************************
+ * Name: file_getinfo
+ *
+ * Description:
+ * This functions performs the client side of the uavcan specification
+ * for getinfo (for a file).
+ *
+ * Input Parameters:
+ * fw_image_size - A pointer to the location that should receive the
+ * firmware image size.
+ * fw_image_crc - A pointer to the location that should receive the
+ * firmware image crc.
+ * fw_path - A pointer to the path of the firmware file that's
+ * info is being requested.
+ * fw_path_length - The path length of the firmware file that's
+ * info is being requested.
+ * fw_source_node_id - The node id of the node to get the info from.
+ *
+ * Returned Value:
+ * None.
+ *
+ ****************************************************************************/
+
+static void file_getinfo(size_t * fw_image_size, uint64_t * fw_image_crc,
+ const uint8_t * fw_path, uint8_t fw_path_length,
+ uint8_t fw_source_node_id)
+{
+ uavcan_getinfo_request_t request;
+ uavcan_getinfo_response_t response;
+ uint8_t transfer_id, retries, i;
+ can_error_t status;
+
+ for (i = 0; i < fw_path_length; i++)
+ {
+ request.path[i] = fw_path[i];
+ }
+ request.path_length = fw_path_length;
+
+ /* UAVCANBootloader_v0.3 #25: SetRetryAndTimeout(3,1000MS) */
+ retries = UAVCAN_SERVICE_RETRIES;
+ transfer_id = 0;
+
+ *fw_image_size = 0;
+ *fw_image_crc = 0;
+
+ while (retries)
+ {
+ /* UAVCANBootloader_v0.3 #26: 585.GetInfo.uavcan(path) */
+ uavcan_tx_getinfo_request(bootloader.node_id, &request,
+ fw_source_node_id, transfer_id);
+
+ /* UAVCANBootloader_v0.3 #28:
+ * 585.GetInfo.uavcan(fw_path,fw_crc,fw_size...), */
+ status =
+ uavcan_rx_getinfo_response(bootloader.node_id, &response,
+ fw_source_node_id, transfer_id,
+ UAVCAN_SERVICE_TIMEOUT_MS);
+
+ transfer_id++;
+
+ /* UAVCANBootloader_v0.3 #27: validateFileInfo(file_info, &errorcode) */
+ if (status == CAN_OK && response.error == UAVCAN_FILE_ERROR_OK &&
+ (response.entry_type & UAVCAN_GETINFO_ENTRY_TYPE_FLAG_FILE) &&
+ (response.entry_type & UAVCAN_GETINFO_ENTRY_TYPE_FLAG_READABLE) &&
+ response.size > 0u && response.size < OPT_APPLICATION_IMAGE_LENGTH)
+ {
+ /* UAVCANBootloader_v0.3 #28.4: save(file_info) */
+ *fw_image_size = response.size;
+ *fw_image_crc = response.crc64;
+ break;
+ }
+ else
+ {
+ retries--;
+ }
+ }
+}
+
+/****************************************************************************
+ * Name: file_read_and_program
+ *
+ * Description:
+ * This functions performs the client side of the uavcan specification
+ * for file read and programs the flash.
+ *
+ * Input Parameters:
+ * fw_source_node_id - The node id of the node to read the file from.
+ * fw_path_length - The path length of the firmware file that is
+ * being read.
+ * fw_path - A pointer to the path of the firmware file that
+ * is being read.
+ * fw_image_size - The size the fw image file should be.
+ * fw_word0 - A pointer to the loactions to store the first
+ * ford of the fw image.
+ * Returned Value:
+ * FLASH_OK - Indicates that the correct amount of data has
+ * ben programed to the FLASH.
+ * processed successful.
+ * FLASH_ERROR - Indicates that an error occurred
+ *
+ ****************************************************************************/
+
+static flash_error_t file_read_and_program(uint8_t fw_source_node_id,
+ uint8_t fw_path_length,
+ const uint8_t * fw_path,
+ size_t fw_image_size,
+ uint32_t * fw_word0)
+{
+ uavcan_read_request_t request;
+ uavcan_read_response_t response;
+ size_t bytes_written, i, write_length;
+ can_error_t can_status;
+ flash_error_t flash_status;
+ uint32_t next_read_deadline;
+ uint8_t transfer_id;
+ uint8_t retries;
+ uint8_t write_remainder[4];
+ uint8_t write_remainder_length;
+ uint8_t *data;
+
+ /* Set up the read request */
+ for (i = 0; i < fw_path_length; i++)
+ {
+ request.path[i] = fw_path[i];
+ }
+ request.path_length = fw_path_length;
+ request.offset = 0u;
+
+ bytes_written = 0u;
+ write_remainder_length = 0u;
+ transfer_id = 0u;
+ next_read_deadline = 0u;
+
+ do
+ {
+ /*
+ * Rate limiting on read requests: - 2/sec on a 125 Kbaud bus - 4/sec on
+ * a 250 Kbaud bus - 8/sec on a 500 Kbaud bus - 16/sec on a 1 Mbaud bus */
+ while (bootloader.uptime < next_read_deadline);
+ next_read_deadline = bootloader.uptime + 6u;
+
+ /* UAVCANBootloader_v0.3 #28.11: SetRetryAndTimeout(3,1000MS) */
+ retries = UAVCAN_SERVICE_RETRIES;
+ can_status = CAN_ERROR;
+ while (retries && can_status != CAN_OK)
+ {
+ /* UAVCANBootloader_v0.3 #28.12: 588.Read.uavcan(0, path) */
+ /* UAVCANBootloader_v0.3 #33: 588.Read.uavcan(N,path) */
+ request.offset = bytes_written + write_remainder_length;
+ uavcan_tx_read_request(bootloader.node_id, &request,
+ fw_source_node_id, transfer_id);
+
+ /* UAVCANBootloader_v0.3 #28.12.1: 588.Read.uavcan(0,path,data) */
+ /* UAVCANBootloader_v0.3 #33.1: 583.Read.uavcan(0,path,data) */
+ can_status = uavcan_rx_read_response(bootloader.node_id,
+ &response, fw_source_node_id,
+ transfer_id,
+ UAVCAN_SERVICE_TIMEOUT_MS);
+
+ transfer_id++;
+
+ /* UAVCANBootloader_v0.3 #34: ValidateReadResp(resp) */
+ if (can_status != CAN_OK || response.error != UAVCAN_FILE_ERROR_OK)
+ {
+ can_status = CAN_ERROR;
+
+ /* UAVCANBootloader_v0.3 #35: [(retries != 0 && timeout) ||
+ * !ValidReadReadResponse]:INDICATE_FW_UPDATE_INVALID_RESPONSE */
+ board_indicate(fw_update_invalid_response);
+
+ /* UAVCANBootloader_v0.3 #36: [(retries != 0 && timeout) ||
+ * !ValidReadReadResponse]:1023.LogMessage.uavcan */
+ send_log_message(bootloader.node_id,
+ UAVCAN_LOGMESSAGE_LEVEL_ERROR,
+ UAVCAN_LOGMESSAGE_STAGE_PROGRAM,
+ UAVCAN_LOGMESSAGE_RESULT_FAIL);
+ retries--;
+ }
+ }
+
+ if (can_status != CAN_OK)
+ {
+ /* UAVCANBootloader_v0.3 #37: [(retries == 0 &&
+ * timeout]:INDICATE_FW_UPDATE_TIMEOUT */
+ board_indicate(fw_update_timeout);
+ break;
+ }
+
+ data = response.data;
+ write_length = response.data_length;
+
+ /*
+ * If this is the last read (zero length) and there are bytes left to
+ * write, pad the firmware image out with zeros to ensure a full-word
+ * write. */
+ if (write_length == 0u && write_remainder_length > 0u)
+ {
+ write_length = 4u - write_remainder_length;
+ data[0] = data[1] = data[2] = 0u;
+ }
+
+ /*
+ * If the length of a previous read was not a multiple of 4, we'll have a
+ * few bytes left over which need to be combined with the next write as
+ * all writes must be word-aligned and a whole number of words long. */
+ flash_status = FLASH_OK;
+ while (write_length && flash_status == FLASH_OK)
+ {
+ write_remainder[write_remainder_length++] = *(data++);
+ write_length--;
+
+ if (write_remainder_length == 4u)
+ {
+ if (bytes_written == 0u)
+ {
+ /* UAVCANBootloader_v0.3 #30: SaveWord0 */
+ ((uint8_t *) fw_word0)[0] = write_remainder[0];
+ ((uint8_t *) fw_word0)[1] = write_remainder[1];
+ ((uint8_t *) fw_word0)[2] = write_remainder[2];
+ ((uint8_t *) fw_word0)[3] = write_remainder[3];
+ }
+ else
+ {
+ flash_status =
+ bl_flash_write_word((uint32_t)
+ (&bootloader.fw_image[bytes_written >> 2u]),
+ write_remainder);
+ }
+
+ bytes_written += 4u;
+ write_remainder_length = 0u;
+ }
+ }
+ }
+ while (bytes_written <= fw_image_size && response.data_length != 0u &&
+ flash_status == FLASH_OK);
+
+ /*
+ * Return success if the last read succeeded, the last write succeeded, the
+ * correct number of bytes were written, and the length of the last response
+ * was zero. */
+ if (can_status == CAN_OK && flash_status == FLASH_OK &&
+ bytes_written == fw_image_size && response.data_length == 0u)
+ {
+ return FLASH_OK;
+ }
+ else
+ {
+ return FLASH_ERROR;
+ }
+}
+
+/****************************************************************************
+ * Name: do_jump
+ *
+ * Description:
+ * This functions begins the execution of the application firmware.
+ *
+ * Input Parameters:
+ * stacktop - The value that should be loaded into the stack pointer.
+ * entrypoint - The address to jump to.
+ *
+ * Returned Value:
+ * Does not return.
+ *
+ ****************************************************************************/
+
+static void do_jump(uint32_t stacktop, uint32_t entrypoint)
+{
+ asm volatile ("msr msp, %0 \n"
+ "bx %1 \n"::"r" (stacktop), "r"(entrypoint):);
+ // just to keep noreturn happy
+ for (;;);
+}
+
+/****************************************************************************
+ * Name: application_run
+ *
+ * Description:
+ * This functions will test the application image is valid by
+ * checking the value of the first word for != 0xffffffff and the
+ * second word for an address that lies inside od the application
+ * fw image in flash.
+ *
+ * Input Parameters:
+ * fw_image_size - The size the fw image is.
+ *
+ * Returned Value:
+ * If the Image is valid this code does not return, but runs the application
+ * via do_jump.
+ * If the image is invalid the function returns.
+ *
+ ****************************************************************************/
+
+static void application_run(size_t fw_image_size)
+{
+ /*
+ * We refuse to program the first word of the app until the upload is marked
+ * complete by the host. So if it's not 0xffffffff, we should try booting it.
+
+ * The second word of the app is the entrypoint; it must point within the
+ * flash area (or we have a bad flash).
+ */
+ if (bootloader.fw_image[0] != 0xffffffff
+ && bootloader.fw_image[1] > APPLICATION_LOAD_ADDRESS
+ && bootloader.fw_image[1] < (APPLICATION_LOAD_ADDRESS + fw_image_size))
+ {
+
+ (void)irqsave();
+
+ stm32_boarddeinitialize();
+
+ /* kill the systick interrupt */
+ up_disable_irq(STM32_IRQ_SYSTICK);
+ putreg32((NVIC_SYSTICK_CTRL_CLKSOURCE | NVIC_SYSTICK_CTRL_TICKINT),
+ NVIC_SYSTICK_CTRL);
+
+ /* and set a specific LED pattern */
+ board_indicate(jump_to_app);
+
+ /* the interface */
+
+ /* switch exception handlers to the application */
+ __asm volatile ("dsb");
+ __asm volatile ("isb");
+ putreg32(APPLICATION_LOAD_ADDRESS, NVIC_VECTAB);
+ __asm volatile ("dsb");
+ /* extract the stack and entrypoint from the app vector table and go */
+ do_jump(bootloader.fw_image[0], bootloader.fw_image[1]);
+ }
+}
+
+/****************************************************************************
+ * Name: autobaud_and_get_dynamic_node_id
+ *
+ * Description:
+ * This helper functions wraps the auto baud and node id allocation
+ *
+ * Input Parameters:
+ * tboot - The id of the timer to use at the tBoot timeout.
+ * speed - A pointer to the location to receive the speed detected by
+ * the auto baud function.
+ * node_id - A pointer to the location to receive the allocated node_id
+ * from the dynamic node allocation.
+ *
+ * Returned Value:
+ * CAN_OK - on Success or a CAN_BOOT_TIMEOUT
+ *
+ ****************************************************************************/
+static int autobaud_and_get_dynamic_node_id(bl_timer_id tboot,
+ can_speed_t *speed,
+ uint32_t *node_id)
+{
+
+ board_indicate(autobaud_start);
+
+ int rv = can_autobaud(speed, tboot);
+
+ if (rv != CAN_BOOT_TIMEOUT) {
+ board_indicate(autobaud_end);
+ board_indicate(allocation_start);
+ rv = get_dynamic_node_id(tboot, node_id);
+ if (rv != CAN_BOOT_TIMEOUT) {
+ board_indicate(allocation_end);
+ }
+ }
+ return rv;
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: main
+ *
+ * Description:
+ * Called by the os_start code
+ *
+ * Input Parameters:
+ * Not used.
+ *
+ * Returned Value:
+ * Does not return.
+ *
+ ****************************************************************************/
+
+__EXPORT int main(int argc, char *argv[])
+{
+
+ uint64_t fw_image_crc;
+ size_t fw_image_size = 0;
+ uint32_t fw_word0;
+ uint8_t fw_path[200];
+ uint8_t fw_path_length;
+ uint8_t fw_source_node_id;
+ uint8_t error_log_stage;
+ flash_error_t status;
+ bootloader_app_shared_t common;
+
+#ifdef OPT_ENABLE_WD
+ /* ... */
+#endif
+
+ memset((void *)&bootloader, 0, sizeof(bootloader));
+
+ bootloader.status_code = UAVCAN_NODESTATUS_STATUS_INITIALIZING;
+
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_INIT;
+
+ bootloader.fw_image = (volatile uint32_t *)(APPLICATION_LOAD_ADDRESS);
+
+#if defined(OPT_WAIT_FOR_GETNODEINFO)
+ bootloader.wait_for_getnodeinfo = 1;
+#endif
+
+#if defined(OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO)
+ bootloader.wait_for_getnodeinfo &= stm32_gpioread(GPIO_GETNODEINFO_JUMPER) ^ OPT_WAIT_FOR_GETNODEINFO_JUMPER_GPIO_INVERT;
+#endif
+
+
+ bootloader.app_valid = is_app_valid(bootloader.fw_image[0]);
+
+ board_indicate(reset);
+
+
+ bootloader.app_bl_request = (OK == bootloader_app_shared_read(&common, App)) &&
+ common.bus_speed && common.node_id;
+ bootloader_app_shared_invalidate();
+
+ bl_timer_cb_t p = null_cb;
+ p.cb = uptime_process;
+ timer_allocate(modeRepeating|modeStarted, 1000, &p);
+
+ p.cb = node_info_process;
+ bl_timer_id tinfo = timer_allocate(modeRepeating, OPT_NODE_INFO_RATE_MS, &p);
+
+ p.cb = node_status_process;
+ bl_timer_id tstatus = timer_allocate(modeRepeating, OPT_NODE_STATUS_RATE_MS, &p);
+
+
+
+ bl_timer_id tboot = timer_allocate(modeRepeating, OPT_TBOOT_MS , 0);
+
+ if (!bootloader.wait_for_getnodeinfo && !bootloader.app_bl_request && bootloader.app_valid) {
+ timer_start(tboot);
+ }
+
+ if (bootloader.app_bl_request) {
+
+ bootloader.bus_speed = common.bus_speed;
+ bootloader.node_id = (uint8_t) common.node_id;
+ can_init(can_freq2speed(common.bus_speed), CAN_Mode_Normal);
+
+ } else {
+
+ can_speed_t speed;
+
+ if (CAN_OK != autobaud_and_get_dynamic_node_id(tboot, &speed, &common.node_id)) {
+ goto boot;
+ }
+
+ /* reset uptime */
+ bootloader.uptime = 0;
+ common.bus_speed = can_speed2freq(speed);
+ bootloader.node_id = (uint8_t) common.node_id;
+
+ }
+ // Start Processes that requier Node Id
+ timer_start(tinfo);
+ timer_start(tstatus);
+
+ while (!bootloader.sent_node_info_response) {
+ if (timer_expired(tboot))
+ {
+ goto boot;
+ }
+ }
+
+ if (bootloader.app_valid &&
+ (bootloader.wait_for_getnodeinfo ||
+ bootloader.app_bl_request)) {
+
+ timer_start(tboot);
+ }
+
+ do
+ {
+ if (CAN_BOOT_TIMEOUT == wait_for_beginfirmwareupdate(tboot,fw_path,
+ &fw_path_length,
+ &fw_source_node_id))
+ {
+ goto boot;
+ }
+ }
+ while (!fw_source_node_id);
+
+ timer_stop(tboot);
+ board_indicate(fw_update_start);
+
+ file_getinfo(&fw_image_size, &fw_image_crc, fw_path, fw_path_length,
+ fw_source_node_id);
+
+ //todo:Check this
+ if (fw_image_size < sizeof(app_descriptor_t) || !fw_image_crc)
+ {
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_GET_INFO;
+ goto failure;
+ }
+
+ /* UAVCANBootloader_v0.3 #28.6: 1023.LogMessage.uavcan("Erase") */
+ send_log_message(bootloader.node_id,
+ UAVCAN_LOGMESSAGE_LEVEL_INFO,
+ UAVCAN_LOGMESSAGE_STAGE_ERASE,
+ UAVCAN_LOGMESSAGE_RESULT_START);
+
+
+ /* Need to signal that the app is no longer valid if Node Info Request are done */
+
+ bootloader.app_valid = false;
+
+ status = bl_flash_erase(APPLICATION_LOAD_ADDRESS);
+ if (status != FLASH_OK)
+ {
+ /* UAVCANBootloader_v0.3 #28.8: [Erase
+ * Failed]:INDICATE_FW_UPDATE_ERASE_FAIL */
+ board_indicate(fw_update_erase_fail);
+
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_ERASE;
+ goto failure;
+ }
+
+ status = file_read_and_program(fw_source_node_id, fw_path_length, fw_path,
+ fw_image_size, &fw_word0);
+ if (status != FLASH_OK)
+ {
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_PROGRAM;
+ goto failure;
+ }
+
+ /* UAVCANBootloader_v0.3 #41: CalulateCRC(file_info) */
+ if (!is_app_valid(fw_word0))
+ {
+ bootloader.app_valid = 0u;
+
+ /* UAVCANBootloader_v0.3 #43: [crc Fail]:INDICATE_FW_UPDATE_INVALID_CRC */
+ board_indicate(fw_update_invalid_crc);
+
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_VALIDATE;
+ goto failure;
+ }
+
+ /* UAVCANBootloader_v0.3 #46: [crc == fw_crc]:write word0 */
+ status = bl_flash_write_word((uint32_t) bootloader.fw_image, (uint8_t *) & fw_word0);
+ if (status != FLASH_OK)
+ {
+ /* Not specifically listed in UAVCANBootloader_v0.3:
+ * 1023.LogMessage.uavcan */
+ error_log_stage = UAVCAN_LOGMESSAGE_STAGE_FINALIZE;
+ goto failure;
+ }
+
+ /* UAVCANBootloader_v0.3 #47: ValidateBootLoaderAppCommon() */
+ bootloader_app_shared_write(&common, BootLoader);
+
+ /* Send a completion log message */
+ send_log_message(bootloader.node_id,
+ UAVCAN_LOGMESSAGE_LEVEL_INFO,
+ UAVCAN_LOGMESSAGE_STAGE_FINALIZE,
+ UAVCAN_LOGMESSAGE_RESULT_OK);
+
+ /* TODO UAVCANBootloader_v0.3 #48: KickTheDog() */
+
+boot:
+ /* UAVCANBootloader_v0.3 #50: jump_to_app */
+ application_run(fw_image_size);
+
+ /* We will fall thru if the Iamage is bad */
+
+failure:
+ /* UAVCANBootloader_v0.3 #28.2:
+ * [!validateFileInfo(file_info)]:1023.LogMessage.uavcan (errorcode) */
+ /* UAVCANBootloader_v0.3 #28.9: [Erase Fail]:1023.LogMessage.uavcan */
+ /* UAVCANBootloader_v0.3 #31: [Program Fail]::1023.LogMessage.uavcan */
+ /* UAVCANBootloader_v0.3 #38: [(retries == 0 &&
+ * timeout)]:1023.LogMessage.uavcan */
+ /* UAVCANBootloader_v0.3 #42: [crc Faill]:1023.LogMessage.uavcan */
+ send_log_message(bootloader.node_id,
+ UAVCAN_LOGMESSAGE_LEVEL_ERROR,
+ error_log_stage, UAVCAN_LOGMESSAGE_RESULT_FAIL);
+
+ /* UAVCANBootloader_v0.3 #28.3:
+ * [!validateFileInfo(file_info)]:550.NodeStatus.uavcan(uptime=t,
+ * STATUS_CRITICAL) */
+ /* UAVCANBootloader_v0.3 #28.10: [Erase
+ * Fail]:550.NodeStatus.uavcan(uptime=t,STATUS_CRITICAL) */
+ /* UAVCANBootloader_v0.3 #32: [Program Fail]:550.NodeStatus.uavcan(uptime=t,
+ * STATUS_CRITICAL) */
+ /* UAVCANBootloader_v0.3 #39: [(retries == 0 &&
+ * timeout)]:550.NodeStatus.uavcan(uptime=t, STATUS_CRITICAL) */
+ /* UAVCANBootloader_v0.3 #44: [crc Fail]:550.NodeStatus.uavcan(uptime=t,
+ * STATUS_CRITICAL) */
+ bootloader.status_code = UAVCAN_NODESTATUS_STATUS_CRITICAL;
+
+ /* UAVCANBootloader_v0.3 #28.1:
+ * [Retries==0]:InvalidateBootLoaderAppCommon(),RestartWithDelay(20,000ms) */
+ /* UAVCANBootloader_v0.3 #40: [Retries==0]:InvalidateBootLoaderAppCommon(),
+ * RestartWithDelay(20,000ms) */
+ /* UAVCANBootloader_v0.3 #45: [crc
+ * Fail]:InvalidateBootLoaderAppCommon(),RestartWithDelay(20,000ms) */
+
+ bl_timer_id tmr = timer_allocate(modeTimeout|modeStarted , OPT_RESTART_TIMEOUT_MS, 0);
+ while(!timer_expired(tmr))
+ {
+ ;
+ }
+ timer_free(tmr);
+ up_systemreset();
+}
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.c b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.c
new file mode 100644
index 000000000..bb8e08d73
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.c
@@ -0,0 +1,723 @@
+/****************************************************************************
+ *
+ * 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 "board_config.h"
+
+#include <stdint.h>
+#include <stdlib.h>
+
+#include "chip.h"
+#include "stm32.h"
+
+#include "timer.h"
+#include "protocol.h"
+#include "driver.h"
+#include "crc.h"
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define CAN_REQUEST_TIMEOUT 1000
+
+/****************************************************************************
+ * Private Types
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Function Prototypes
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+/****************************************************************************
+ * Name: uavcan_tx_multiframe_
+ ****************************************************************************/
+static void uavcan_tx_multiframe_(uavcan_frame_id_t *frame_id,
+ uint8_t dest_node_id,
+ size_t message_length,
+ const uint8_t *message,
+ uint16_t initial_crc,
+ uint8_t mailbox)
+{
+ uint32_t i, m;
+ uint16_t frame_crc;
+ uint8_t payload[8];
+
+ /* Calculate the message CRC */
+ frame_crc = crc16_signature(initial_crc, message_length, message);
+
+ /* Ensure message ID has the frame details zeroed */
+ frame_id->last_frame = 0u;
+ frame_id->frame_index = 0u;
+
+ /*
+ Send the message -- only prepend CRC if the message will not fit within a
+ single frame
+ */
+ payload[0] = dest_node_id;
+ m = 1u;
+ if (message_length > 7u) {
+ payload[m++] = (uint8_t)frame_crc;
+ payload[m++] = (uint8_t)(frame_crc >> 8u);
+ }
+ for (i = 0u; i < message_length; i++) {
+ payload[m++] = message[i];
+ if (i == message_length - 1u) {
+ break;
+ } else if (m == 8u) {
+ can_tx(uavcan_make_message_id(frame_id), 8u, payload, mailbox);
+ frame_id->frame_index++;
+ payload[0] = dest_node_id;
+ m = 1u;
+ }
+ }
+
+ /* Send the last (only?) frame */
+ frame_id->last_frame = 1u;
+ can_tx(uavcan_make_message_id(frame_id), m, payload, mailbox);
+}
+
+/****************************************************************************
+ * Name: uavcan_rx_multiframe_
+ ****************************************************************************/
+
+static can_error_t uavcan_rx_multiframe_(uint8_t node_id,
+ uavcan_frame_id_t *frame_id,
+ size_t *message_length,
+ uint8_t *message,
+ uint16_t initial_crc,
+ uint32_t timeout_ms)
+{
+ uavcan_frame_id_t rx_id;
+ size_t rx_length;
+ size_t m;
+ size_t i;
+ uint32_t rx_message_id;
+ uint16_t calculated_crc;
+ uint16_t message_crc;
+ uint8_t payload[8];
+ uint8_t got_frame;
+ uint8_t num_frames;
+
+ bl_timer_id timer = timer_allocate(modeTimeout|modeStarted, timeout_ms, 0);
+
+ num_frames = 0u;
+ rx_id.last_frame = 0u;
+ message_crc = 0u;
+ i = 0;
+
+ do {
+ rx_message_id = 0u;
+ rx_length = 0u;
+ got_frame = can_rx(&rx_message_id, &rx_length, payload, MBAll);
+ if (!got_frame) {
+ continue;
+ }
+
+ uavcan_parse_message_id(&rx_id, rx_message_id, frame_id->transfer_type);
+
+ /*
+ Skip this frame if the source node ID is wrong, or if the data type or
+ transfer type do not match what we're expecting
+ */
+ if ((frame_id->source_node_id != 0xFFu &&
+ rx_id.source_node_id != frame_id->source_node_id) ||
+ rx_id.transfer_type != frame_id->transfer_type ||
+ rx_id.data_type_id != frame_id->data_type_id ||
+ payload[0] != node_id) {
+ continue;
+ }
+
+ /*
+ Get the CRC if this is the first frame of a multi-frame transfer.
+
+ Also increase the timeout to UAVCAN_SERVICE_TIMEOUT_TICKS.
+ */
+ if (rx_id.frame_index == 0u) {
+ num_frames = 0u;
+ frame_id->transfer_id = rx_id.transfer_id;
+ if (frame_id->source_node_id == 0xFFu) {
+ frame_id->source_node_id = rx_id.source_node_id;
+ }
+ }
+
+ /* Skip if the transfer ID is wrong */
+ if ((frame_id->transfer_id ^ rx_id.transfer_id) & 0x7u) {
+ continue;
+ }
+
+ /*
+ Get the CRC and increase the service timeout if this is the first
+ frame
+ */
+ if (num_frames == 0u && !rx_id.last_frame) {
+ timer_restart(timer, UAVCAN_SERVICE_TIMEOUT_MS);
+ message_crc = (uint16_t)(payload[1] | (payload[2] << 8u));
+ m = 3u;
+ } else {
+ m = 1u;
+ }
+
+ /* Copy message bytes to the response */
+ for (; m < rx_length && i < *message_length; m++, i++) {
+ message[i] = payload[m];
+ }
+ num_frames++;
+
+ if (rx_id.last_frame) {
+ break;
+ }
+ } while (!timer_expired(timer));
+ timer_free(timer);
+ if (!rx_id.last_frame) {
+ return CAN_ERROR;
+ } else {
+ /* Validate CRC */
+ calculated_crc = crc16_signature(initial_crc, i, message);
+
+ *message_length = i;
+
+ if (num_frames == 1u || message_crc == calculated_crc) {
+ return CAN_OK;
+ } else {
+ return CAN_ERROR;
+ }
+ }
+}
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: uavcan_pack_nodestatus
+ *
+ * Description:
+ * This function formats the data of a uavcan_nodestatus_t structure into
+ * an array of bytes.
+ *
+ * Input Parameters:
+ * data - The array of bytes to populate.
+ * message - The uavcan_nodestatus_t to pack into the data
+ *
+ * Returned value:
+ * Number of bytes written.
+ *
+ ****************************************************************************/
+
+size_t uavcan_pack_nodestatus(uint8_t *data,
+ const uavcan_nodestatus_t *message)
+{
+ /* No need to clear the top 4 bits of uptime_sec */
+ data[0] = ((uint8_t*)&message->uptime_sec)[0];
+ data[1] = ((uint8_t*)&message->uptime_sec)[1];
+ data[2] = ((uint8_t*)&message->uptime_sec)[2];
+ data[3] = ((uint8_t*)&message->uptime_sec)[3] | message->status_code;
+ data[4] = ((uint8_t*)&message->vendor_specific_status_code)[0];
+ data[5] = ((uint8_t*)&message->vendor_specific_status_code)[1];
+ return 6u;
+}
+
+
+/****************************************************************************
+ * Name: uavcan_pack_logmessage
+ *
+ * Description:
+ * This function formats the data of a uavcan_logmessage_t structure into
+ * an array of bytes.
+ *
+ * Input Parameters:
+ * data - The array of bytes to populate.
+ * message - The uavcan_logmessage_t to pack into the data
+ *
+ * Returned value:
+ * Number of bytes written.
+ *
+ ****************************************************************************/
+
+size_t uavcan_pack_logmessage(uint8_t *data,
+ const uavcan_logmessage_t *message)
+{
+ data[0] = (uint8_t)(((message->level & 0x7u) << 5u) | 4u);
+ data[1] = UAVCAN_LOGMESSAGE_SOURCE_0;
+ data[2] = UAVCAN_LOGMESSAGE_SOURCE_1;
+ data[3] = UAVCAN_LOGMESSAGE_SOURCE_2;
+ data[4] = UAVCAN_LOGMESSAGE_SOURCE_3;
+ data[5] = message->message[0];
+ data[6] = message->message[1];
+ return 7u;
+}
+
+
+/****************************************************************************
+ * Name: uavcan_make_message_id
+ *
+ * Description:
+ * This function formats the data of a uavcan_frame_id_t structure into
+ * a unit32.
+ *
+ * Input Parameters:
+ * frame_id - The uavcan_frame_id_t to pack.
+ *
+ * Returned value:
+ * A unit32 that is the message id formed from packing the
+ * uavcan_frame_id_t.
+ *
+ ****************************************************************************/
+
+uint32_t uavcan_make_message_id(const uavcan_frame_id_t *frame_id)
+{
+ return (frame_id->transfer_id & 0x7u) |
+ ((frame_id->last_frame ? 1u : 0u) << 3u) |
+ ((frame_id->frame_index & 0x3Fu) << 4u) |
+ ((frame_id->source_node_id & 0x7Fu) << 10u) |
+ ((frame_id->transfer_type & 0x3u) << 17u) |
+ ((frame_id->data_type_id & 0x3FFu) << 19u);
+}
+
+/****************************************************************************
+ * Name: uavcan_parse_message_id
+ *
+ * Description:
+ * This function formats the data of a uavcan message_id contained in a uint32
+ * into uavcan_frame_id_t structure.
+ *
+ * Input Parameters:
+ * frame_id - A pointer to a uavcan_frame_id_t parse the message_id into.
+ * message_id - The message id to parse into the uavcan_frame_id_t
+ * expected_id -The expected uavcan data_type_id that has been parsed into
+ * frame_id's data_type_id field
+ *
+ * Returned value:
+ * The result of comparing the data_type_id to the expected_id
+ * Non Zero if they match otherwise zero.
+ *
+ ****************************************************************************/
+int uavcan_parse_message_id(uavcan_frame_id_t *frame_id, uint32_t message_id,
+ uint16_t expected_id)
+{
+ frame_id->transfer_id = message_id & 0x7u;
+ frame_id->last_frame = (message_id & 0x8u) ? 1u : 0u;
+ frame_id->frame_index = (message_id >> 4u) & 0x3Fu;
+ frame_id->source_node_id = (message_id >> 10u) & 0x7Fu;
+ frame_id->transfer_type = (message_id >> 17u) & 0x3u;
+ frame_id->data_type_id = (message_id >> 19u) & 0x3FFu;
+ return expected_id == frame_id->data_type_id;
+}
+
+/****************************************************************************
+ * Name: uavcan_tx_nodestatus
+ *
+ * Description:
+ * This function sends a uavcan nodestatus message
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * uptime_sec - This node's uptime in seconds.
+ * status_code - This node's current status code
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void uavcan_tx_nodestatus(uint8_t node_id, uint32_t uptime_sec,
+ uint8_t status_code)
+{
+ uavcan_nodestatus_t message;
+ uavcan_frame_id_t frame_id;
+ uint8_t payload[8];
+ size_t frame_len;
+
+ frame_id.transfer_id = 0;
+ frame_id.last_frame = 1u;
+ frame_id.frame_index = 0;
+ frame_id.source_node_id = node_id;
+ frame_id.transfer_type = MESSAGE_BROADCAST;
+ frame_id.data_type_id = UAVCAN_NODESTATUS_DTID;
+
+ message.uptime_sec = uptime_sec;
+ message.status_code = status_code;
+ message.vendor_specific_status_code = 0u;
+ frame_len = uavcan_pack_nodestatus(payload, &message);
+
+ can_tx(uavcan_make_message_id(&frame_id), frame_len, payload, MBNodeStatus);
+}
+
+/****************************************************************************
+ * 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.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted 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,
+ uint8_t transfer_id)
+{
+ uint8_t payload[8];
+ uavcan_frame_id_t frame_id;
+ size_t i;
+ size_t max_offset;
+ size_t checksum;
+
+ max_offset = unique_id_offset + 7u;
+ if (max_offset > unique_id_length) {
+ max_offset = unique_id_length;
+ }
+
+ payload[0] = (uint8_t)((requested_node_id << 1u) |
+ (unique_id_offset ? 0u : 1u));
+ for (checksum = 0u, i = 0u; i < max_offset - unique_id_offset; i++) {
+ payload[i + 1u] = unique_id[unique_id_offset + i];
+ checksum += unique_id[unique_id_offset + i];
+ }
+
+ frame_id.transfer_id = transfer_id;
+ frame_id.last_frame = 1u;
+ frame_id.frame_index = (uint8_t)checksum;
+ frame_id.source_node_id = 0u;
+ frame_id.transfer_type = MESSAGE_BROADCAST;
+ frame_id.data_type_id = UAVCAN_DYNAMICNODEIDALLOCATION_DTID;
+
+ can_tx(uavcan_make_message_id(&frame_id), i + 1u,
+ payload, MBAll);
+}
+
+/****************************************************************************
+ * Name: uavcan_tx_getnodeinfo_response
+ *
+ * Description:
+ * This function sends a uavcan getnodeinfo response to a getnodeinfo
+ * request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer to this node's uavcan_getnodeinfo_response_t
+ * response data.
+ * dest_node_id - The destination node id to send the message to.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_getnodeinfo_response(uint8_t node_id,
+ uavcan_getnodeinfo_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id)
+{
+ /*
+ This sends via mailbox 1 because it's called from SysTick. It may also
+ clobber response->name because it moves the name to the end of the COA.
+ */
+ uint32_t i;
+ uavcan_frame_id_t frame_id;
+ size_t fixed_length;
+ size_t contiguous_length;
+ size_t packet_length;
+
+ fixed_length = 6u + sizeof(uavcan_softwareversion_t) + 2u + 16u + 1u;
+ contiguous_length = fixed_length +
+ response->hardware_version.certificate_of_authenticity_length;
+ packet_length = contiguous_length + response->name_length;
+
+ /* Move name so it's contiguous with the start of the packet */
+ for (i = 0u; i < response->name_length; i++) {
+ ((uint8_t*)response)[contiguous_length + i] = response->name[i];
+ }
+
+ /* Set up the message ID */
+ frame_id.transfer_id = transfer_id;
+ frame_id.source_node_id = node_id;
+ frame_id.transfer_type = SERVICE_RESPONSE;
+ frame_id.data_type_id = UAVCAN_GETNODEINFO_DTID;
+
+ uavcan_tx_multiframe_(&frame_id, dest_node_id, packet_length,
+ (const uint8_t*)response, UAVCAN_GETNODEINFO_CRC,
+ MBGetNodeInfo);
+}
+
+/****************************************************************************
+ * Name: uavcan_rx_beginfirmwareupdate_request
+ *
+ * Description:
+ * This function attempts to receive a uavcan beginfirmwareupdate request
+ * message
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_beginfirmwareupdate_request_t to
+ * receive the request data into.
+ * frame_id - A pointer to a uavcan_frame_id_t to return frame_id
+ * components in.
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+
+can_error_t uavcan_rx_beginfirmwareupdate_request(uint8_t node_id,
+ uavcan_beginfirmwareupdate_request_t *request,
+ uavcan_frame_id_t *frame_id)
+{
+ size_t length;
+ can_error_t status;
+
+ length = sizeof(uavcan_beginfirmwareupdate_request_t) - 1;
+ frame_id->transfer_id = 0xFFu;
+ frame_id->source_node_id = 0xFFu;
+ frame_id->transfer_type = SERVICE_REQUEST;
+ frame_id->data_type_id = UAVCAN_BEGINFIRMWAREUPDATE_DTID;
+
+ status = uavcan_rx_multiframe_(node_id, frame_id, &length,
+ (uint8_t*)request,
+ UAVCAN_BEGINFIRMWAREUPDATE_CRC, CAN_REQUEST_TIMEOUT);
+
+ if (status == CAN_OK && length >= 1u) {
+ request->path_length = (uint8_t)(length - 1u);
+ return CAN_OK;
+ } else {
+ return CAN_ERROR;
+ }
+}
+
+/****************************************************************************
+ * Name: uavcan_tx_read_request
+ *
+ * Description:
+ * This function sends a uavcan read request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_read_request_t to
+ * send.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_read_request(uint8_t node_id,
+ const uavcan_read_request_t *request,
+ uint8_t dest_node_id,
+ uint8_t transfer_id)
+{
+ uavcan_frame_id_t frame_id;
+
+ /* Set up the message ID */
+ frame_id.transfer_id = transfer_id;
+ frame_id.source_node_id = node_id;
+ frame_id.transfer_type = SERVICE_REQUEST;
+ frame_id.data_type_id = UAVCAN_READ_DTID;
+
+ uavcan_tx_multiframe_(&frame_id, dest_node_id, request->path_length + 4u,
+ (const uint8_t*)request, UAVCAN_READ_CRC, MBAll);
+}
+
+
+/****************************************************************************
+ * Name: uavcan_rx_read_response
+ *
+ * Description:
+ * This function attempts to receive a uavcan read response message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer a uavcan_read_response_t to receive the
+ * response data into.
+ * dest_node_id - The remote node id to expect the message from.
+ * transfer_id - The expected transfer_id used to correlate this response
+ * message to the transmitted request message.
+ * timeout_ms - The number of milliseconds to wait for a response
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+
+can_error_t uavcan_rx_read_response(uint8_t node_id,
+ uavcan_read_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id,
+ uint32_t timeout_ms)
+{
+ uavcan_frame_id_t frame_id;
+ size_t length;
+ can_error_t status;
+
+ length = sizeof(uavcan_read_response_t) - 1;
+ frame_id.transfer_id = transfer_id;
+ frame_id.source_node_id = dest_node_id;
+ frame_id.transfer_type = SERVICE_RESPONSE;
+ frame_id.data_type_id = UAVCAN_READ_DTID;
+
+ status = uavcan_rx_multiframe_(node_id, &frame_id, &length,
+ (uint8_t*)response, UAVCAN_READ_CRC,
+ timeout_ms);
+
+ if (status == CAN_OK && length >= 2u) {
+ response->data_length = (uint8_t)(length - 2u);
+ return CAN_OK;
+ } else {
+ return CAN_ERROR;
+ }
+}
+
+/****************************************************************************
+ * Name: uavcan_tx_getinfo_request
+ *
+ * Description:
+ * This function sends a uavcan getinfo request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_getinfo_request_t to
+ * send.
+ * dest_node_id - The destination node id to send the message to.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_getinfo_request(uint8_t node_id,
+ const uavcan_getinfo_request_t *request,
+ uint8_t dest_node_id,
+ uint8_t transfer_id)
+{
+ uavcan_frame_id_t frame_id;
+
+ /* Set up the message ID */
+ frame_id.transfer_id = transfer_id;
+ frame_id.source_node_id = node_id;
+ frame_id.transfer_type = SERVICE_REQUEST;
+ frame_id.data_type_id = UAVCAN_GETINFO_DTID;
+
+ uavcan_tx_multiframe_(&frame_id, dest_node_id, request->path_length,
+ (const uint8_t*)request, UAVCAN_GETINFO_CRC, MBAll);
+}
+
+/****************************************************************************
+ * Name: uavcan_rx_getinfo_response
+ *
+ * Description:
+ * This function attempts to receive a uavcan getinfo response message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer a uavcan_getinfo_response_t to receive the
+ * response data into.
+ * dest_node_id - The remote node id to expect the message from.
+ * transfer_id - The expected transfer_id used to correlate this response
+ * message to the transmitted request message.
+ * timeout_ms - The number of milliseconds to wait for a response
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+can_error_t uavcan_rx_getinfo_response(uint8_t node_id,
+ uavcan_getinfo_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id,
+ uint32_t timeout_ms)
+{
+ uavcan_frame_id_t frame_id;
+ size_t length;
+ can_error_t status;
+
+ length = sizeof(uavcan_getinfo_response_t);
+ frame_id.transfer_id = transfer_id;
+ frame_id.source_node_id = dest_node_id;
+ frame_id.transfer_type = SERVICE_RESPONSE;
+ frame_id.data_type_id = UAVCAN_GETINFO_DTID;
+
+ status = uavcan_rx_multiframe_(node_id, &frame_id, &length,
+ (uint8_t*)response, UAVCAN_GETINFO_CRC,
+ timeout_ms);
+
+ if (status == CAN_OK && length == sizeof(uavcan_getinfo_response_t)) {
+ return CAN_OK;
+ } else {
+ return CAN_ERROR;
+ }
+}
+
+
diff --git a/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.h b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.h
new file mode 100644
index 000000000..f14dbd685
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/bootloader/uavcan/protocol.h
@@ -0,0 +1,501 @@
+/****************************************************************************
+ *
+ * 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 <nuttx/compiler.h>
+
+#include <stdint.h>
+#include <stdlib.h>
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+#define UAVCAN_SERVICE_RETRIES 3
+#define UAVCAN_SERVICE_TIMEOUT_MS 1000
+#define UAVCAN_NODESTATUS_INTERVAL_MS 500
+
+/****************************************************************************
+ * Public Type Definitions
+ ****************************************************************************/
+
+typedef enum
+{
+ CAN_OK = 0,
+ CAN_BOOT_TIMEOUT,
+ CAN_ERROR
+} can_error_t;
+
+/* UAVCAN message formats */
+typedef enum {
+ SERVICE_RESPONSE = 0,
+ SERVICE_REQUEST = 1,
+ MESSAGE_BROADCAST = 2,
+ MESSAGE_UNICAST = 3
+} uavcan_transfertype_t;
+
+typedef struct packed_struct uavcan_frame_id_t {
+ uint8_t transfer_id;
+ uint8_t last_frame;
+ uint8_t frame_index;
+ uint8_t source_node_id;
+ uavcan_transfertype_t transfer_type;
+ uint16_t data_type_id;
+} uavcan_frame_id_t;
+
+typedef struct packed_struct uavcan_nodestatus_t {
+ uint32_t uptime_sec;
+ uint8_t status_code;
+ uint16_t vendor_specific_status_code;
+} uavcan_nodestatus_t;
+
+#define UAVCAN_NODESTATUS_DTID 550u
+#define UAVCAN_NODESTATUS_STATUS_INITIALIZING 1u
+#define UAVCAN_NODESTATUS_STATUS_WARNING 2u
+#define UAVCAN_NODESTATUS_STATUS_CRITICAL 3u
+
+
+typedef struct packed_struct uavcan_softwareversion_t {
+ uint8_t major;
+ uint8_t minor;
+ uint8_t optional_field_mask;
+ uint32_t vcs_commit;
+ uint64_t image_crc;
+} uavcan_softwareversion_t;
+
+typedef struct packed_struct uavcan_hardwareversion_t {
+ uint8_t major;
+ uint8_t minor;
+ uint8_t unique_id[16];
+ uint8_t certificate_of_authenticity_length;
+ uint8_t certificate_of_authenticity[255];
+} uavcan_hardwareversion_t;
+
+typedef struct packed_struct uavcan_getnodeinfo_response_t {
+ uint8_t nodestatus[6];
+
+ uavcan_softwareversion_t software_version;
+ uavcan_hardwareversion_t hardware_version;
+
+ uint8_t name[80];
+ uint8_t name_length;
+} uavcan_getnodeinfo_response_t;
+
+#define UAVCAN_GETNODEINFO_DTID 551u
+#define UAVCAN_GETNODEINFO_CRC 0x14BBu
+
+
+typedef struct packed_struct uavcan_allocation_t {
+ uint8_t node_id; /* bottom bit is the first part flag */
+ uint8_t unique_id[16];
+} uavcan_allocation_t;
+
+#define UAVCAN_DYNAMICNODEIDALLOCATION_DTID 559u
+
+
+typedef struct packed_struct uavcan_logmessage_t {
+ uint8_t level;
+ uint8_t message[2];
+} uavcan_logmessage_t;
+
+#define UAVCAN_LOGMESSAGE_DTID 1023u
+#define UAVCAN_LOGMESSAGE_LEVEL_DEBUG 0u
+#define UAVCAN_LOGMESSAGE_LEVEL_INFO 1u
+#define UAVCAN_LOGMESSAGE_LEVEL_WARNING 2u
+#define UAVCAN_LOGMESSAGE_LEVEL_ERROR 3u
+#define UAVCAN_LOGMESSAGE_SOURCE_0 'B'
+#define UAVCAN_LOGMESSAGE_SOURCE_1 'O'
+#define UAVCAN_LOGMESSAGE_SOURCE_2 'O'
+#define UAVCAN_LOGMESSAGE_SOURCE_3 'T'
+
+#define UAVCAN_LOGMESSAGE_STAGE_INIT 'I'
+#define UAVCAN_LOGMESSAGE_STAGE_GET_INFO 'G'
+#define UAVCAN_LOGMESSAGE_STAGE_ERASE 'E'
+#define UAVCAN_LOGMESSAGE_STAGE_READ 'R'
+#define UAVCAN_LOGMESSAGE_STAGE_PROGRAM 'P'
+#define UAVCAN_LOGMESSAGE_STAGE_VALIDATE 'V'
+#define UAVCAN_LOGMESSAGE_STAGE_FINALIZE 'F'
+#define UAVCAN_LOGMESSAGE_RESULT_START 's'
+#define UAVCAN_LOGMESSAGE_RESULT_FAIL 'f'
+#define UAVCAN_LOGMESSAGE_RESULT_OK 'o'
+
+
+typedef struct packed_struct uavcan_beginfirmwareupdate_request_t {
+ uint8_t source_node_id;
+ uint8_t path[200];
+ uint8_t path_length;
+} uavcan_beginfirmwareupdate_request_t;
+
+typedef struct packed_struct uavcan_beginfirmwareupdate_response_t {
+ uint8_t error;
+} uavcan_beginfirmwareupdate_response_t;
+
+#define UAVCAN_BEGINFIRMWAREUPDATE_DTID 580u
+#define UAVCAN_BEGINFIRMWAREUPDATE_CRC 0x729Eu
+#define UAVCAN_BEGINFIRMWAREUPDATE_ERROR_OK 0u
+#define UAVCAN_BEGINFIRMWAREUPDATE_ERROR_INVALID_MODE 1u
+#define UAVCAN_BEGINFIRMWAREUPDATE_ERROR_IN_PROGRESS 2u
+#define UAVCAN_BEGINFIRMWAREUPDATE_ERROR_UNKNOWN 255u
+
+
+typedef struct packed_struct uavcan_getinfo_request_t {
+ uint8_t path[200];
+ uint8_t path_length;
+} uavcan_getinfo_request_t;
+
+typedef struct packed_struct uavcan_getinfo_response_t {
+ uint64_t crc64;
+ uint32_t size;
+ uint16_t error;
+ uint8_t entry_type;
+} uavcan_getinfo_response_t;
+
+#define UAVCAN_GETINFO_DTID 585u
+#define UAVCAN_GETINFO_CRC 0x37A0u
+#define UAVCAN_GETINFO_ENTRY_TYPE_FLAG_FILE 0x01u
+#define UAVCAN_GETINFO_ENTRY_TYPE_FLAG_DIRECTORY 0x02u
+#define UAVCAN_GETINFO_ENTRY_TYPE_FLAG_SYMLINK 0x04u
+#define UAVCAN_GETINFO_ENTRY_TYPE_FLAG_READABLE 0x08u
+#define UAVCAN_GETINFO_ENTRY_TYPE_FLAG_WRITEABLE 0x10u
+
+
+typedef struct packed_struct uavcan_read_request_t {
+ uint32_t offset;
+ uint8_t path[200];
+ uint8_t path_length;
+} uavcan_read_request_t;
+
+typedef struct packed_struct uavcan_read_response_t {
+ uint16_t error;
+ uint8_t data[250];
+ uint8_t data_length;
+} uavcan_read_response_t;
+
+#define UAVCAN_READ_DTID 588u
+#define UAVCAN_READ_CRC 0x2921u
+
+#define UAVCAN_FILE_ERROR_OK 0u
+/* Left the others out for now because we don't really care why it failed */
+
+
+#define UAVCAN_ALLOCATION_CRC 0x7BAAu
+
+/****************************************************************************
+ * Global Variables
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Function Prototypes
+ ****************************************************************************/
+/****************************************************************************
+ * Name: uavcan_pack_nodestatus
+ *
+ * Description:
+ * This function formats the data of a uavcan_nodestatus_t structure into
+ * an array of bytes.
+ *
+ * Input Parameters:
+ * data - The array of bytes to populate.
+ * message - The uavcan_nodestatus_t to pack into the data
+ *
+ * Returned value:
+ * Number of bytes written.
+ *
+ ****************************************************************************/
+
+size_t uavcan_pack_nodestatus(uint8_t *data,
+ const uavcan_nodestatus_t *message);
+
+/****************************************************************************
+ * Name: uavcan_pack_logmessage
+ *
+ * Description:
+ * This function formats the data of a uavcan_logmessage_t structure into
+ * an array of bytes.
+ *
+ * Input Parameters:
+ * data - The array of bytes to populate.
+ * message - The uavcan_logmessage_t to pack into the data
+ *
+ * Returned value:
+ * Number of bytes written.
+ *
+ ****************************************************************************/
+
+size_t uavcan_pack_logmessage(uint8_t *data,
+ const uavcan_logmessage_t *message);
+
+/****************************************************************************
+ * Name: uavcan_make_message_id
+ *
+ * Description:
+ * This function formats the data of a uavcan_frame_id_t structure into
+ * a unit32.
+ *
+ * Input Parameters:
+ * frame_id - The uavcan_frame_id_t to pack.
+ *
+ * Returned value:
+ * A unit32 that is the message id formed from packing the
+ * uavcan_frame_id_t.
+ *
+ ****************************************************************************/
+
+uint32_t uavcan_make_message_id(const uavcan_frame_id_t *frame_id);
+
+/****************************************************************************
+ * Name: uavcan_parse_message_id
+ *
+ * Description:
+ * This function formats the data of a uavcan message_id contained in a uint32
+ * into uavcan_frame_id_t structure.
+ *
+ * Input Parameters:
+ * frame_id - A pointer to a uavcan_frame_id_t parse the message_id into.
+ * message_id - The message id to parse into the uavcan_frame_id_t
+ * expected_id -The expected uavcan data_type_id that has been parsed into
+ * frame_id's data_type_id field
+ *
+ * Returned value:
+ * The result of comparing the data_type_id to the expected_id
+ * Non Zero if they match otherwise zero.
+ *
+ ****************************************************************************/
+int uavcan_parse_message_id(uavcan_frame_id_t *frame_id, uint32_t message_id,
+ uint16_t expected_id);
+
+/****************************************************************************
+ * Name: uavcan_tx_nodestatus
+ *
+ * Description:
+ * This function sends a uavcan nodestatus message
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * uptime_sec - This node's uptime in seconds.
+ * status_code - This node's current status code
+ *
+ * Returned value:
+ * None.
+ *
+ ****************************************************************************/
+
+void uavcan_tx_nodestatus(uint8_t node_id, uint32_t uptime_sec,
+ uint8_t status_code);
+
+/****************************************************************************
+ * 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.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted 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,
+ uint8_t transfer_id);
+
+/****************************************************************************
+ * Name: uavcan_tx_getnodeinfo_response
+ *
+ * Description:
+ * This function sends a uavcan getnodeinfo response to a getnodeinfo
+ * request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer to this node's uavcan_getnodeinfo_response_t
+ * response data.
+ * dest_node_id - The destination node id to send the message to.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_getnodeinfo_response(uint8_t node_id,
+ uavcan_getnodeinfo_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id);
+
+/****************************************************************************
+ * Name: uavcan_rx_beginfirmwareupdate_request
+ *
+ * Description:
+ * This function attempts to receive a uavcan beginfirmwareupdate request
+ * message
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_beginfirmwareupdate_request_t to
+ * receive the request data into.
+ * frame_id - A pointer to a uavcan_frame_id_t to return frame_id
+ * components in.
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+
+can_error_t uavcan_rx_beginfirmwareupdate_request(uint8_t node_id,
+ uavcan_beginfirmwareupdate_request_t *request,
+ uavcan_frame_id_t *frame_id);
+
+/****************************************************************************
+ * Name: uavcan_tx_read_request
+ *
+ * Description:
+ * This function sends a uavcan read request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_read_request_t to
+ * send.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_read_request(uint8_t node_id,
+ const uavcan_read_request_t *request,
+ uint8_t dest_node_id,
+ uint8_t transfer_id);
+
+/****************************************************************************
+ * Name: uavcan_rx_read_response
+ *
+ * Description:
+ * This function attempts to receive a uavcan read response message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer a uavcan_read_response_t to receive the
+ * response data into.
+ * dest_node_id - The remote node id to expect the message from.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ * timeout_ms - The number of milliseconds to wait for a response
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+
+can_error_t uavcan_rx_read_response(uint8_t node_id,
+ uavcan_read_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id,
+ uint32_t timeout_ms);
+
+/****************************************************************************
+ * Name: uavcan_tx_getinfo_request
+ *
+ * Description:
+ * This function sends a uavcan getinfo request message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * request - A pointer a uavcan_getinfo_request_t to
+ * send.
+ * dest_node_id - The destination node id to send the message to.
+ * transfer_id - An incrementing count used to correlate a received
+ * message to this transmitted message.
+ *
+ * Returned value:
+ * None
+ *
+ ****************************************************************************/
+
+void uavcan_tx_getinfo_request(uint8_t node_id,
+ const uavcan_getinfo_request_t *request,
+ uint8_t dest_node_id,
+ uint8_t transfer_id);
+
+/****************************************************************************
+ * Name: uavcan_rx_getinfo_response
+ *
+ * Description:
+ * This function attempts to receive a uavcan getinfo response message.
+ *
+ * Input Parameters:
+ * node_id - This node's node id
+ * response - A pointer a uavcan_getinfo_response_t to receive the
+ * response data into.
+ * dest_node_id - The remote node id to expect the message from.
+ * transfer_id - The expected transfer_id used to correlate this response
+ * message to the transmitted request message.
+ * timeout_ms - The number of milliseconds to wait for a response
+ *
+ *
+ * Returned value:
+ * CAN_OK on Success and CAN_ERROR otherwise.
+ *
+ ****************************************************************************/
+can_error_t uavcan_rx_getinfo_response(uint8_t node_id,
+ uavcan_getinfo_response_t *response,
+ uint8_t dest_node_id,
+ uint8_t transfer_id,
+ uint32_t timeout_ms);
diff --git a/src/drivers/boards/px4cannode-v1/module.mk b/src/drivers/boards/px4cannode-v1/module.mk
new file mode 100644
index 000000000..fbed87330
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/module.mk
@@ -0,0 +1,15 @@
+#
+# Board-specific startup code for the PX4CANNODE
+#
+
+SRCS = \
+ px4cannode_can.c \
+ px4cannode_buttons.c \
+ px4cannode_init.c \
+ px4cannode_led.c \
+ px4cannode_spi.c \
+ ../../../drivers/device/cdev.cpp \
+ ../../../drivers/device/device.cpp \
+ ../../../modules/systemlib/up_cxxinitialize.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/drivers/boards/px4cannode-v1/px4cannode_buttons.c b/src/drivers/boards/px4cannode-v1/px4cannode_buttons.c
new file mode 100644
index 000000000..bd2363cce
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_buttons.c
@@ -0,0 +1,154 @@
+/****************************************************************************
+ *
+ * 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 px4cannode_buttons.c
+ *
+ * PX4CANNODE- Buttons
+ */
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/board.h>
+#include <arch/board/board.h>
+
+#include "board_config.h"
+
+#ifdef CONFIG_ARCH_BUTTONS
+
+/****************************************************************************
+ * Pre-processor Definitions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Data
+ ****************************************************************************/
+
+/****************************************************************************
+ * Private Functions
+ ****************************************************************************/
+
+/****************************************************************************
+ * Public Functions
+ ****************************************************************************/
+void board_button_initialize(void);
+xcpt_t board_button_irq(int id, xcpt_t irqhandler);
+/****************************************************************************
+ * Button support.
+ *
+ * Description:
+ * board_button_initialize() must be called to initialize button resources.
+ *
+ * After board_button_initialize() has been called, board_buttons() may be
+ * called to collect the state of all buttons. board_buttons() returns an
+ * 8-bit bit set with each bit associated with a button.
+ * See the BUTTON_*_BIT definitions in board.h for the meaning of each bit.
+ *
+ * board_button_irq() may be called to register an interrupt handler that
+ * will be called when a button is depressed or released. The ID value is
+ * a button enumeration value that uniquely identifies a button resource.
+ * See the BUTTON_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned
+ * (so that it may restored, if so desired).
+ *
+ ****************************************************************************/
+
+/****************************************************************************
+ * Name: board_button_initialize
+ *
+ * Description:
+ * board_button_initialize() must be called to initialize button resources.
+ * After that, board_buttons() may be called to collect the current state of
+ * all buttons or board_button_irq() may be called to register button
+ * interrupt handlers.
+ *
+ ****************************************************************************/
+
+void board_button_initialize(void)
+{
+ stm32_configgpio(BUTTON_BOOT0n);
+}
+
+/****************************************************************************
+ * Name: board_buttons
+ *
+ * Description:
+ *
+ * After board_button_initialize() has been called, board_buttons() may be
+ * called to collect the state of all buttons. board_buttons() returns an
+ * 8-bit bit set with each bit associated with a button.
+ * See the BUTTON_*_BIT definitions in board.h for the meaning of each bit.
+ *
+ ****************************************************************************/
+
+uint8_t board_buttons(void)
+{
+ return stm32_gpioread(BUTTON_BOOT0n) ? 0 : BUTTON_BOOT0_MASK;
+}
+
+/****************************************************************************
+ * Name: board_button_irq
+ *
+ * Description:
+ *
+ * board_button_irq() may be called to register an interrupt handler that
+ * will be called when a button is depressed or released. The ID value is
+ * a button enumeration value that uniquely identifies a button resource.
+ * See the BUTTON_* definitions in board.h for the meaning of enumeration
+ * value. The previous interrupt handler address is returned
+ * (so that it may restored, if so desired).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_ARCH_IRQBUTTONS
+xcpt_t board_button_irq(int id, xcpt_t irqhandler)
+{
+ xcpt_t oldhandler = NULL;
+
+ /* The following should be atomic */
+
+ if (id == IRQBUTTON)
+ {
+ oldhandler = stm32_gpiosetevent(BUTTON_BOOT0n, true, true, true, irqhandler);
+ }
+
+ return oldhandler;
+}
+#endif
+#endif /* CONFIG_ARCH_BUTTONS */
diff --git a/src/drivers/boards/px4cannode-v1/px4cannode_can.c b/src/drivers/boards/px4cannode-v1/px4cannode_can.c
new file mode 100644
index 000000000..d0bf9e24b
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_can.c
@@ -0,0 +1,147 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file pxesc_can.c
+ *
+ * Board-specific CAN functions.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/can.h>
+#include <arch/board/board.h>
+
+#include "chip.h"
+#include "up_arch.h"
+
+#include "stm32.h"
+#include "stm32_can.h"
+#include "board_config.h"
+
+#if defined(CONFIG_CAN)
+
+/************************************************************************************
+ * Pre-processor Definitions
+ ************************************************************************************/
+/* Configuration ********************************************************************/
+/* The STM32F107VC supports CAN1 and CAN2 */
+
+#if defined(CONFIG_STM32_CAN1) && defined(CONFIG_STM32_CAN2)
+# warning "Both CAN1 and CAN2 are enabled. Assuming only CAN1."
+# undef CONFIG_STM32_CAN2
+#endif
+
+#ifdef CONFIG_STM32_CAN1
+# define CAN_PORT 1
+#else
+# define CAN_PORT 2
+#endif
+
+/* Debug ***************************************************************************/
+/* Non-standard debug that may be enabled just for testing CAN */
+
+#ifdef CONFIG_DEBUG_CAN
+# define candbg dbg
+# define canvdbg vdbg
+# define canlldbg lldbg
+# define canllvdbg llvdbg
+#else
+# define candbg(x...)
+# define canvdbg(x...)
+# define canlldbg(x...)
+# define canllvdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+int can_devinit(void);
+
+/************************************************************************************
+ * Name: can_devinit
+ *
+ * Description:
+ * All STM32 architectures must provide the following interface to work with
+ * examples/can.
+ *
+ ************************************************************************************/
+
+__EXPORT int can_devinit(void)
+{
+ static bool initialized = false;
+ struct can_dev_s *can;
+ int ret;
+
+ /* Check if we have already initialized */
+
+ if (!initialized)
+ {
+ /* Call stm32_caninitialize() to get an instance of the CAN interface */
+
+ can = stm32_caninitialize(CAN_PORT);
+ if (can == NULL)
+ {
+ candbg("ERROR: Failed to get CAN interface\n");
+ return -ENODEV;
+ }
+
+ /* Register the CAN driver at "/dev/can0" */
+
+ ret = can_register("/dev/can0", can);
+ if (ret < 0)
+ {
+ candbg("ERROR: can_register failed: %d\n", ret);
+ return ret;
+ }
+
+ /* Now we are initialized */
+
+ initialized = true;
+ }
+
+ return OK;
+}
+
+#endif /* CONFIG_CAN && CONFIG_STM32_CAN1 */
diff --git a/src/drivers/boards/px4cannode-v1/px4cannode_init.c b/src/drivers/boards/px4cannode-v1/px4cannode_init.c
new file mode 100644
index 000000000..2ede792bb
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_init.c
@@ -0,0 +1,200 @@
+/****************************************************************************
+ *
+ * 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 px4cannode_init.c
+ *
+ * PX4CANNODE-specific early startup code. This file implements the
+ * nsh_archinitialize() function that is called early by nsh during startup.
+ *
+ * Code here is run before the rcS script is invoked; it should start required
+ * subsystems and perform board-specific initialization.
+ */
+
+/****************************************************************************
+ * Included Files
+ ****************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <stdio.h>
+#include <debug.h>
+#include <errno.h>
+
+#include <nuttx/arch.h>
+#include <nuttx/board.h>
+#include <nuttx/spi/spi.h>
+#include <nuttx/i2c.h>
+#include <nuttx/mmcsd.h>
+#include <nuttx/analog/adc.h>
+
+#include <stm32.h>
+#include "board_config.h"
+#include "stm32_uart.h"
+
+#include <arch/board/board.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_led.h>
+
+#include <systemlib/cpuload.h>
+
+#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
+#include <systemlib/systemlib.h>
+#endif
+
+#include "board_config.h"
+
+/* todo: This is constant but not proper */
+__BEGIN_DECLS
+extern void led_off(int led);
+__END_DECLS
+
+
+/****************************************************************************
+ * Pre-Processor Definitions
+ ****************************************************************************/
+
+/* Configuration ************************************************************/
+
+/* Debug ********************************************************************/
+
+/****************************************************************************
+ * Protected 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)
+{
+ /* configure LEDs */
+ board_led_initialize();
+ board_button_initialize();
+ stm32_configgpio(GPIO_CAN_CTRL);
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || \
+ defined(CONFIG_STM32_SPI3)
+ board_spiinitialize();
+#endif
+}
+
+
+__EXPORT void board_initialize(void)
+{
+}
+
+/****************************************************************************
+ * Name: nsh_archinitialize
+ *
+ * Description:
+ * Perform architecture specific initialization
+ *
+ ****************************************************************************/
+
+
+#include <math.h>
+
+#ifdef __cplusplus
+__EXPORT int matherr(struct __exception *e)
+{
+ return 1;
+}
+#else
+__EXPORT int matherr(struct exception *e)
+{
+ return 1;
+}
+#endif
+
+#ifdef CONFIG_NSH_LIBRARY
+__EXPORT int nsh_archinitialize(void)
+#else
+__EXPORT int app_archinitialize(void)
+#endif
+{
+ int result = OK;
+
+#if defined(CONFIG_HAVE_CXX) && defined(CONFIG_HAVE_CXXINITIALIZE)
+
+ /* run C++ ctors before we go any further */
+
+ up_cxxinitialize();
+
+# if defined(CONFIG_EXAMPLES_NSH_CXXINITIALIZE)
+# error CONFIG_EXAMPLES_NSH_CXXINITIALIZE Must not be defined! Use CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE.
+# endif
+
+#else
+# error platform is dependent on c++ both CONFIG_HAVE_CXX and CONFIG_HAVE_CXXINITIALIZE must be defined.
+#endif
+
+ /* configure the high-resolution time/callout interface */
+ hrt_init();
+
+ /* set up the serial DMA polling */
+ static struct hrt_call serial_dma_call;
+ struct timespec ts;
+
+ /*
+ * Poll at 1ms intervals for received bytes that have not triggered
+ * a DMA event.
+ */
+ ts.tv_sec = 0;
+ ts.tv_nsec = 1000000;
+
+ hrt_call_every(&serial_dma_call,
+ ts_to_abstime(&ts),
+ ts_to_abstime(&ts),
+ (hrt_callout)stm32_serial_dma_poll,
+ NULL);
+
+ /* initial LED state */
+ drv_led_start();
+
+ led_off(LED_AMBER);
+ led_off(LED_BLUE);
+
+ return result;
+}
diff --git a/src/drivers/boards/px4cannode-v1/px4cannode_led.c b/src/drivers/boards/px4cannode-v1/px4cannode_led.c
new file mode 100644
index 000000000..a34af704d
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_led.c
@@ -0,0 +1,175 @@
+/****************************************************************************
+ *
+ * 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 px4cannode_led.c
+ *
+ * PX4ESC LED backend.
+ */
+
+#include <nuttx/config.h>
+
+#include <stdbool.h>
+#include <nuttx/board.h>
+
+#include "stm32.h"
+#include "board_config.h"
+
+#include <arch/board/board.h>
+
+#include <systemlib/px4_macros.h>
+
+/*
+ * Ideally we'd be able to get these from up_internal.h,
+ * but since we want to be able to disable the NuttX use
+ * of leds for system indication at will and there is no
+ * separate switch, we need to build independent of the
+ * CONFIG_ARCH_LEDS configuration switch.
+ */
+__BEGIN_DECLS
+extern void led_init(void);
+extern void led_on(int led);
+extern void led_off(int led);
+extern void led_toggle(int led);
+__END_DECLS
+
+static uint16_t g_ledmap[] = {
+ GPIO_LED_GREEN, // Indexed by LED_GREEN
+ GPIO_LED_YELLOW, // Indexed by LED_YELLOW
+};
+
+__EXPORT void led_init(void)
+{
+ /* Configure LED1-2 GPIOs for output */
+ for (size_t l = 0; l < arraySize(g_ledmap); l++) {
+ stm32_configgpio(g_ledmap[l]);
+ }
+}
+
+__EXPORT void board_led_initialize(void)
+{
+ led_init();
+}
+
+static void phy_set_led(int led, bool state)
+{
+ /* Pull Up to switch on */
+ stm32_gpiowrite(g_ledmap[led], state);
+}
+
+static bool phy_get_led(int led)
+{
+
+ return !stm32_gpioread(g_ledmap[led]);
+}
+
+__EXPORT void led_on(int led)
+{
+ phy_set_led(led, true);
+}
+
+__EXPORT void led_off(int led)
+{
+ phy_set_led(led, false);
+}
+
+__EXPORT void led_toggle(int led)
+{
+
+ phy_set_led(led, !phy_get_led(led));
+}
+
+static bool g_initialized;
+
+// Nuttx Usages
+
+__EXPORT void board_led_on(int led)
+{
+ switch (led)
+ {
+ default:
+ case LED_STARTED:
+ case LED_HEAPALLOCATE:
+ case LED_IRQSENABLED:
+ phy_set_led(LED_GREEN, false);
+ phy_set_led(LED_YELLOW, false);
+ break;
+
+ case LED_STACKCREATED:
+ phy_set_led(LED_GREEN, true);
+ phy_set_led(LED_YELLOW, false);
+ g_initialized = true;
+ break;
+
+ case LED_INIRQ:
+ case LED_SIGNAL:
+ case LED_ASSERTION:
+ case LED_PANIC:
+ phy_set_led(LED_YELLOW, true);
+ break;
+
+ case LED_IDLE : /* IDLE */
+ phy_set_led(LED_GREEN, false);
+ break;
+ }
+}
+
+/****************************************************************************
+ * Name: board_led_off
+ ****************************************************************************/
+
+
+__EXPORT void board_led_off(int led)
+{
+ switch (led)
+ {
+ default:
+ case LED_STARTED:
+ case LED_HEAPALLOCATE:
+ case LED_IRQSENABLED:
+ case LED_STACKCREATED:
+ phy_set_led(LED_GREEN, false);
+ // no break
+
+ case LED_INIRQ:
+ case LED_SIGNAL:
+ case LED_ASSERTION:
+ case LED_PANIC:
+ phy_set_led(LED_YELLOW, false);
+ break;
+
+ case LED_IDLE: /* IDLE */
+ phy_set_led(LED_GREEN, g_initialized);
+ break;
+ }
+}
diff --git a/src/drivers/boards/px4cannode-v1/px4cannode_spi.c b/src/drivers/boards/px4cannode-v1/px4cannode_spi.c
new file mode 100644
index 000000000..a82b4f399
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_spi.c
@@ -0,0 +1,232 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4cannode_led.c
+ *
+ * PX4FMU SPI backend.
+ */
+
+/************************************************************************************
+ * Included Files
+ ************************************************************************************/
+
+#include <nuttx/config.h>
+
+#include <stdint.h>
+#include <stdbool.h>
+#include <errno.h>
+#include <debug.h>
+
+#include <nuttx/spi/spi.h>
+#include <arch/board/board.h>
+
+#include <nuttx/board.h>
+#include "chip.h"
+#include "stm32.h"
+#include "board_config.h"
+
+#if defined(CONFIG_STM32_SPI1) || defined(CONFIG_STM32_SPI2) || defined(CONFIG_STM32_SPI3)
+
+/************************************************************************************
+ * Definitions
+ ************************************************************************************/
+
+/* Enables debug output from this file (needs CONFIG_DEBUG too) */
+
+#undef SPI_DEBUG /* Define to enable debug */
+#undef SPI_VERBOSE /* Define to enable verbose debug */
+
+#ifdef SPI_DEBUG
+# define spidbg lldbg
+# ifdef SPI_VERBOSE
+# define spivdbg lldbg
+# else
+# define spivdbg(x...)
+# endif
+#else
+# undef SPI_VERBOSE
+# define spidbg(x...)
+# define spivdbg(x...)
+#endif
+
+/************************************************************************************
+ * Private Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Public Functions
+ ************************************************************************************/
+
+/************************************************************************************
+ * Name: stm32_spiinitialize
+ *
+ * Description:
+ * Called to configure SPI chip select GPIO pins for the board.
+ *
+ ************************************************************************************/
+
+void weak_function board_spiinitialize(void)
+{
+ /* Setup CS */
+
+#ifdef CONFIG_STM32_SPI1
+ stm32_configgpio(USER_CSn);
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+ stm32_configgpio(MMCSD_CSn);
+#endif
+}
+
+/****************************************************************************
+ * Name: stm32_spi1/2/3select and stm32_spi1/2/3status
+ *
+ * Description:
+ * The external functions, stm32_spi1/2/3select and stm32_spi1/2/3status
+ * must be provided by board-specific logic. They are implementations of
+ * the select and status methods of the SPI interface defined by struct
+ * spi_ops_s (see include/nuttx/spi/spi.h). All other methods (including
+ * up_spiinitialize()) are provided by common STM32 logic. To use this
+ * common SPI logic on your board:
+ *
+ * 1. Provide logic in stm32_boardinitialize() to configure SPI chip
+ * select pins.
+ * 2. Provide stm32_spi1/2/3select() and stm32_spi1/2/3status() functions
+ * in your board-specific logic. These functions will perform chip
+ * selection and status operations using GPIOs in the way your board
+ * is configured.
+ * 3. Add a calls to up_spiinitialize() in your low level application
+ * initialization logic
+ * 4. The handle returned by up_spiinitialize() may then be used to bind
+ * the SPI driver to higher level logic (e.g., calling
+ * mmcsd_spislotinitialize(), for example, will bind the SPI driver to
+ * the SPI MMC/SD driver).
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_STM32_SPI1
+void stm32_spi1select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+ if (devid == SPIDEV_USER)
+ {
+ stm32_gpiowrite(USER_CSn, !selected);
+ }
+}
+
+uint8_t stm32_spi1status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return 0;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+void stm32_spi2select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+#if defined(CONFIG_MMCSD)
+ if (devid == SPIDEV_MMCSD)
+ {
+ stm32_gpiowrite(MMCSD_CSn, !selected);
+ }
+#endif
+}
+
+uint8_t stm32_spi2status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ /* No switch on SD card socket so assume it is here */
+
+ return SPI_STATUS_PRESENT;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+void stm32_spi3select(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool selected)
+{
+ spidbg("devid: %d CS: %s\n", (int)devid, selected ? "assert" : "de-assert");
+}
+
+uint8_t stm32_spi3status(FAR struct spi_dev_s *dev, enum spi_dev_e devid)
+{
+ return 0;
+}
+#endif
+
+/****************************************************************************
+ * Name: stm32_spi1cmddata
+ *
+ * Description:
+ * Set or clear the SH1101A A0 or SD1306 D/C n bit to select data (true)
+ * or command (false). This function must be provided by platform-specific
+ * logic. This is an implementation of the cmddata method of the SPI
+ * interface defined by struct spi_ops_s (see include/nuttx/spi/spi.h).
+ *
+ * Input Parameters:
+ *
+ * spi - SPI device that controls the bus the device that requires the CMD/
+ * DATA selection.
+ * devid - If there are multiple devices on the bus, this selects which one
+ * to select cmd or data. NOTE: This design restricts, for example,
+ * one one SPI display per SPI bus.
+ * cmd - true: select command; false: select data
+ *
+ * Returned Value:
+ * None
+ *
+ ****************************************************************************/
+
+#ifdef CONFIG_SPI_CMDDATA
+#ifdef CONFIG_STM32_SPI1
+int stm32_spi1cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
+{
+ return OK;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI2
+int stm32_spi2cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
+{
+ return OK;
+}
+#endif
+
+#ifdef CONFIG_STM32_SPI3
+int stm32_spi3cmddata(FAR struct spi_dev_s *dev, enum spi_dev_e devid, bool cmd)
+{
+ return -ENODEV;
+}
+#endif
+#endif /* CONFIG_SPI_CMDDATA */
+
+#endif /* CONFIG_STM32_SPI1 || CONFIG_STM32_SPI2 */
diff --git a/src/drivers/boards/px4fmu-v1/board_config.h b/src/drivers/boards/px4fmu-v1/board_config.h
index 38738cb48..3cce92bf7 100644
--- a/src/drivers/boards/px4fmu-v1/board_config.h
+++ b/src/drivers/boards/px4fmu-v1/board_config.h
@@ -61,7 +61,6 @@ __BEGIN_DECLS
/* PX4IO connection configuration */
#define PX4IO_SERIAL_DEVICE "/dev/ttyS2"
-#define UDID_START 0x1FFF7A10
//#ifdef CONFIG_STM32_SPI2
//# error "SPI2 is not supported on this board"
diff --git a/src/drivers/boards/px4fmu-v2/board_config.h b/src/drivers/boards/px4fmu-v2/board_config.h
index 541f5c50a..20510f428 100644
--- a/src/drivers/boards/px4fmu-v2/board_config.h
+++ b/src/drivers/boards/px4fmu-v2/board_config.h
@@ -53,8 +53,6 @@ __BEGIN_DECLS
#include <stm32.h>
#include <arch/board/board.h>
-#define UDID_START 0x1FFF7A10
-
/****************************************************************************************************
* Definitions
****************************************************************************************************/
diff --git a/src/lib/version/version.h b/src/lib/version/version.h
index 366ba80a0..26c9b022e 100644
--- a/src/lib/version/version.h
+++ b/src/lib/version/version.h
@@ -65,4 +65,8 @@
#define HW_ARCH "AEROCORE"
#endif
+#ifdef CONFIG_ARCH_BOARD_PX4CANNODE_V1
+#define HW_ARCH "PX4CANNODE_V1"
+#endif
+
#endif /* VERSION_H_ */
diff --git a/src/modules/systemlib/board_serial.c b/src/modules/systemlib/board_serial.c
index 182fd15c6..563b5141c 100644
--- a/src/modules/systemlib/board_serial.c
+++ b/src/modules/systemlib/board_serial.c
@@ -46,7 +46,7 @@
int get_board_serial(uint8_t *serialid)
{
- const volatile uint32_t *udid_ptr = (const uint32_t *)UDID_START;
+ const volatile uint32_t *udid_ptr = (const uint32_t *)STM32_SYSMEM_UID;
union udid id;
val_read((uint32_t *)&id, udid_ptr, sizeof(id));
diff --git a/src/modules/systemlib/mcu_version.c b/src/modules/systemlib/mcu_version.c
index 24f4e4207..f152aad23 100644
--- a/src/modules/systemlib/mcu_version.c
+++ b/src/modules/systemlib/mcu_version.c
@@ -47,15 +47,24 @@
#ifdef CONFIG_ARCH_CHIP_STM32
#include <up_arch.h>
-#define DBGMCU_IDCODE 0xE0042000 //STM DocID018909 Rev 8 Sect 38.18 (MCU device ID code)
-#define UNIQUE_ID 0x1FFF7A10 //STM DocID018909 Rev 8 Sect 39.1 (Unique device ID Register)
+# define DBGMCU_IDCODE 0xE0042000 //STM DocID018909 Rev 8 Sect 38.18 (MCU device ID code)
+# define REVID_MASK 0xFFFF0000
+# define DEVID_MASK 0xFFF
-#define STM32F40x_41x 0x413
-#define STM32F42x_43x 0x419
-
-#define REVID_MASK 0xFFFF0000
-#define DEVID_MASK 0xFFF
+# define STM32F40x_41x 0x413
+# define STM32F42x_43x 0x419
+# define STM32F103_LD 0x412
+# define STM32F103_MD 0x410
+# define STM32F103_HD 0x414
+# define STM32F103_XLD 0x430
+# define STM32F103_CON 0x418
+# if defined(CONFIG_STM32_STM32F40XX)
+# define UNIQUE_ID 0x1FFF7A10 //STM DocID018909 Rev 8 Sect 39.1 (Unique device ID Register)
+# endif
+# if defined(CONFIG_STM32_STM32F10XX)
+# define UNIQUE_ID 0x1FFFF7E8 //STM DocID13902 Rev 14 Sect 30.2 (Unique device ID Register)
+# endif
#endif
/** Copy the 96bit MCU Unique ID into the provided pointer */
@@ -78,9 +87,24 @@ int mcu_version(char* rev, char** revstr)
case STM32F40x_41x:
*revstr = "STM32F40x";
break;
- case STM32F42x_43x:
- *revstr = "STM32F42x";
- break;
+ case STM32F42x_43x:
+ *revstr = "STM32F42x";
+ break;
+ case STM32F103_LD:
+ *revstr = "STM32F1xx Low";
+ break;
+ case STM32F103_MD:
+ *revstr = "STM32F1xx Med";
+ break;
+ case STM32F103_HD:
+ *revstr = "STM32F1xx Hi";
+ break;
+ case STM32F103_XLD:
+ *revstr = "STM32F1xx XL";
+ break;
+ case STM32F103_CON:
+ *revstr = "STM32F1xx Con";
+ break;
default:
*revstr = "STM32F???";
break;
@@ -104,6 +128,7 @@ int mcu_version(char* rev, char** revstr)
*rev = '3';
break;
default:
+ // todo add rev for 103 - if needed
*rev = '?';
revid = -1;
break;
diff --git a/src/modules/uavcan/module.mk b/src/modules/uavcan/module.mk
index 4f63629a0..f7feeadab 100644
--- a/src/modules/uavcan/module.mk
+++ b/src/modules/uavcan/module.mk
@@ -58,7 +58,8 @@ SRCS += sensors/sensor_bridge.cpp \
# libuavcan
#
include $(PX4_LIB_DIR)uavcan/libuavcan/include.mk
-SRCS += $(LIBUAVCAN_SRC)
+# Use the relitive path to keep the genrated files in the BUILD_DIR
+SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_SRC))
INCLUDE_DIRS += $(LIBUAVCAN_INC)
# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
# because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode.
@@ -68,7 +69,8 @@ override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAV
# libuavcan drivers for STM32
#
include $(PX4_LIB_DIR)uavcan/libuavcan_drivers/stm32/driver/include.mk
-SRCS += $(LIBUAVCAN_STM32_SRC)
+# Use the relitive path to keep the genrated files in the BUILD_DIR
+SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_STM32_SRC))
INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=2
diff --git a/src/modules/uavcannode/.gitignore b/src/modules/uavcannode/.gitignore
new file mode 100644
index 000000000..24fbf171f
--- /dev/null
+++ b/src/modules/uavcannode/.gitignore
@@ -0,0 +1 @@
+./dsdlc_generated/
diff --git a/src/modules/uavcannode/indication_controller.cpp b/src/modules/uavcannode/indication_controller.cpp
new file mode 100644
index 000000000..3ac31a42b
--- /dev/null
+++ b/src/modules/uavcannode/indication_controller.cpp
@@ -0,0 +1,94 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ * Author: Pavel Kirienko <pavel.kirienko@gmail.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 <systemlib/systemlib.h>
+#include "indication_controller.hpp"
+#include <uavcan/equipment/indication/LightsCommand.hpp>
+#include "led.hpp"
+
+namespace
+{
+unsigned self_light_index = 0;
+
+void cb_light_command(const uavcan::ReceivedDataStructure<uavcan::equipment::indication::LightsCommand>& msg)
+{
+ uavcan::uint32_t red = 0;
+ uavcan::uint32_t green = 0;
+ uavcan::uint32_t blue = 0;
+ for (auto& cmd : msg.commands)
+ {
+ if (cmd.light_id == self_light_index)
+ {
+ using uavcan::equipment::indication::RGB565;
+
+ red = uavcan::uint32_t(float(cmd.color.red) *
+ (255.0F / float(RGB565::FieldTypes::red::max())) + 0.5F);
+
+ green = uavcan::uint32_t(float(cmd.color.green) *
+ (255.0F / float(RGB565::FieldTypes::green::max())) + 0.5F);
+
+ blue = uavcan::uint32_t(float(cmd.color.blue) *
+ (255.0F / float(RGB565::FieldTypes::blue::max())) + 0.5F);
+
+ red = uavcan::min<uavcan::uint32_t>(red, 0xFFU);
+ green = uavcan::min<uavcan::uint32_t>(green, 0xFFU);
+ blue = uavcan::min<uavcan::uint32_t>(blue, 0xFFU);
+ }
+
+ if (cmd.light_id == self_light_index+1) {
+ static int c = 0;
+ if (c++ % 100 == 0) {
+ ::syslog(LOG_INFO,"rgb:%d %d %d hz %d\n",red, green, blue, int(cmd.color.red));
+ }
+ rgb_led(red, green, blue, int(cmd.color.red));
+ break;
+ }
+ }
+}
+}
+
+int init_indication_controller(uavcan::INode& node)
+{
+ static uavcan::Subscriber<uavcan::equipment::indication::LightsCommand> sub_light(node);
+
+ self_light_index = 0;
+
+ int res = 0;
+
+ res = sub_light.start(cb_light_command);
+ if (res != 0) {
+ return res;
+ }
+ return 0;
+}
diff --git a/src/modules/uavcannode/indication_controller.hpp b/src/modules/uavcannode/indication_controller.hpp
new file mode 100644
index 000000000..1b78e2872
--- /dev/null
+++ b/src/modules/uavcannode/indication_controller.hpp
@@ -0,0 +1,41 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 PX4 Development Team. All rights reserved.
+ * Author: Pavel Kirienko <pavel.kirienko@gmail.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
+
+#include <uavcan_stm32/uavcan_stm32.hpp>
+
+
+int init_indication_controller(uavcan::INode& node);
+
diff --git a/src/modules/uavcannode/led.cpp b/src/modules/uavcannode/led.cpp
new file mode 100644
index 000000000..0c069471a
--- /dev/null
+++ b/src/modules/uavcannode/led.cpp
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * 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 <nuttx/config.h>
+
+#include <stdint.h>
+
+#include <arch/board/board.h>
+#include "chip/stm32_tim.h"
+
+
+#include "led.hpp"
+
+void rgb_led(int r, int g ,int b, int freqs)
+{
+
+ long fosc = 72000000;
+ long prescale = 2048;
+ long p1s = fosc/prescale;
+ long p0p5s = p1s/2;
+ stm32_tim_channel_t mode = (stm32_tim_channel_t)(STM32_TIM_CH_OUTPWM | STM32_TIM_CH_POLARITY_NEG);
+ static struct stm32_tim_dev_s *tim = 0;
+
+ if (tim == 0) {
+ tim = stm32_tim_init(3);
+ STM32_TIM_SETMODE(tim, STM32_TIM_MODE_UP);
+ STM32_TIM_SETCLOCK(tim, p1s-8);
+ STM32_TIM_SETPERIOD(tim, p1s);
+ STM32_TIM_SETCOMPARE(tim, 1, 0);
+ STM32_TIM_SETCOMPARE(tim, 2, 0);
+ STM32_TIM_SETCOMPARE(tim, 3, 0);
+ STM32_TIM_SETCHANNEL(tim, 1, mode);
+ STM32_TIM_SETCHANNEL(tim, 2, mode);
+ STM32_TIM_SETCHANNEL(tim, 3, mode);
+ }
+
+ long p = freqs==0 ? p1s : p1s/freqs;
+ STM32_TIM_SETPERIOD(tim, p);
+
+ p = freqs==0 ? p1s+1 : p0p5s/freqs;
+
+ STM32_TIM_SETCOMPARE(tim, 1, (r * p)/255 );
+ STM32_TIM_SETCOMPARE(tim, 2, (g * p)/255);
+ STM32_TIM_SETCOMPARE(tim, 3, (b * p)/255);
+}
+
diff --git a/src/modules/uavcannode/led.hpp b/src/modules/uavcannode/led.hpp
new file mode 100644
index 000000000..53d8d653f
--- /dev/null
+++ b/src/modules/uavcannode/led.hpp
@@ -0,0 +1,38 @@
+/****************************************************************************
+ *
+ * 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 <systemlib/visibility.h>
+
+__BEGIN_DECLS
+void rgb_led(int r, int g ,int b, int freqs);
+__END_DECLS
diff --git a/src/modules/uavcannode/module.mk b/src/modules/uavcannode/module.mk
new file mode 100644
index 000000000..75d81120d
--- /dev/null
+++ b/src/modules/uavcannode/module.mk
@@ -0,0 +1,82 @@
+############################################################################
+#
+# Copyright (c) 2013-2015 PX4 Development Team. All rights reserved.
+# Author: Pavel Kirienko <pavel.kirienko@gmail.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.
+#
+############################################################################
+
+#
+# UAVCAN <--> som Simple Sensor
+#
+
+MODULE_COMMAND = uavcannode
+
+MAXOPTIMIZATION = -O3
+
+MODULE_STACKSIZE = 920
+
+
+# Main
+SRCS += uavcannode_main.cpp \
+ uavcannode_clock.cpp \
+ indication_controller.cpp \
+ sim_controller.cpp \
+ led.cpp \
+ resources.cpp \
+ uavcannode_params.c
+
+
+# Sensors
+
+#
+# libuavcan
+#
+include $(PX4_LIB_DIR)uavcan/libuavcan/include.mk
+# Use the relitive path to keep the genrated files in the BUILD_DIR
+SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_SRC))
+INCLUDE_DIRS += $(LIBUAVCAN_INC)
+# Since actual compiler mode is C++11, the library will default to UAVCAN_CPP11, but it will fail to compile
+# because this platform lacks most of the standard library and STL. Hence we need to force C++03 mode.
+override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_CPP_VERSION=UAVCAN_CPP03 -DUAVCAN_NO_ASSERTIONS
+
+#
+# libuavcan drivers for STM32
+#
+include $(PX4_LIB_DIR)uavcan/libuavcan_drivers/stm32/driver/include.mk
+# Use the relitive path to keep the genrated files in the BUILD_DIR
+SRCS += $(subst $(PX4_MODULE_SRC),../../,$(LIBUAVCAN_STM32_SRC))
+INCLUDE_DIRS += $(LIBUAVCAN_STM32_INC)
+override EXTRADEFINES := $(EXTRADEFINES) -DUAVCAN_STM32_NUTTX -DUAVCAN_STM32_NUM_IFACES=1
+
+#
+# Invoke DSDL compiler
+#
+$(info $(shell $(LIBUAVCAN_DSDLC) $(UAVCAN_DSDL_DIR)))
+INCLUDE_DIRS += dsdlc_generated
diff --git a/src/modules/uavcannode/resources.cpp b/src/modules/uavcannode/resources.cpp
new file mode 100644
index 000000000..8383e4794
--- /dev/null
+++ b/src/modules/uavcannode/resources.cpp
@@ -0,0 +1,182 @@
+/****************************************************************************
+ *
+ * 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 <nuttx/config.h>
+#include <nuttx/progmem.h>
+#include <nuttx/compiler.h>
+#include <stdlib.h>
+#include <syslog.h>
+
+#include <nuttx/arch.h>
+
+#include <systemlib/cpuload.h>
+#include "resources.hpp"
+
+#if !defined(CONFIG_NSH_LIBRARY)
+
+static const char *
+tstate_name(const tstate_t s)
+{
+ switch (s) {
+ case TSTATE_TASK_INVALID: return "init";
+
+ case TSTATE_TASK_PENDING: return "PEND";
+ case TSTATE_TASK_READYTORUN: return "READY";
+ case TSTATE_TASK_RUNNING: return "RUN";
+
+ case TSTATE_TASK_INACTIVE: return "inact";
+ case TSTATE_WAIT_SEM: return "w:sem";
+#ifndef CONFIG_DISABLE_SIGNALS
+ case TSTATE_WAIT_SIG: return "w:sig";
+#endif
+#ifndef CONFIG_DISABLE_MQUEUE
+ case TSTATE_WAIT_MQNOTEMPTY: return "w:mqe";
+ case TSTATE_WAIT_MQNOTFULL: return "w:mqf";
+#endif
+#ifdef CONFIG_PAGING
+ case TSTATE_WAIT_PAGEFILL: return "w:pgf";
+#endif
+
+ default:
+ return "ERROR";
+ }
+}
+
+void stack_check(void)
+{
+
+ for (int i = 0; i < CONFIG_MAX_TASKS; i++) {
+
+ if (system_load.tasks[i].tcb) {
+ size_t stack_size = system_load.tasks[i].tcb->adj_stack_size;
+ ssize_t stack_free = 0;
+
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ if (system_load.tasks[i].tcb->pid == 0) {
+ stack_size = (CONFIG_ARCH_INTERRUPTSTACK & ~3);
+ stack_free = up_check_intstack_remain();
+ } else {
+#endif
+ stack_free = up_check_tcbstack_remain(system_load.tasks[i].tcb);
+#if CONFIG_ARCH_INTERRUPTSTACK > 3
+ }
+#endif
+ ::syslog(LOG_INFO, "%4d %*-s %8lld %5u/%5u %3u (%3u) ",
+ system_load.tasks[i].tcb->pid,
+ CONFIG_TASK_NAME_SIZE, system_load.tasks[i].tcb->name,
+ (system_load.tasks[i].total_runtime / 1000),
+ stack_size - stack_free,
+ stack_size,
+ system_load.tasks[i].tcb->sched_priority,
+ system_load.tasks[i].tcb->base_priority);
+
+#if CONFIG_RR_INTERVAL > 0
+ /* print scheduling info with RR time slice */
+ ::syslog(LOG_INFO, " %6d\n", system_load.tasks[i].tcb->timeslice);
+#else
+ /* print task state instead */
+ ::syslog(LOG_INFO," %-6s\n", tstate_name((tstate_t)system_load.tasks[i].tcb->task_state));
+#endif
+ }
+ }
+}
+
+static void free_getprogmeminfo(struct mallinfo * mem)
+{
+ size_t page = 0, stpage = 0xFFFF;
+ size_t pagesize = 0;
+ ssize_t status;
+
+ mem->arena = 0;
+ mem->fordblks = 0;
+ mem->uordblks = 0;
+ mem->mxordblk = 0;
+
+ for (status=0, page=0; status >= 0; page++)
+ {
+ status = up_progmem_ispageerased(page);
+ pagesize = up_progmem_pagesize(page);
+
+ mem->arena += pagesize;
+
+ /* Is this beginning of new free space section */
+
+ if (status == 0)
+ {
+ if (stpage == 0xFFFF) stpage = page;
+ mem->fordblks += pagesize;
+ }
+ else if (status != 0)
+ {
+ mem->uordblks += pagesize;
+
+ if (stpage != 0xFFFF && up_progmem_isuniform())
+ {
+ stpage = page - stpage;
+ if (stpage > (size_t) mem->mxordblk)
+ {
+ mem->mxordblk = stpage;
+ }
+ stpage = 0xFFFF;
+ }
+ }
+ }
+
+ mem->mxordblk *= pagesize;
+}
+
+void free_check(void)
+{
+ struct mallinfo data;
+ struct mallinfo prog;
+
+#ifdef CONFIG_CAN_PASS_STRUCTS
+ data = mallinfo();
+#else
+ (void)mallinfo(&data);
+#endif
+
+ free_getprogmeminfo(&prog);
+
+
+ ::syslog(LOG_INFO," total used free largest\n");
+
+ ::syslog(LOG_INFO,"Data: %11d%11d%11d%11d\n",
+ data.arena, data.uordblks, data.fordblks, data.mxordblk);
+
+ ::syslog(LOG_INFO,"Prog: %11d%11d%11d%11d\n",
+ prog.arena, prog.uordblks, prog.fordblks, prog.mxordblk);
+}
+#endif /* CONFIG_NSH_LIBRARY */
+
diff --git a/src/modules/uavcannode/resources.hpp b/src/modules/uavcannode/resources.hpp
new file mode 100644
index 000000000..25e835f23
--- /dev/null
+++ b/src/modules/uavcannode/resources.hpp
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * 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 <systemlib/visibility.h>
+
+__BEGIN_DECLS
+#if defined(CONFIG_NSH_LIBRARY)
+#define stack_check()
+#define free_check() free_main(0,0)
+#else
+void stack_check(void);
+void free_check(void);
+#endif
+__END_DECLS
diff --git a/src/modules/uavcannode/sim_controller.cpp b/src/modules/uavcannode/sim_controller.cpp
new file mode 100644
index 000000000..bd084d3f7
--- /dev/null
+++ b/src/modules/uavcannode/sim_controller.cpp
@@ -0,0 +1,147 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 PX4 Development Team. All rights reserved.
+ * Author: Pavel Kirienko <pavel.kirienko@gmail.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.
+ *
+ ****************************************************************************/
+#include <nuttx/config.h>
+
+#include <syslog.h>
+#include <systemlib/systemlib.h>
+
+#include "sim_controller.hpp"
+#include <uavcan/equipment/esc/RawCommand.hpp>
+#include <uavcan/equipment/esc/RPMCommand.hpp>
+#include <uavcan/equipment/esc/Status.hpp>
+#include "led.hpp"
+
+
+uavcan::Publisher<uavcan::equipment::esc::Status>* pub_status;
+namespace {
+unsigned self_index = 0;
+int rpm = 0;
+
+static void cb_raw_command(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::RawCommand>& msg)
+{
+ if (msg.cmd.size() <= self_index) {
+ rgb_led(0,0,0,0);
+ return;
+ }
+
+ const float scaled = msg.cmd[self_index] / float(uavcan::equipment::esc::RawCommand::FieldTypes::cmd::RawValueType::max());
+
+ static int c = 0;
+ if (c++ % 100 == 0) {
+ ::syslog(LOG_INFO,"scaled:%d\n",(int)scaled);
+ }
+ if (scaled > 0) {
+ } else {
+ }
+}
+
+static void cb_rpm_command(const uavcan::ReceivedDataStructure<uavcan::equipment::esc::RPMCommand>& msg)
+{
+ if (msg.rpm.size() <= self_index) {
+ return;
+ }
+
+ rpm = msg.rpm[self_index];
+ static int c = 0;
+ if (c++ % 100 == 0) {
+ ::syslog(LOG_INFO,"rpm:%d\n",rpm);
+ }
+
+ if (rpm > 0) {
+ rgb_led(255,0,0,rpm);
+ } else {
+ rgb_led(0,0,0,0);
+ }
+}
+
+void cb_10Hz(const uavcan::TimerEvent& event)
+{
+ uavcan::equipment::esc::Status msg;
+
+ msg.esc_index = self_index;
+ msg.rpm = rpm;
+ msg.voltage = 3.3F;
+ msg.current = 0.001F;
+ msg.temperature = 24.0F;
+ msg.power_rating_pct = static_cast<unsigned>(.5F * 100 + 0.5F);
+ msg.error_count = 0;
+
+ if (rpm != 0) {
+ // Lower the publish rate to 1Hz if the motor is not running
+ static uavcan::MonotonicTime prev_pub_ts;
+ if ((event.scheduled_time - prev_pub_ts).toMSec() >= 990) {
+ prev_pub_ts = event.scheduled_time;
+ pub_status->broadcast(msg);
+ }
+ } else {
+ pub_status->broadcast(msg);
+ }
+}
+
+}
+int init_sim_controller(uavcan::INode& node)
+{
+
+ typedef void (*cb)(const uavcan::TimerEvent&);
+ static uavcan::Subscriber<uavcan::equipment::esc::RawCommand> sub_raw_command(node);
+ static uavcan::Subscriber<uavcan::equipment::esc::RPMCommand> sub_rpm_command(node);
+ static uavcan::TimerEventForwarder<cb> timer_10hz(node);
+
+ self_index = 0;
+
+ int res = 0;
+
+ res = sub_raw_command.start(cb_raw_command);
+ if (res != 0) {
+ return res;
+ }
+
+ res = sub_rpm_command.start(cb_rpm_command);
+ if (res != 0) {
+ return res;
+ }
+
+ pub_status = new uavcan::Publisher<uavcan::equipment::esc::Status>(node);
+ res = pub_status->init();
+ if (res != 0) {
+ return res;
+ }
+
+ timer_10hz.setCallback(&cb_10Hz);
+ timer_10hz.startPeriodic(uavcan::MonotonicDuration::fromMSec(100));
+
+ return 0;
+}
+
diff --git a/src/modules/uavcannode/sim_controller.hpp b/src/modules/uavcannode/sim_controller.hpp
new file mode 100644
index 000000000..06f5312cd
--- /dev/null
+++ b/src/modules/uavcannode/sim_controller.hpp
@@ -0,0 +1,41 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 PX4 Development Team. All rights reserved.
+ * Author: Pavel Kirienko <pavel.kirienko@gmail.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
+
+#include <uavcan_stm32/uavcan_stm32.hpp>
+
+int init_sim_controller(uavcan::INode& node);
+
diff --git a/src/modules/uavcannode/uavcannode_clock.cpp b/src/modules/uavcannode/uavcannode_clock.cpp
new file mode 100644
index 000000000..fe8ba406a
--- /dev/null
+++ b/src/modules/uavcannode/uavcannode_clock.cpp
@@ -0,0 +1,81 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2014 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 <uavcan_stm32/uavcan_stm32.hpp>
+#include <drivers/drv_hrt.h>
+
+/**
+ * @file uavcan_clock.cpp
+ *
+ * Implements a clock for the CAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+namespace uavcan_stm32
+{
+namespace clock
+{
+
+uavcan::MonotonicTime getMonotonic()
+{
+ return uavcan::MonotonicTime::fromUSec(hrt_absolute_time());
+}
+
+uavcan::UtcTime getUtc()
+{
+ return uavcan::UtcTime();
+}
+
+void adjustUtc(uavcan::UtcDuration adjustment)
+{
+ (void)adjustment;
+}
+
+uavcan::uint64_t getUtcUSecFromCanInterrupt();
+
+uavcan::uint64_t getUtcUSecFromCanInterrupt()
+{
+ return 0;
+}
+
+} // namespace clock
+
+SystemClock &SystemClock::instance()
+{
+ static SystemClock inst;
+ return inst;
+}
+
+}
+
diff --git a/src/modules/uavcannode/uavcannode_main.cpp b/src/modules/uavcannode/uavcannode_main.cpp
new file mode 100644
index 000000000..774441c02
--- /dev/null
+++ b/src/modules/uavcannode/uavcannode_main.cpp
@@ -0,0 +1,467 @@
+/****************************************************************************
+ *
+ *
+ * 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/config.h>
+#include <nuttx/clock.h>
+
+#include <cstdlib>
+#include <cstring>
+#include <fcntl.h>
+#include <systemlib/err.h>
+#include <systemlib/systemlib.h>
+#include <systemlib/param/param.h>
+#include <systemlib/mixer/mixer.h>
+#include <systemlib/board_serial.h>
+#include <systemlib/scheduling_priorities.h>
+#include <version/version.h>
+#include <arch/board/board.h>
+#include <arch/chip/chip.h>
+
+#include <drivers/drv_hrt.h>
+#include <drivers/drv_pwm_output.h>
+
+#include "uavcannode_main.hpp"
+#include "indication_controller.hpp"
+#include "sim_controller.hpp"
+#include "resources.hpp"
+
+/**
+ * @file uavcan_main.cpp
+ *
+ * Implements basic functinality of UAVCAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+#define RESOURCE_DEBUG
+#if defined(RESOURCE_DEBUG)
+#define resources() free_check(); \
+ stack_check();
+#else
+#define resources()
+#endif
+/*
+ * UavcanNode
+ */
+UavcanNode *UavcanNode::_instance;
+
+UavcanNode::UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock) :
+ CDev("uavcan", UAVCAN_DEVICE_PATH),
+ _node(can_driver, system_clock),
+ _node_mutex()
+{
+ const int res = pthread_mutex_init(&_node_mutex, nullptr);
+ if (res < 0) {
+ std::abort();
+ }
+
+}
+
+UavcanNode::~UavcanNode()
+{
+ if (_task != -1) {
+ /* tell the task we want it to go away */
+ _task_should_exit = true;
+
+ unsigned i = 10;
+
+ do {
+ /* wait 5ms - it should wake every 10ms or so worst-case */
+ ::usleep(5000);
+
+ /* if we have given up, kill it */
+ if (--i == 0) {
+ task_delete(_task);
+ break;
+ }
+
+ } while (_task != -1);
+ }
+
+ _instance = nullptr;
+
+}
+
+int UavcanNode::start(uavcan::NodeID node_id, uint32_t bitrate)
+{
+
+
+ if (_instance != nullptr) {
+ warnx("Already started");
+ return -1;
+ }
+
+ /*
+ * GPIO config.
+ * Forced pull up on CAN2 is required for Pixhawk v1 where the second interface lacks a transceiver.
+ * If no transceiver is connected, the RX pin will float, occasionally causing CAN controller to
+ * fail during initialization.
+ */
+ stm32_configgpio(GPIO_CAN1_RX);
+ stm32_configgpio(GPIO_CAN1_TX);
+#if defined(GPIO_CAN2_RX)
+ stm32_configgpio(GPIO_CAN2_RX | GPIO_PULLUP);
+ stm32_configgpio(GPIO_CAN2_TX);
+#endif
+ /*
+ * CAN driver init
+ */
+ static CanInitHelper can;
+ static bool can_initialized = false;
+
+ if (!can_initialized) {
+ const int can_init_res = can.init(bitrate);
+
+ if (can_init_res < 0) {
+ warnx("CAN driver init failed %i", can_init_res);
+ return can_init_res;
+ }
+
+ can_initialized = true;
+ }
+
+ /*
+ * Node init
+ */
+ _instance = new UavcanNode(can.driver, uavcan_stm32::SystemClock::instance());
+
+ if (_instance == nullptr) {
+ warnx("Out of memory");
+ return -1;
+ }
+
+ resources();
+ const int node_init_res = _instance->init(node_id);
+ resources();
+
+ if (node_init_res < 0) {
+ delete _instance;
+ _instance = nullptr;
+ warnx("Node init failed %i", node_init_res);
+ return node_init_res;
+ }
+
+ /*
+ * Start the task. Normally it should never exit.
+ */
+ static auto run_trampoline = [](int, char *[]) {return UavcanNode::_instance->run();};
+ _instance->_task = task_spawn_cmd("uavcan", SCHED_DEFAULT, SCHED_PRIORITY_ACTUATOR_OUTPUTS, StackSize,
+ static_cast<main_t>(run_trampoline), nullptr);
+
+ if (_instance->_task < 0) {
+ warnx("start failed: %d", errno);
+ return -errno;
+ }
+
+ return OK;
+}
+
+void UavcanNode::fill_node_info()
+{
+ /* software version */
+ uavcan::protocol::SoftwareVersion swver;
+
+ // Extracting the first 8 hex digits of FW_GIT and converting them to int
+ char fw_git_short[9] = {};
+ std::memmove(fw_git_short, FW_GIT, 8);
+ assert(fw_git_short[8] == '\0');
+ char *end = nullptr;
+ swver.vcs_commit = std::strtol(fw_git_short, &end, 16);
+ swver.optional_field_mask |= swver.OPTIONAL_FIELD_MASK_VCS_COMMIT;
+
+ warnx("SW version vcs_commit: 0x%08x", unsigned(swver.vcs_commit));
+
+ _node.setSoftwareVersion(swver);
+
+ /* hardware version */
+ uavcan::protocol::HardwareVersion hwver;
+
+ hwver.major = 1;
+
+ uint8_t udid[12] = {}; // Someone seems to love magic numbers
+ get_board_serial(udid);
+ uavcan::copy(udid, udid + sizeof(udid), hwver.unique_id.begin());
+
+ _node.setHardwareVersion(hwver);
+}
+
+int UavcanNode::init(uavcan::NodeID node_id)
+{
+ int ret = -1;
+
+ // Do regular cdev init
+ ret = CDev::init();
+
+ if (ret != OK) {
+ return ret;
+ }
+
+ _node.setName("org.pixhawk.cannode");
+
+ _node.setNodeID(node_id);
+
+ fill_node_info();
+
+ return _node.start();
+}
+
+
+/*
+ * Restart handler
+ */
+class RestartRequestHandler: public uavcan::IRestartRequestHandler
+{
+ bool handleRestartRequest(uavcan::NodeID request_source) override
+ {
+ ::syslog(LOG_INFO,"UAVCAN: Restarting by request from %i\n", int(request_source.get()));
+ ::usleep(20*1000*1000);
+ systemreset(false);
+ return true; // Will never be executed BTW
+ }
+} restart_request_handler;
+
+void UavcanNode::node_spin_once()
+{
+ const int spin_res = _node.spin(uavcan::MonotonicTime());
+ if (spin_res < 0) {
+ warnx("node spin error %i", spin_res);
+ }
+}
+
+/*
+ add a fd to the list of polled events. This assumes you want
+ POLLIN for now.
+ */
+int UavcanNode::add_poll_fd(int fd)
+{
+ int ret = _poll_fds_num;
+ if (_poll_fds_num >= UAVCAN_NUM_POLL_FDS) {
+ errx(1, "uavcan: too many poll fds, exiting");
+ }
+ _poll_fds[_poll_fds_num] = ::pollfd();
+ _poll_fds[_poll_fds_num].fd = fd;
+ _poll_fds[_poll_fds_num].events = POLLIN;
+ _poll_fds_num += 1;
+ return ret;
+}
+
+
+int UavcanNode::run()
+{
+
+ get_node().setRestartRequestHandler(&restart_request_handler);
+
+ while (init_indication_controller(get_node()) < 0) {
+ ::syslog(LOG_INFO,"UAVCAN: Indication controller init failed\n");
+ ::sleep(1);
+ }
+
+ while (init_sim_controller(get_node()) < 0) {
+ ::syslog(LOG_INFO,"UAVCAN: sim controller init failed\n");
+ ::sleep(1);
+ }
+
+ (void)pthread_mutex_lock(&_node_mutex);
+
+ const unsigned PollTimeoutMs = 50;
+
+ const int busevent_fd = ::open(uavcan_stm32::BusEvent::DevName, 0);
+ if (busevent_fd < 0)
+ {
+ warnx("Failed to open %s", uavcan_stm32::BusEvent::DevName);
+ _task_should_exit = true;
+ }
+
+
+ _node.setStatusOk();
+
+ /*
+ * This event is needed to wake up the thread on CAN bus activity (RX/TX/Error).
+ * Please note that with such multiplexing it is no longer possible to rely only on
+ * the value returned from poll() to detect whether actuator control has timed out or not.
+ * Instead, all ORB events need to be checked individually (see below).
+ */
+ add_poll_fd(busevent_fd);
+
+ uint32_t start_tick = clock_systimer();
+
+ while (!_task_should_exit) {
+ // Mutex is unlocked while the thread is blocked on IO multiplexing
+ (void)pthread_mutex_unlock(&_node_mutex);
+
+ const int poll_ret = ::poll(_poll_fds, _poll_fds_num, PollTimeoutMs);
+
+
+ (void)pthread_mutex_lock(&_node_mutex);
+
+ node_spin_once(); // Non-blocking
+
+
+ // this would be bad...
+ if (poll_ret < 0) {
+ log("poll error %d", errno);
+ continue;
+ } else {
+ // Do Somthing
+ }
+ if (clock_systimer() - start_tick > TICK_PER_SEC) {
+ start_tick = clock_systimer();
+ resources();
+ }
+
+ }
+
+ teardown();
+ warnx("exiting.");
+
+ exit(0);
+}
+
+int
+UavcanNode::teardown()
+{
+ return 0;
+}
+
+
+
+int
+UavcanNode::ioctl(file *filp, int cmd, unsigned long arg)
+{
+ int ret = OK;
+
+ lock();
+
+ switch (cmd) {
+
+
+
+ default:
+ ret = -ENOTTY;
+ break;
+ }
+
+ unlock();
+
+ if (ret == -ENOTTY) {
+ ret = CDev::ioctl(filp, cmd, arg);
+ }
+
+ return ret;
+}
+
+void
+UavcanNode::print_info()
+{
+ if (!_instance) {
+ warnx("not running, start first");
+ }
+
+ (void)pthread_mutex_lock(&_node_mutex);
+
+
+ (void)pthread_mutex_unlock(&_node_mutex);
+}
+
+/*
+ * App entry point
+ */
+static void print_usage()
+{
+ warnx("usage: \n"
+ "\tuavcannode {start|status|stop|arm|disarm}");
+}
+
+extern "C" __EXPORT int uavcannode_start(int argc, char *argv[]);
+
+int uavcannode_start(int argc, char *argv[])
+{
+
+ app_archinitialize();
+
+ resources();
+ // Node ID
+ int32_t node_id = 0;
+ (void)param_get(param_find("UAVCAN_NODE_ID"), &node_id);
+
+ if (node_id < 0 || node_id > uavcan::NodeID::Max || !uavcan::NodeID(node_id).isUnicast()) {
+ warnx("Invalid Node ID %i", node_id);
+ ::exit(1);
+ }
+
+ // CAN bitrate
+ int32_t bitrate = 0;
+ (void)param_get(param_find("UAVCAN_BITRATE"), &bitrate);
+
+ // Start
+ warnx("Node ID %u, bitrate %u", node_id, bitrate);
+ int rv = UavcanNode::start(node_id, bitrate);
+ resources();
+ ::sleep(1);
+ return rv;
+}
+
+extern "C" __EXPORT int uavcannode_main(int argc, char *argv[]);
+int uavcannode_main(int argc, char *argv[])
+{
+ if (argc < 2) {
+ print_usage();
+ ::exit(1);
+ }
+
+ if (!std::strcmp(argv[1], "start")) {
+
+ if (UavcanNode::instance()) {
+ errx(1, "already started");
+ }
+ return uavcannode_start(argc, argv);
+ }
+
+ /* commands below require the app to be started */
+ UavcanNode *const inst = UavcanNode::instance();
+
+ if (!inst) {
+ errx(1, "application not running");
+ }
+
+ if (!std::strcmp(argv[1], "status") || !std::strcmp(argv[1], "info")) {
+ inst->print_info();
+ ::exit(0);
+ }
+
+ if (!std::strcmp(argv[1], "stop")) {
+ delete inst;
+ ::exit(0);
+ }
+
+ print_usage();
+ ::exit(1);
+}
diff --git a/src/modules/uavcannode/uavcannode_main.hpp b/src/modules/uavcannode/uavcannode_main.hpp
new file mode 100644
index 000000000..d35c48c90
--- /dev/null
+++ b/src/modules/uavcannode/uavcannode_main.hpp
@@ -0,0 +1,101 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+#include <nuttx/config.h>
+#include <uavcan_stm32/uavcan_stm32.hpp>
+#include <drivers/device/device.h>
+
+/**
+ * @file uavcan_main.hpp
+ *
+ * Defines basic functinality of UAVCAN node.
+ *
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#define NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN 1
+#define UAVCAN_DEVICE_PATH "/dev/uavcan/node"
+
+// we add two to allow for actuator_direct and busevent
+#define UAVCAN_NUM_POLL_FDS (NUM_ACTUATOR_CONTROL_GROUPS_UAVCAN+2)
+
+/**
+ * A UAVCAN node.
+ */
+class UavcanNode : public device::CDev
+{
+ static constexpr unsigned MemPoolSize = 2800; ///< Refer to the libuavcan manual to learn why
+ static constexpr unsigned RxQueueLenPerIface = 64;
+ static constexpr unsigned StackSize = 1064;
+
+public:
+ typedef uavcan::Node<MemPoolSize> Node;
+ typedef uavcan_stm32::CanInitHelper<RxQueueLenPerIface> CanInitHelper;
+
+ UavcanNode(uavcan::ICanDriver &can_driver, uavcan::ISystemClock &system_clock);
+
+ virtual ~UavcanNode();
+
+ virtual int ioctl(file *filp, int cmd, unsigned long arg);
+
+ static int start(uavcan::NodeID node_id, uint32_t bitrate);
+
+ Node& get_node() { return _node; }
+
+ int teardown();
+
+ void print_info();
+
+ static UavcanNode* instance() { return _instance; }
+
+private:
+ void fill_node_info();
+ int init(uavcan::NodeID node_id);
+ void node_spin_once();
+ int run();
+ int add_poll_fd(int fd); ///< add a fd to poll list, returning index into _poll_fds[]
+
+
+ int _task = -1; ///< handle to the OS task
+ bool _task_should_exit = false; ///< flag to indicate to tear down the CAN driver
+
+ static UavcanNode *_instance; ///< singleton pointer
+ Node _node; ///< library instance
+ pthread_mutex_t _node_mutex;
+
+ pollfd _poll_fds[UAVCAN_NUM_POLL_FDS] = {};
+ unsigned _poll_fds_num = 0;
+
+};
diff --git a/src/modules/uavcannode/uavcannode_params.c b/src/modules/uavcannode/uavcannode_params.c
new file mode 100644
index 000000000..e6ea8a8fb
--- /dev/null
+++ b/src/modules/uavcannode/uavcannode_params.c
@@ -0,0 +1,73 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2014 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @author Pavel Kirienko <pavel.kirienko@gmail.com>
+ */
+
+#include <nuttx/config.h>
+#include <systemlib/param/param.h>
+
+/**
+ * Enable UAVCAN.
+ *
+ * Enables support for UAVCAN-interfaced actuators and sensors.
+ *
+ * @min 0
+ * @max 1
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_ENABLE, 0);
+
+/**
+ * UAVCAN Node ID.
+ *
+ * Read the specs at http://uavcan.org to learn more about Node ID.
+ *
+ * @min 1
+ * @max 125
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_NODE_ID, 1);
+
+/**
+ * UAVCAN CAN bus bitrate.
+ *
+ * @min 20000
+ * @max 1000000
+ * @group UAVCAN
+ */
+PARAM_DEFINE_INT32(UAVCAN_BITRATE, 1000000);
+
+
+