aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorDavid Sidrane <david_s5@nscdg.com>2015-03-24 14:12:46 -1000
committerDavid Sidrane <david_s5@nscdg.com>2015-03-24 14:12:46 -1000
commitc532ec57249aabdf250bdeeeb2b016fdf98a58d7 (patch)
tree734b6b8fc978135f44c7f9fcdcda31566eaf9284
parent4acc12903d050ed0116f19e2ede9e12251d5d494 (diff)
downloadpx4-firmware-c532ec57249aabdf250bdeeeb2b016fdf98a58d7.tar.gz
px4-firmware-c532ec57249aabdf250bdeeeb2b016fdf98a58d7.tar.bz2
px4-firmware-c532ec57249aabdf250bdeeeb2b016fdf98a58d7.zip
Initail Commit PX4 CAN Node on Olimexino-STM32
-rw-r--r--Images/px4cannode-v1.prototype12
-rw-r--r--makefiles/board_px4cannode-v1.mk12
-rw-r--r--makefiles/config_px4cannode-v1_default.mk37
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk4
-rw-r--r--nuttx-configs/px4cannode-v1/Kconfig22
-rwxr-xr-xnuttx-configs/px4cannode-v1/include/README.txt5
-rwxr-xr-xnuttx-configs/px4cannode-v1/include/board.h223
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/Make.defs172
-rw-r--r--nuttx-configs/px4cannode-v1/nsh/defconfig1149
-rwxr-xr-xnuttx-configs/px4cannode-v1/nsh/setenv.sh80
-rw-r--r--nuttx-configs/px4cannode-v1/scripts/ld.script116
-rw-r--r--nuttx-configs/px4cannode-v1/src/Makefile84
-rw-r--r--nuttx-configs/px4cannode-v1/src/empty.c4
-rw-r--r--src/drivers/boards/px4cannode-v1/board_config.h298
-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.c191
-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/lib/version/version.h4
21 files changed, 3135 insertions, 1 deletions
diff --git a/Images/px4cannode-v1.prototype b/Images/px4cannode-v1.prototype
new file mode 100644
index 000000000..2f7e83edc
--- /dev/null
+++ b/Images/px4cannode-v1.prototype
@@ -0,0 +1,12 @@
+{
+ "board_id": 21,
+ "magic": "ESCFWv1",
+ "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/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_default.mk b/makefiles/config_px4cannode-v1_default.mk
new file mode 100644
index 000000000..913b6eb53
--- /dev/null
+++ b/makefiles/config_px4cannode-v1_default.mk
@@ -0,0 +1,37 @@
+#
+# 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/nshterm
+MODULES += systemcmds/ver
+
+#
+# Library modules
+#
+MODULES += modules/systemlib
+
+
+#
+# Unit tests
+#
+#MODULES += modules/unit_test
+#MODULES += modules/commander/commander_tests
+
+#
+# Demo apps
+#
+
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
index 853885a3b..b1ef31a87 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 \
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/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..ce153dc4c
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/include/board.h
@@ -0,0 +1,223 @@
+/************************************************************************************
+ * 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.
+ */
+
+/************************************************************************************
+ * 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);
+
+#undef EXTERN
+#if defined(__cplusplus)
+}
+#endif
+
+/************************************************************************************
+ * 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
+
+#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..8860661ce
--- /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..f03f8c324
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/nsh/defconfig
@@ -0,0 +1,1149 @@
+#
+# 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=y
+# 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
+CONFIG_CAN_EXTID=y
+CONFIG_CAN1_BAUD=250000
+CONFIG_CAN_TSEG1=6
+CONFIG_CAN_TSEG2=7
+CONFIG_CAN_LOOPBACK=y
+
+#
+# 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=y
+# 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=y
+
+#
+# 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=340
+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=1
+CONFIG_START_DAY=1
+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 is not set
+
+#
+# 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=5
+CONFIG_NAME_MAX=8
+CONFIG_PRIORITY_INHERITANCE=y
+CONFIG_SEM_PREALLOCHOLDERS=16
+CONFIG_SEM_NNESTPRIO=16
+
+#
+# RTOS hooks
+#
+CONFIG_BOARD_INITIALIZE=y
+# CONFIG_BOARD_INITTHREAD is not set
+# CONFIG_SCHED_STARTHOOK is not set
+# CONFIG_SCHED_ATEXIT is not set
+# CONFIG_SCHED_ONEXIT is not set
+
+#
+# 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=32
+
+#
+# Work Queue Support
+#
+CONFIG_SCHED_WORKQUEUE=y
+CONFIG_SCHED_HPWORK=y
+CONFIG_SCHED_HPWORKPRIORITY=224
+CONFIG_SCHED_HPWORKPERIOD=100000
+CONFIG_SCHED_HPWORKSTACKSIZE=758
+# CONFIG_SCHED_LPWORK is not set
+
+#
+# Stack and heap information
+#
+CONFIG_IDLETHREAD_STACKSIZE=300
+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 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=y
+CONFIG_CAN_FIFOSIZE=8
+CONFIG_CAN_NPENDINGRTR=4
+# 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=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_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=768
+
+#
+# Examples
+#
+# CONFIG_EXAMPLES_BUTTONS is not set
+CONFIG_EXAMPLES_CAN=y
+# 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 is not set
+# 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=40
+CONFIG_NSH_DISABLE_SEMICOLON=y
+# CONFIG_NSH_CMDPARMS is not set
+CONFIG_NSH_MAXARGUMENTS=6
+# 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 is not set
+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 is not set
+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 is not set
+CONFIG_NSH_DISABLE_MKDIR=y
+CONFIG_NSH_DISABLE_MKFIFO=y
+CONFIG_NSH_DISABLE_MKRD=y
+# CONFIG_NSH_DISABLE_MH is not set
+CONFIG_NSH_DISABLE_MOUNT=y
+CONFIG_NSH_DISABLE_MV=y
+# CONFIG_NSH_DISABLE_MW is not set
+# CONFIG_NSH_DISABLE_PS is not set
+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 is not set
+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 is not set
+
+#
+# Configure Command Options
+#
+CONFIG_NSH_CODECS_BUFSIZE=0
+# CONFIG_NSH_CMDOPT_HEXDUMP is not set
+CONFIG_NSH_FILEIOSIZE=128
+
+#
+# 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/ld.script b/nuttx-configs/px4cannode-v1/scripts/ld.script
new file mode 100644
index 000000000..ceef71e8c
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/scripts/ld.script
@@ -0,0 +1,116 @@
+/****************************************************************************
+ * 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(_stext)
+SECTIONS
+{
+ .text : {
+ _stext = ABSOLUTE(.);
+ *(.vectors)
+ *(.text .text.*)
+ *(.fixup)
+ *(.gnu.warning)
+ *(.rodata .rodata.*)
+ *(.gnu.linkonce.t.*)
+ *(.glue_7)
+ *(.glue_7t)
+ *(.got)
+ *(.gcc_except_table)
+ *(.gnu.linkonce.r.*)
+ _etext = ABSOLUTE(.);
+ } > flash
+
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ *(.init_array .init_array.*)
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ .ARM.extab : {
+ *(.ARM.extab*)
+ } > flash
+
+ __exidx_start = ABSOLUTE(.);
+ .ARM.exidx : {
+ *(.ARM.exidx*)
+ } > flash
+ __exidx_end = ABSOLUTE(.);
+
+ _eronly = ABSOLUTE(.);
+
+ .data : {
+ _sdata = ABSOLUTE(.);
+ *(.data .data.*)
+ *(.gnu.linkonce.d.*)
+ CONSTRUCTORS
+ _edata = ABSOLUTE(.);
+ } > sram AT > flash
+
+ .bss : {
+ _sbss = ABSOLUTE(.);
+ *(.bss .bss.*)
+ *(.gnu.linkonce.b.*)
+ *(COMMON)
+ _ebss = ABSOLUTE(.);
+ } > sram
+
+ /* Stabs debugging sections. */
+ .stab 0 : { *(.stab) }
+ .stabstr 0 : { *(.stabstr) }
+ .stab.excl 0 : { *(.stab.excl) }
+ .stab.exclstr 0 : { *(.stab.exclstr) }
+ .stab.index 0 : { *(.stab.index) }
+ .stab.indexstr 0 : { *(.stab.indexstr) }
+ .comment 0 : { *(.comment) }
+ .debug_abbrev 0 : { *(.debug_abbrev) }
+ .debug_info 0 : { *(.debug_info) }
+ .debug_line 0 : { *(.debug_line) }
+ .debug_pubnames 0 : { *(.debug_pubnames) }
+ .debug_aranges 0 : { *(.debug_aranges) }
+}
diff --git a/nuttx-configs/px4cannode-v1/src/Makefile b/nuttx-configs/px4cannode-v1/src/Makefile
new file mode 100644
index 000000000..74313880e
--- /dev/null
+++ b/nuttx-configs/px4cannode-v1/src/Makefile
@@ -0,0 +1,84 @@
+############################################################################
+# nuttx-configs/px4cannode-v1//src/Makefile
+#
+# Copyright (C) 2015 Gregory Nutt. All rights reserved.
+# Author: Gregory Nutt <spudmonkey@racsa.co.cr>
+#
+# 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))
+
+CSRCS = empty.c
+
+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..ace900866
--- /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/src/drivers/boards/px4cannode-v1/board_config.h b/src/drivers/boards/px4cannode-v1/board_config.h
new file mode 100644
index 000000000..ddf5603b6
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/board_config.h
@@ -0,0 +1,298 @@
+/****************************************************************************
+ *
+ * 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
+ ************************************************************************************/
+#define UDID_START 0x1FFF7A10
+
+#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
+
+/************************************************************************************
+ * 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/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..724394211
--- /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..92f09d0cc
--- /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.
+ *
+ ************************************************************************************/
+
+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..b1c3e71a5
--- /dev/null
+++ b/src/drivers/boards/px4cannode-v1/px4cannode_init.c
@@ -0,0 +1,191 @@
+/****************************************************************************
+ *
+ * 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
+
+/* 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();
+ board_spiinitialize();
+
+}
+
+
+__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
+
+__EXPORT int nsh_archinitialize(void)
+{
+ 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..fe765d653
--- /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..0277098b9
--- /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/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_ */