aboutsummaryrefslogtreecommitdiff
path: root/nuttx-configs/px4fmu-v1
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-08-02 23:11:04 -0700
committerpx4dev <px4@purgatory.org>2013-08-02 23:11:04 -0700
commitecc7bc5bca40e9d5e0a7271105dea9b3441af0a8 (patch)
tree2dbe20984da5cc24405e00ab43a88664e8fdc757 /nuttx-configs/px4fmu-v1
parent9d6ec6b3655fcd902be7a7fe4f2a24033c714afb (diff)
downloadpx4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.tar.gz
px4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.tar.bz2
px4-firmware-ecc7bc5bca40e9d5e0a7271105dea9b3441af0a8.zip
Clean out unused trash from the NuttX configs.
Diffstat (limited to 'nuttx-configs/px4fmu-v1')
-rw-r--r--nuttx-configs/px4fmu-v1/Kconfig21
-rw-r--r--nuttx-configs/px4fmu-v1/common/Make.defs184
-rw-r--r--nuttx-configs/px4fmu-v1/common/ld.script149
-rw-r--r--nuttx-configs/px4fmu-v1/nsh/Make.defs178
-rw-r--r--nuttx-configs/px4fmu-v1/ostest/Make.defs122
-rw-r--r--nuttx-configs/px4fmu-v1/ostest/defconfig583
-rwxr-xr-xnuttx-configs/px4fmu-v1/ostest/setenv.sh75
-rw-r--r--nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld129
-rw-r--r--nuttx-configs/px4fmu-v1/scripts/ld.script58
-rwxr-xr-xnuttx-configs/px4fmu-v1/tools/px_mkfw.py110
-rwxr-xr-xnuttx-configs/px4fmu-v1/tools/px_uploader.py416
-rwxr-xr-xnuttx-configs/px4fmu-v1/tools/upload.sh27
12 files changed, 219 insertions, 1833 deletions
diff --git a/nuttx-configs/px4fmu-v1/Kconfig b/nuttx-configs/px4fmu-v1/Kconfig
deleted file mode 100644
index edbafa06f..000000000
--- a/nuttx-configs/px4fmu-v1/Kconfig
+++ /dev/null
@@ -1,21 +0,0 @@
-#
-# For a description of the syntax of this configuration file,
-# see misc/tools/kconfig-language.txt.
-#
-
-if ARCH_BOARD_PX4FMU_V1
-
-config HRT_TIMER
- bool "High resolution timer support"
- default y
- ---help---
- Enable high resolution timer for PPM capture and system clocks.
-
-config HRT_PPM
- bool "PPM input capture"
- default y
- depends on HRT_TIMER
- ---help---
- Enable PPM input capture via HRT (for CPPM / PPM sum RC inputs)
-
-endif
diff --git a/nuttx-configs/px4fmu-v1/common/Make.defs b/nuttx-configs/px4fmu-v1/common/Make.defs
deleted file mode 100644
index 756286ccb..000000000
--- a/nuttx-configs/px4fmu-v1/common/Make.defs
+++ /dev/null
@@ -1,184 +0,0 @@
-############################################################################
-# configs/px4fmu/common/Make.defs
-#
-# Copyright (C) 2011 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.
-#
-############################################################################
-
-#
-# Generic Make.defs for the PX4FMU
-# Do not specify/use this file directly - it is included by config-specific
-# Make.defs in the per-config directories.
-#
-
-include ${TOPDIR}/tools/Config.mk
-
-#
-# We only support building with the ARM bare-metal toolchain from
-# https://launchpad.net/gcc-arm-embedded on Windows, Linux or Mac OS.
-#
-CONFIG_ARMV7M_TOOLCHAIN := GNU_EABI
-
-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 = -O3
-ARCHCPUFLAGS = -mcpu=cortex-m4 \
- -mthumb \
- -march=armv7e-m \
- -mfpu=fpv4-sp-d16 \
- -mfloat-abi=hard
-
-
-# enable precise stack overflow tracking
-INSTRUMENTATIONDEFINES = -finstrument-functions \
- -ffixed-r10
-
-# pull in *just* libm from the toolchain ... this is grody
-LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
-EXTRA_LIBS += $(LIBM)
-
-# 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)/common/$(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)/common/$(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)/common/$(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 \
- -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 \
- -Wunsuffixed-float-constants
-ARCHWARNINGSXX = $(ARCHWARNINGS) \
- -Wno-psabi
-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/px4fmu-v1/common/ld.script b/nuttx-configs/px4fmu-v1/common/ld.script
deleted file mode 100644
index de8179e8d..000000000
--- a/nuttx-configs/px4fmu-v1/common/ld.script
+++ /dev/null
@@ -1,149 +0,0 @@
-/****************************************************************************
- * configs/px4fmu/common/ld.script
- *
- * Copyright (C) 2011 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 STM32F405 has 1024Kb of FLASH beginning at address 0x0800:0000 and
- * 192Kb of SRAM. SRAM is split up into three blocks:
- *
- * 1) 112Kb of SRAM beginning at address 0x2000:0000
- * 2) 16Kb of SRAM beginning at address 0x2001:c000
- * 3) 64Kb of TCM SRAM beginning at address 0x1000:0000
- *
- * When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
- * where the code expects to begin execution by jumping to the entry point in
- * the 0x0800:0000 address range.
- *
- * The first 0x4000 of flash is reserved for the bootloader.
- */
-
-MEMORY
-{
- flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
- sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
- ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
-}
-
-OUTPUT_ARCH(arm)
-
-ENTRY(__start) /* treat __start as the anchor for dead code stripping */
-EXTERN(_vectors) /* force the vectors to be included in the output */
-
-/*
- * Ensure that abort() is present in the final object. The exception handling
- * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
- */
-EXTERN(abort)
-
-SECTIONS
-{
- .text : {
- _stext = ABSOLUTE(.);
- *(.vectors)
- *(.text .text.*)
- *(.fixup)
- *(.gnu.warning)
- *(.rodata .rodata.*)
- *(.gnu.linkonce.t.*)
- *(.got)
- *(.gcc_except_table)
- *(.gnu.linkonce.r.*)
- _etext = ABSOLUTE(.);
-
- /*
- * This is a hack to make the newlib libm __errno() call
- * use the NuttX get_errno_ptr() function.
- */
- __errno = get_errno_ptr;
- } > flash
-
- /*
- * Init functions (static constructors and the like)
- */
- .init_section : {
- _sinit = ABSOLUTE(.);
- KEEP(*(.init_array .init_array.*))
- _einit = ABSOLUTE(.);
- } > flash
-
- /*
- * Construction data for parameters.
- */
- __param ALIGN(4): {
- __param_start = ABSOLUTE(.);
- KEEP(*(__param*))
- __param_end = ABSOLUTE(.);
- } > flash
-
- .ARM.extab : {
- *(.ARM.extab*)
- } > flash
-
- __exidx_start = ABSOLUTE(.);
- .ARM.exidx : {
- *(.ARM.exidx*)
- } > flash
- __exidx_end = ABSOLUTE(.);
-
- _eronly = ABSOLUTE(.);
-
- .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/px4fmu-v1/nsh/Make.defs b/nuttx-configs/px4fmu-v1/nsh/Make.defs
index 81936334b..7b2ea703a 100644
--- a/nuttx-configs/px4fmu-v1/nsh/Make.defs
+++ b/nuttx-configs/px4fmu-v1/nsh/Make.defs
@@ -1,3 +1,179 @@
+############################################################################
+# configs/px4fmu-v1/nsh/Make.defs
+#
+# Copyright (C) 2011 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
+
+#
+# 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 = -O3
+ARCHCPUFLAGS = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+
+# enable precise stack overflow tracking
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM = "${shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a}"
+EXTRA_LIBS += $(LIBM)
+
+# 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 \
+ -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 \
+ -Wunsuffixed-float-constants
+ARCHWARNINGSXX = $(ARCHWARNINGS) \
+ -Wno-psabi
+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 =
-include $(TOPDIR)/configs/px4fmu-v1/common/Make.defs
diff --git a/nuttx-configs/px4fmu-v1/ostest/Make.defs b/nuttx-configs/px4fmu-v1/ostest/Make.defs
deleted file mode 100644
index 7b807abdb..000000000
--- a/nuttx-configs/px4fmu-v1/ostest/Make.defs
+++ /dev/null
@@ -1,122 +0,0 @@
-############################################################################
-# configs/stm32f4discovery/ostest/Make.defs
-#
-# Copyright (C) 2011-2012 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
-
-LDSCRIPT = ld.script
-
-ifeq ($(WINTOOL),y)
- # Windows-native toolchains
- 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)}"
- MAXOPTIMIZATION = -O2
-else
- # Linux/Cygwin-native toolchain
- ARCHINCLUDES = -I. -isystem $(TOPDIR)/include
- ARCHXXINCLUDES = -I. -isystem $(TOPDIR)/include -isystem $(TOPDIR)/include/cxx
- ARCHSCRIPT = -T$(TOPDIR)/configs/$(CONFIG_ARCH_BOARD)/scripts/$(LDSCRIPT)
-endif
-
-CC = $(CROSSDEV)gcc
-CXX = $(CROSSDEV)g++
-CPP = $(CROSSDEV)gcc -E
-LD = $(CROSSDEV)ld
-AR = $(ARCROSSDEV)ar rcs
-NM = $(ARCROSSDEV)nm
-OBJCOPY = $(CROSSDEV)objcopy
-OBJDUMP = $(CROSSDEV)objdump
-
-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}
-
-ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
- ARCHOPTIMIZATION = -g
-else
- ARCHOPTIMIZATION = $(MAXOPTIMIZATION) -fno-strict-aliasing -fno-strength-reduce -fomit-frame-pointer
-endif
-
-ARCHCFLAGS = -fno-builtin
-ARCHCXXFLAGS = -fno-builtin -fno-exceptions -fno-rtti
-ARCHWARNINGS = -Wall -Wstrict-prototypes -Wshadow
-ARCHWARNINGSXX = -Wall -Wshadow
-ARCHDEFINES =
-ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
-
-CFLAGS = $(ARCHCFLAGS) $(ARCHWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
-CPICFLAGS = $(ARCHPICFLAGS) $(CFLAGS)
-CXXFLAGS = $(ARCHCXXFLAGS) $(ARCHWARNINGSXX) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHXXINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe
-CXXPICFLAGS = $(ARCHPICFLAGS) $(CXXFLAGS)
-CPPFLAGS = $(ARCHINCLUDES) $(ARCHDEFINES) $(EXTRADEFINES)
-AFLAGS = $(CFLAGS) -D__ASSEMBLY__
-
-NXFLATLDFLAGS1 = -r -d -warn-common
-NXFLATLDFLAGS2 = $(NXFLATLDFLAGS1) -T$(TOPDIR)/binfmt/libnxflat/gnu-nxflat-pcrel.ld -no-check-sections
-LDNXFLATFLAGS = -e main -s 2048
-
-OBJEXT = .o
-LIBEXT = .a
-EXEEXT =
-
-ifneq ($(CROSSDEV),arm-nuttx-elf-)
- LDFLAGS += -nostartfiles -nodefaultlibs
-endif
-ifeq ($(CONFIG_DEBUG_SYMBOLS),y)
- LDFLAGS += -g
-endif
-
-
-HOSTCC = gcc
-HOSTINCLUDES = -I.
-HOSTCFLAGS = -Wall -Wstrict-prototypes -Wshadow -g -pipe
-HOSTLDFLAGS =
-ifeq ($(CONFIG_HOST_WINDOWS),y)
- HOSTEXEEXT = .exe
-else
- HOSTEXEEXT =
-endif
-
-ifeq ($(WINTOOL),y)
- # Windows-native host tools
- DIRLINK = $(TOPDIR)/tools/copydir.sh
- DIRUNLINK = $(TOPDIR)/tools/unlink.sh
- MKDEP = $(TOPDIR)/tools/mknulldeps.sh
-else
- # Linux/Cygwin-native host tools
- MKDEP = $(TOPDIR)/tools/mkdeps$(HOSTEXEEXT)
-endif
-
diff --git a/nuttx-configs/px4fmu-v1/ostest/defconfig b/nuttx-configs/px4fmu-v1/ostest/defconfig
deleted file mode 100644
index c7fb6b2a5..000000000
--- a/nuttx-configs/px4fmu-v1/ostest/defconfig
+++ /dev/null
@@ -1,583 +0,0 @@
-#
-# Automatically generated file; DO NOT EDIT.
-# Nuttx/ Configuration
-#
-CONFIG_NUTTX_NEWCONFIG=y
-
-#
-# Build Setup
-#
-# CONFIG_EXPERIMENTAL is not set
-# CONFIG_HOST_LINUX is not set
-# CONFIG_HOST_OSX is not set
-CONFIG_HOST_WINDOWS=y
-# CONFIG_HOST_OTHER is not set
-# CONFIG_WINDOWS_NATIVE is not set
-CONFIG_WINDOWS_CYGWIN=y
-# CONFIG_WINDOWS_MSYS is not set
-# CONFIG_WINDOWS_OTHER is not set
-# CONFIG_WINDOWS_MKLINK is not set
-
-#
-# Build Configuration
-#
-# CONFIG_APPS_DIR="../apps"
-# 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
-
-#
-# Customize Header Files
-#
-# CONFIG_ARCH_STDBOOL_H is not set
-# CONFIG_ARCH_MATH_H is not set
-# CONFIG_ARCH_FLOAT_H is not set
-# CONFIG_ARCH_STDARG_H is not set
-
-#
-# Debug Options
-#
-# CONFIG_DEBUG is not set
-# CONFIG_DEBUG_SYMBOLS is not set
-
-#
-# System Type
-#
-# CONFIG_ARCH_8051 is not set
-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_C5471 is not set
-# CONFIG_ARCH_CHIP_CALYPSO is not set
-# CONFIG_ARCH_CHIP_DM320 is not set
-# CONFIG_ARCH_CHIP_IMX is not set
-# CONFIG_ARCH_CHIP_KINETIS is not set
-# CONFIG_ARCH_CHIP_LM3S 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_SAM3U is not set
-CONFIG_ARCH_CHIP_STM32=y
-# CONFIG_ARCH_CHIP_STR71X is not set
-CONFIG_ARCH_CORTEXM4=y
-CONFIG_ARCH_FAMILY="armv7-m"
-CONFIG_ARCH_CHIP="stm32"
-CONFIG_ARCH_HAVE_CMNVECTOR=y
-# CONFIG_ARMV7M_CMNVECTOR is not set
-# CONFIG_ARCH_FPU is not set
-CONFIG_ARCH_HAVE_MPU=y
-# CONFIG_ARMV7M_MPU is not set
-CONFIG_ARCH_IRQPRIO=y
-CONFIG_BOARD_LOOPSPERMSEC=16717
-# CONFIG_ARCH_CALIBRATION is not set
-# CONFIG_SERIAL_TERMIOS is not set
-
-#
-# STM32 Configuration Options
-#
-# 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_STM32F103RET6 is not set
-# CONFIG_ARCH_CHIP_STM32F103VCT6 is not set
-# CONFIG_ARCH_CHIP_STM32F103VET6 is not set
-# CONFIG_ARCH_CHIP_STM32F103ZET6 is not set
-# CONFIG_ARCH_CHIP_STM32F105VBT7 is not set
-# CONFIG_ARCH_CHIP_STM32F107VC is not set
-# CONFIG_ARCH_CHIP_STM32F207IG 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=y
-# 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_STM32_STM32F40XX=y
-# CONFIG_STM32_CODESOURCERYW is not set
-CONFIG_STM32_CODESOURCERYL=y
-# CONFIG_STM32_ATOLLIC_LITE is not set
-# CONFIG_STM32_ATOLLIC_PRO is not set
-# CONFIG_STM32_DEVKITARM is not set
-# CONFIG_STM32_RAISONANCE is not set
-# CONFIG_STM32_BUILDROOT is not set
-# CONFIG_STM32_DFU is not set
-
-#
-# STM32 Peripheral Support
-#
-# CONFIG_STM32_ADC1 is not set
-# CONFIG_STM32_ADC2 is not set
-# CONFIG_STM32_ADC3 is not set
-# CONFIG_STM32_BKPSRAM is not set
-# CONFIG_STM32_CAN1 is not set
-# CONFIG_STM32_CAN2 is not set
-# CONFIG_STM32_CCMDATARAM is not set
-# CONFIG_STM32_CRC is not set
-# CONFIG_STM32_CRYP is not set
-# CONFIG_STM32_DMA1 is not set
-# CONFIG_STM32_DMA2 is not set
-# CONFIG_STM32_DAC1 is not set
-# CONFIG_STM32_DAC2 is not set
-# CONFIG_STM32_DCMI is not set
-# CONFIG_STM32_ETHMAC is not set
-# CONFIG_STM32_FSMC is not set
-# CONFIG_STM32_HASH is not set
-# CONFIG_STM32_I2C1 is not set
-# CONFIG_STM32_I2C2 is not set
-# CONFIG_STM32_I2C3 is not set
-# CONFIG_STM32_IWDG is not set
-# CONFIG_STM32_OTGFS is not set
-# CONFIG_STM32_OTGHS is not set
-# CONFIG_STM32_PWR is not set
-# CONFIG_STM32_RNG is not set
-# CONFIG_STM32_SDIO is not set
-# CONFIG_STM32_SPI1 is not set
-# CONFIG_STM32_SPI2 is not set
-# CONFIG_STM32_SPI3 is not set
-CONFIG_STM32_SYSCFG=y
-# CONFIG_STM32_TIM1 is not set
-# CONFIG_STM32_TIM2 is not set
-# CONFIG_STM32_TIM3 is not set
-# CONFIG_STM32_TIM4 is not set
-# CONFIG_STM32_TIM5 is not set
-# CONFIG_STM32_TIM6 is not set
-# CONFIG_STM32_TIM7 is not set
-# CONFIG_STM32_TIM8 is not set
-# CONFIG_STM32_TIM9 is not set
-# CONFIG_STM32_TIM10 is not set
-# CONFIG_STM32_TIM11 is not set
-# CONFIG_STM32_TIM12 is not set
-# CONFIG_STM32_TIM13 is not set
-# CONFIG_STM32_TIM14 is not set
-# CONFIG_STM32_USART1 is not set
-CONFIG_STM32_USART2=y
-# CONFIG_STM32_USART3 is not set
-# CONFIG_STM32_UART4 is not set
-# CONFIG_STM32_UART5 is not set
-# CONFIG_STM32_USART6 is not set
-# CONFIG_STM32_WWDG is not set
-
-#
-# Alternate Pin Mapping
-#
-# CONFIG_STM32_JTAG_DISABLE is not set
-# CONFIG_STM32_JTAG_FULL_ENABLE is not set
-# CONFIG_STM32_JTAG_NOJNTRST_ENABLE is not set
-CONFIG_STM32_JTAG_SW_ENABLE=y
-# CONFIG_STM32_FORCEPOWER is not set
-# CONFIG_ARCH_BOARD_STM32_CUSTOM_CLOCKCONFIG is not set
-# CONFIG_STM32_CCMEXCLUDE is not set
-
-#
-# USB Host Configuration
-#
-
-#
-# Architecture Options
-#
-# CONFIG_ARCH_NOINTC is not set
-# CONFIG_ARCH_DMA is not set
-CONFIG_ARCH_STACKDUMP=y
-
-#
-# Board Settings
-#
-CONFIG_DRAM_START=0x20000000
-CONFIG_DRAM_SIZE=114688
-CONFIG_ARCH_HAVE_INTERRUPTSTACK=y
-CONFIG_ARCH_INTERRUPTSTACK=0
-
-#
-# 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
-
-#
-# Board Selection
-#
-CONFIG_ARCH_BOARD_STM32F4_DISCOVERY=y
-# CONFIG_ARCH_BOARD_CUSTOM is not set
-CONFIG_ARCH_BOARD="stm32f4discovery"
-
-#
-# Common Board Options
-#
-CONFIG_ARCH_HAVE_LEDS=y
-CONFIG_ARCH_LEDS=y
-CONFIG_ARCH_HAVE_BUTTONS=y
-# CONFIG_ARCH_BUTTONS is not set
-CONFIG_ARCH_HAVE_IRQBUTTONS=y
-
-#
-# Board-Specific Options
-#
-
-#
-# RTOS Features
-#
-CONFIG_MSEC_PER_TICK=10
-CONFIG_RR_INTERVAL=200
-# CONFIG_SCHED_INSTRUMENTATION is not set
-CONFIG_TASK_NAME_SIZE=0
-# CONFIG_JULIAN_TIME is not set
-CONFIG_START_YEAR=2009
-CONFIG_START_MONTH=9
-CONFIG_START_DAY=21
-CONFIG_DEV_CONSOLE=y
-# CONFIG_MUTEX_TYPES is not set
-# CONFIG_PRIORITY_INHERITANCE is not set
-# CONFIG_FDCLONE_DISABLE is not set
-# CONFIG_FDCLONE_STDIO is not set
-CONFIG_SDCLONE_DISABLE=y
-# CONFIG_SCHED_WORKQUEUE is not set
-# CONFIG_SCHED_WAITPID is not set
-# CONFIG_SCHED_ATEXIT is not set
-# CONFIG_SCHED_ONEXIT is not set
-CONFIG_USER_ENTRYPOINT="ostest_main"
-CONFIG_DISABLE_OS_API=y
-# CONFIG_DISABLE_CLOCK is not set
-# CONFIG_DISABLE_POSIX_TIMERS is not set
-# CONFIG_DISABLE_PTHREAD is not set
-# CONFIG_DISABLE_SIGNALS is not set
-# CONFIG_DISABLE_MQUEUE is not set
-CONFIG_DISABLE_MOUNTPOINT=y
-CONFIG_DISABLE_ENVIRON=y
-CONFIG_DISABLE_POLL=y
-
-#
-# Sizes of configurable things (0 disables)
-#
-CONFIG_MAX_TASKS=16
-CONFIG_MAX_TASK_ARGS=4
-CONFIG_NPTHREAD_KEYS=4
-CONFIG_NFILE_DESCRIPTORS=8
-CONFIG_NFILE_STREAMS=8
-CONFIG_NAME_MAX=32
-CONFIG_PREALLOC_MQ_MSGS=4
-CONFIG_MQ_MAXMSGSIZE=32
-CONFIG_MAX_WDOGPARMS=2
-CONFIG_PREALLOC_WDOGS=4
-CONFIG_PREALLOC_TIMERS=4
-
-#
-# Stack and heap information
-#
-# CONFIG_CUSTOM_STACK is not set
-CONFIG_IDLETHREAD_STACKSIZE=1024
-CONFIG_USERMAIN_STACKSIZE=2048
-CONFIG_PTHREAD_STACK_MIN=256
-CONFIG_PTHREAD_STACK_DEFAULT=2048
-
-#
-# Device Drivers
-#
-CONFIG_DEV_NULL=y
-# CONFIG_DEV_ZERO is not set
-# CONFIG_LOOP is not set
-# CONFIG_RAMDISK is not set
-# CONFIG_CAN is not set
-# CONFIG_PWM is not set
-# CONFIG_I2C is not set
-CONFIG_ARCH_HAVE_I2CRESET=y
-# CONFIG_SPI is not set
-# CONFIG_RTC is not set
-# CONFIG_WATCHDOG is not set
-# CONFIG_ANALOG 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_PIPES is not set
-# CONFIG_PM is not set
-# CONFIG_POWER is not set
-# CONFIG_SENSORS is not set
-# CONFIG_SERCOMM_CONSOLE is not set
-CONFIG_SERIAL=y
-CONFIG_DEV_LOWCONSOLE=y
-# CONFIG_16550_UART is not set
-CONFIG_ARCH_HAVE_USART2=y
-CONFIG_MCU_SERIAL=y
-CONFIG_STANDARD_SERIAL=y
-CONFIG_USART2_SERIAL_CONSOLE=y
-# CONFIG_NO_SERIAL_CONSOLE is not set
-
-#
-# USART2 Configuration
-#
-CONFIG_USART2_RXBUFSIZE=128
-CONFIG_USART2_TXBUFSIZE=128
-CONFIG_USART2_BAUD=115200
-CONFIG_USART2_BITS=8
-CONFIG_USART2_PARITY=0
-CONFIG_USART2_2STOP=0
-# 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
-
-#
-# Networking Support
-#
-# CONFIG_NET is not set
-
-#
-# File Systems
-#
-
-#
-# File system configuration
-#
-# CONFIG_FS_RAMMAP is not set
-
-#
-# System Logging
-#
-# CONFIG_SYSLOG is not set
-
-#
-# Graphics Support
-#
-# CONFIG_NX is not set
-
-#
-# Memory Management
-#
-# CONFIG_MM_SMALL is not set
-CONFIG_MM_REGIONS=2
-# CONFIG_GRAN is not set
-
-#
-# Binary Formats
-#
-# CONFIG_BINFMT_DISABLE is not set
-# CONFIG_NXFLAT is not set
-# CONFIG_ELF is not set
-CONFIG_SYMTAB_ORDEREDBYNAME=y
-
-#
-# Library Routines
-#
-CONFIG_STDIO_BUFFER_SIZE=64
-CONFIG_STDIO_LINEBUFFER=y
-CONFIG_NUNGET_CHARS=2
-# CONFIG_LIBM is not set
-# CONFIG_NOPRINTF_FIELDWIDTH is not set
-# CONFIG_LIBC_FLOATINGPOINT is not set
-# 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_STRERROR is not set
-# CONFIG_LIBC_PERROR_STDOUT is not set
-CONFIG_ARCH_LOWPUTC=y
-CONFIG_LIB_SENDFILE_BUFSIZE=512
-# CONFIG_ARCH_ROMGETC is not set
-# CONFIG_ARCH_OPTIMIZED_FUNCTIONS is not set
-
-#
-# Basic CXX Support
-#
-# CONFIG_HAVE_CXX is not set
-
-#
-# Application Configuration
-#
-
-#
-# Named Applications
-#
-# CONFIG_BUILTIN is not set
-
-#
-# Examples
-#
-# CONFIG_EXAMPLES_BUTTONS is not set
-# CONFIG_EXAMPLES_CAN is not set
-# CONFIG_EXAMPLES_CDCACM is not set
-# CONFIG_EXAMPLES_COMPOSITE 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_IGMP is not set
-# CONFIG_EXAMPLES_LCDRW is not set
-# CONFIG_EXAMPLES_MM is not set
-# CONFIG_EXAMPLES_MOUNT is not set
-# CONFIG_EXAMPLES_MODBUS is not set
-# CONFIG_EXAMPLES_NETTEST is not set
-# CONFIG_EXAMPLES_NSH is not set
-# CONFIG_EXAMPLES_NULL is not set
-# CONFIG_EXAMPLES_NX is not set
-# CONFIG_EXAMPLES_NXCONSOLE 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=y
-# CONFIG_EXAMPLES_OSTEST_BUILTIN is not set
-CONFIG_EXAMPLES_OSTEST_LOOPS=1
-CONFIG_EXAMPLES_OSTEST_STACKSIZE=2048
-CONFIG_EXAMPLES_OSTEST_NBARRIER_THREADS=3
-CONFIG_EXAMPLES_OSTEST_RR_RANGE=10000
-CONFIG_EXAMPLES_OSTEST_RR_RUNS=10
-# CONFIG_EXAMPLES_PASHELLO is not set
-# CONFIG_EXAMPLES_PIPE is not set
-# CONFIG_EXAMPLES_POLL 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_SERLOOP 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_UDP is not set
-# CONFIG_EXAMPLES_UIP is not set
-# CONFIG_EXAMPLES_USBSERIAL is not set
-# CONFIG_EXAMPLES_USBMSC is not set
-# CONFIG_EXAMPLES_USBTERM is not set
-# CONFIG_EXAMPLES_WATCHDOG is not set
-# CONFIG_EXAMPLES_WLAN is not set
-
-#
-# Interpreters
-#
-
-#
-# Interpreters
-#
-# CONFIG_INTERPRETERS_FICL is not set
-# CONFIG_INTERPRETERS_PCODE is not set
-
-#
-# Network Utilities
-#
-
-#
-# Networking Utilities
-#
-# CONFIG_NETUTILS_CODECS is not set
-# CONFIG_NETUTILS_DHCPC is not set
-# CONFIG_NETUTILS_DHCPD is not set
-# CONFIG_NETUTILS_FTPC is not set
-# CONFIG_NETUTILS_FTPD is not set
-# CONFIG_NETUTILS_JSON is not set
-# CONFIG_NETUTILS_RESOLV is not set
-# CONFIG_NETUTILS_SMTP is not set
-# CONFIG_NETUTILS_TELNETD is not set
-# CONFIG_NETUTILS_TFTPC is not set
-# CONFIG_NETUTILS_THTTPD is not set
-# CONFIG_NETUTILS_UIPLIB is not set
-# CONFIG_NETUTILS_WEBCLIENT is not set
-
-#
-# ModBus
-#
-
-#
-# FreeModbus
-#
-# CONFIG_MODBUS is not set
-
-#
-# NSH Library
-#
-# CONFIG_NSH_LIBRARY is not set
-
-#
-# NxWidgets/NxWM
-#
-
-#
-# System NSH Add-Ons
-#
-
-#
-# Custom Free Memory Command
-#
-# CONFIG_SYSTEM_FREE is not set
-
-#
-# I2C tool
-#
-
-#
-# FLASH Program Installation
-#
-# CONFIG_SYSTEM_INSTALL is not set
-
-#
-# readline()
-#
-# CONFIG_SYSTEM_READLINE is not set
-
-#
-# Power Off
-#
-# CONFIG_SYSTEM_POWEROFF is not set
-
-#
-# RAMTRON
-#
-# CONFIG_SYSTEM_RAMTRON is not set
-
-#
-# SD Card
-#
-# CONFIG_SYSTEM_SDCARD is not set
-
-#
-# Sysinfo
-#
-# CONFIG_SYSTEM_SYSINFO is not set
diff --git a/nuttx-configs/px4fmu-v1/ostest/setenv.sh b/nuttx-configs/px4fmu-v1/ostest/setenv.sh
deleted file mode 100755
index a67fdc5a8..000000000
--- a/nuttx-configs/px4fmu-v1/ostest/setenv.sh
+++ /dev/null
@@ -1,75 +0,0 @@
-#!/bin/bash
-# configs/stm32f4discovery/ostest/setenv.sh
-#
-# Copyright (C) 2011-2012 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"
-
-# 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 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/px4fmu-v1/scripts/gnu-elf.ld b/nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld
deleted file mode 100644
index 1f29f02f5..000000000
--- a/nuttx-configs/px4fmu-v1/scripts/gnu-elf.ld
+++ /dev/null
@@ -1,129 +0,0 @@
-/****************************************************************************
- * configs/stm32f4discovery/scripts/gnu-elf.ld
- *
- * Copyright (C) 2012 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.
- *
- ****************************************************************************/
-
-SECTIONS
-{
- .text 0x00000000 :
- {
- _stext = . ;
- *(.text)
- *(.text.*)
- *(.gnu.warning)
- *(.stub)
- *(.glue_7)
- *(.glue_7t)
- *(.jcr)
-
- /* C++ support: The .init and .fini sections contain specific logic
- * to manage static constructors and destructors.
- */
-
- *(.gnu.linkonce.t.*)
- *(.init) /* Old ABI */
- *(.fini) /* Old ABI */
- _etext = . ;
- }
-
- .rodata :
- {
- _srodata = . ;
- *(.rodata)
- *(.rodata1)
- *(.rodata.*)
- *(.gnu.linkonce.r*)
- _erodata = . ;
- }
-
- .data :
- {
- _sdata = . ;
- *(.data)
- *(.data1)
- *(.data.*)
- *(.gnu.linkonce.d*)
- _edata = . ;
- }
-
- /* C++ support. For each global and static local C++ object,
- * GCC creates a small subroutine to construct the object. Pointers
- * to these routines (not the routines themselves) are stored as
- * simple, linear arrays in the .ctors section of the object file.
- * Similarly, pointers to global/static destructor routines are
- * stored in .dtors.
- */
-
- .ctors :
- {
- _sctors = . ;
- *(.ctors) /* Old ABI: Unallocated */
- *(.init_array) /* New ABI: Allocated */
- _edtors = . ;
- }
-
- .dtors :
- {
- _sdtors = . ;
- *(.dtors) /* Old ABI: Unallocated */
- *(.fini_array) /* New ABI: Allocated */
- _edtors = . ;
- }
-
- .bss :
- {
- _sbss = . ;
- *(.bss)
- *(.bss.*)
- *(.sbss)
- *(.sbss.*)
- *(.gnu.linkonce.b*)
- *(COMMON)
- _ebss = . ;
- }
-
- /* 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/px4fmu-v1/scripts/ld.script b/nuttx-configs/px4fmu-v1/scripts/ld.script
index f6560743b..ced5b21b7 100644
--- a/nuttx-configs/px4fmu-v1/scripts/ld.script
+++ b/nuttx-configs/px4fmu-v1/scripts/ld.script
@@ -1,7 +1,7 @@
/****************************************************************************
- * configs/stm32f4discovery/scripts/ld.script
+ * configs/px4fmu-v1/scripts/ld.script
*
- * Copyright (C) 2011-2012 Gregory Nutt. All rights reserved.
+ * Copyright (C) 2011 Gregory Nutt. All rights reserved.
* Author: Gregory Nutt <gnutt@nuttx.org>
*
* Redistribution and use in source and binary forms, with or without
@@ -42,41 +42,67 @@
*
* When booting from FLASH, FLASH memory is aliased to address 0x0000:0000
* where the code expects to begin execution by jumping to the entry point in
- * the 0x0800:0000 address
- * range.
+ * the 0x0800:0000 address range.
+ *
+ * The first 0x4000 of flash is reserved for the bootloader.
*/
MEMORY
{
- flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
- sram (rwx) : ORIGIN = 0x20000000, LENGTH = 112K
+ flash (rx) : ORIGIN = 0x08004000, LENGTH = 1008K
+ sram (rwx) : ORIGIN = 0x20000000, LENGTH = 128K
+ ccsram (rwx) : ORIGIN = 0x10000000, LENGTH = 64K
}
OUTPUT_ARCH(arm)
-EXTERN(_vectors)
-ENTRY(_stext)
+
+ENTRY(__start) /* treat __start as the anchor for dead code stripping */
+EXTERN(_vectors) /* force the vectors to be included in the output */
+
+/*
+ * Ensure that abort() is present in the final object. The exception handling
+ * code pulled in by libgcc.a requires it (and that code cannot be easily avoided).
+ */
+EXTERN(abort)
+
SECTIONS
{
.text : {
_stext = ABSOLUTE(.);
*(.vectors)
- *(.text .text.*)
+ *(.text .text.*)
*(.fixup)
*(.gnu.warning)
- *(.rodata .rodata.*)
+ *(.rodata .rodata.*)
*(.gnu.linkonce.t.*)
- *(.glue_7)
- *(.glue_7t)
*(.got)
*(.gcc_except_table)
*(.gnu.linkonce.r.*)
_etext = ABSOLUTE(.);
+
+ /*
+ * This is a hack to make the newlib libm __errno() call
+ * use the NuttX get_errno_ptr() function.
+ */
+ __errno = get_errno_ptr;
} > flash
- .init_section : {
- _sinit = ABSOLUTE(.);
- *(.init_array .init_array.*)
- _einit = ABSOLUTE(.);
+ /*
+ * Init functions (static constructors and the like)
+ */
+ .init_section : {
+ _sinit = ABSOLUTE(.);
+ KEEP(*(.init_array .init_array.*))
+ _einit = ABSOLUTE(.);
+ } > flash
+
+ /*
+ * Construction data for parameters.
+ */
+ __param ALIGN(4): {
+ __param_start = ABSOLUTE(.);
+ KEEP(*(__param*))
+ __param_end = ABSOLUTE(.);
} > flash
.ARM.extab : {
diff --git a/nuttx-configs/px4fmu-v1/tools/px_mkfw.py b/nuttx-configs/px4fmu-v1/tools/px_mkfw.py
deleted file mode 100755
index 9f4ddad62..000000000
--- a/nuttx-configs/px4fmu-v1/tools/px_mkfw.py
+++ /dev/null
@@ -1,110 +0,0 @@
-#!/usr/bin/env python
-############################################################################
-#
-# Copyright (C) 2012 PX4 Development Team. All rights reserved.
-#
-# Redistribution and use in source and binary forms, with or without
-# modification, are permitted provided that the following conditions
-# are met:
-#
-# 1. Redistributions of source code must retain the above copyright
-# notice, this list of conditions and the following disclaimer.
-# 2. Redistributions in binary form must reproduce the above copyright
-# notice, this list of conditions and the following disclaimer in
-# the documentation and/or other materials provided with the
-# distribution.
-# 3. Neither the name PX4 nor the names of its contributors may be
-# used to endorse or promote products derived from this software
-# without specific prior written permission.
-#
-# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
-# "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
-# LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
-# FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
-# COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
-# INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
-# BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
-# OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
-# AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
-# LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
-# ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
-# POSSIBILITY OF SUCH DAMAGE.
-#
-############################################################################
-
-#
-# PX4 firmware image generator
-#
-# The PX4 firmware file is a JSON-encoded Python object, containing
-# metadata fields and a zlib-compressed base64-encoded firmware image.
-#
-
-import sys
-import argparse
-import json
-import base64
-import zlib
-import time
-import subprocess
-
-#
-# Construct a basic firmware description
-#
-def mkdesc():
- proto = {}
- proto['magic'] = "PX4FWv1"
- proto['board_id'] = 0
- proto['board_revision'] = 0
- proto['version'] = ""
- proto['summary'] = ""
- proto['description'] = ""
- proto['git_identity'] = ""
- proto['build_time'] = 0
- proto['image'] = base64.b64encode(bytearray())
- proto['image_size'] = 0
- return proto
-
-# Parse commandline
-parser = argparse.ArgumentParser(description="Firmware generator for the PX autopilot system.")
-parser.add_argument("--prototype", action="store", help="read a prototype description from a file")
-parser.add_argument("--board_id", action="store", help="set the board ID required")
-parser.add_argument("--board_revision", action="store", help="set the board revision required")
-parser.add_argument("--version", action="store", help="set a version string")
-parser.add_argument("--summary", action="store", help="set a brief description")
-parser.add_argument("--description", action="store", help="set a longer description")
-parser.add_argument("--git_identity", action="store", help="the working directory to check for git identity")
-parser.add_argument("--image", action="store", help="the firmware image")
-args = parser.parse_args()
-
-# Fetch the firmware descriptor prototype if specified
-if args.prototype != None:
- f = open(args.prototype,"r")
- desc = json.load(f)
- f.close()
-else:
- desc = mkdesc()
-
-desc['build_time'] = int(time.time())
-
-if args.board_id != None:
- desc['board_id'] = int(args.board_id)
-if args.board_revision != None:
- desc['board_revision'] = int(args.board_revision)
-if args.version != None:
- desc['version'] = str(args.version)
-if args.summary != None:
- desc['summary'] = str(args.summary)
-if args.description != None:
- desc['description'] = str(args.description)
-if args.git_identity != None:
- cmd = " ".join(["git", "--git-dir", args.git_identity + "/.git", "describe", "--always", "--dirty"])
- p = subprocess.Popen(cmd, shell=True, stdout=subprocess.PIPE).stdout
- desc['git_identity'] = p.read().strip()
- p.close()
-if args.image != None:
- f = open(args.image, "rb")
- bytes = f.read()
- desc['image_size'] = len(bytes)
- desc['image'] = base64.b64encode(zlib.compress(bytes,9))
-
-print json.dumps(desc, indent=4)
diff --git a/nuttx-configs/px4fmu-v1/tools/px_uploader.py b/nuttx-configs/px4fmu-v1/tools/px_uploader.py
deleted file mode 100755
index 3b23f4f83..000000000
--- a/nuttx-configs/px4fmu-v1/tools/px_uploader.py
+++ /dev/null
@@ -1,416 +0,0 @@
-#!/usr/bin/env python
-############################################################################
-#
-# Copyright (C) 2012 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.
-#
-############################################################################
-
-#
-# Serial firmware uploader for the PX4FMU bootloader
-#
-# The PX4 firmware file is a JSON-encoded Python object, containing
-# metadata fields and a zlib-compressed base64-encoded firmware image.
-#
-# The uploader uses the following fields from the firmware file:
-#
-# image
-# The firmware that will be uploaded.
-# image_size
-# The size of the firmware in bytes.
-# board_id
-# The board for which the firmware is intended.
-# board_revision
-# Currently only used for informational purposes.
-#
-
-import sys
-import argparse
-import binascii
-import serial
-import os
-import struct
-import json
-import zlib
-import base64
-import time
-import array
-
-from sys import platform as _platform
-
-class firmware(object):
- '''Loads a firmware file'''
-
- desc = {}
- image = bytes()
- crctab = array.array('I', [
- 0x00000000, 0x77073096, 0xee0e612c, 0x990951ba, 0x076dc419, 0x706af48f, 0xe963a535, 0x9e6495a3,
- 0x0edb8832, 0x79dcb8a4, 0xe0d5e91e, 0x97d2d988, 0x09b64c2b, 0x7eb17cbd, 0xe7b82d07, 0x90bf1d91,
- 0x1db71064, 0x6ab020f2, 0xf3b97148, 0x84be41de, 0x1adad47d, 0x6ddde4eb, 0xf4d4b551, 0x83d385c7,
- 0x136c9856, 0x646ba8c0, 0xfd62f97a, 0x8a65c9ec, 0x14015c4f, 0x63066cd9, 0xfa0f3d63, 0x8d080df5,
- 0x3b6e20c8, 0x4c69105e, 0xd56041e4, 0xa2677172, 0x3c03e4d1, 0x4b04d447, 0xd20d85fd, 0xa50ab56b,
- 0x35b5a8fa, 0x42b2986c, 0xdbbbc9d6, 0xacbcf940, 0x32d86ce3, 0x45df5c75, 0xdcd60dcf, 0xabd13d59,
- 0x26d930ac, 0x51de003a, 0xc8d75180, 0xbfd06116, 0x21b4f4b5, 0x56b3c423, 0xcfba9599, 0xb8bda50f,
- 0x2802b89e, 0x5f058808, 0xc60cd9b2, 0xb10be924, 0x2f6f7c87, 0x58684c11, 0xc1611dab, 0xb6662d3d,
- 0x76dc4190, 0x01db7106, 0x98d220bc, 0xefd5102a, 0x71b18589, 0x06b6b51f, 0x9fbfe4a5, 0xe8b8d433,
- 0x7807c9a2, 0x0f00f934, 0x9609a88e, 0xe10e9818, 0x7f6a0dbb, 0x086d3d2d, 0x91646c97, 0xe6635c01,
- 0x6b6b51f4, 0x1c6c6162, 0x856530d8, 0xf262004e, 0x6c0695ed, 0x1b01a57b, 0x8208f4c1, 0xf50fc457,
- 0x65b0d9c6, 0x12b7e950, 0x8bbeb8ea, 0xfcb9887c, 0x62dd1ddf, 0x15da2d49, 0x8cd37cf3, 0xfbd44c65,
- 0x4db26158, 0x3ab551ce, 0xa3bc0074, 0xd4bb30e2, 0x4adfa541, 0x3dd895d7, 0xa4d1c46d, 0xd3d6f4fb,
- 0x4369e96a, 0x346ed9fc, 0xad678846, 0xda60b8d0, 0x44042d73, 0x33031de5, 0xaa0a4c5f, 0xdd0d7cc9,
- 0x5005713c, 0x270241aa, 0xbe0b1010, 0xc90c2086, 0x5768b525, 0x206f85b3, 0xb966d409, 0xce61e49f,
- 0x5edef90e, 0x29d9c998, 0xb0d09822, 0xc7d7a8b4, 0x59b33d17, 0x2eb40d81, 0xb7bd5c3b, 0xc0ba6cad,
- 0xedb88320, 0x9abfb3b6, 0x03b6e20c, 0x74b1d29a, 0xead54739, 0x9dd277af, 0x04db2615, 0x73dc1683,
- 0xe3630b12, 0x94643b84, 0x0d6d6a3e, 0x7a6a5aa8, 0xe40ecf0b, 0x9309ff9d, 0x0a00ae27, 0x7d079eb1,
- 0xf00f9344, 0x8708a3d2, 0x1e01f268, 0x6906c2fe, 0xf762575d, 0x806567cb, 0x196c3671, 0x6e6b06e7,
- 0xfed41b76, 0x89d32be0, 0x10da7a5a, 0x67dd4acc, 0xf9b9df6f, 0x8ebeeff9, 0x17b7be43, 0x60b08ed5,
- 0xd6d6a3e8, 0xa1d1937e, 0x38d8c2c4, 0x4fdff252, 0xd1bb67f1, 0xa6bc5767, 0x3fb506dd, 0x48b2364b,
- 0xd80d2bda, 0xaf0a1b4c, 0x36034af6, 0x41047a60, 0xdf60efc3, 0xa867df55, 0x316e8eef, 0x4669be79,
- 0xcb61b38c, 0xbc66831a, 0x256fd2a0, 0x5268e236, 0xcc0c7795, 0xbb0b4703, 0x220216b9, 0x5505262f,
- 0xc5ba3bbe, 0xb2bd0b28, 0x2bb45a92, 0x5cb36a04, 0xc2d7ffa7, 0xb5d0cf31, 0x2cd99e8b, 0x5bdeae1d,
- 0x9b64c2b0, 0xec63f226, 0x756aa39c, 0x026d930a, 0x9c0906a9, 0xeb0e363f, 0x72076785, 0x05005713,
- 0x95bf4a82, 0xe2b87a14, 0x7bb12bae, 0x0cb61b38, 0x92d28e9b, 0xe5d5be0d, 0x7cdcefb7, 0x0bdbdf21,
- 0x86d3d2d4, 0xf1d4e242, 0x68ddb3f8, 0x1fda836e, 0x81be16cd, 0xf6b9265b, 0x6fb077e1, 0x18b74777,
- 0x88085ae6, 0xff0f6a70, 0x66063bca, 0x11010b5c, 0x8f659eff, 0xf862ae69, 0x616bffd3, 0x166ccf45,
- 0xa00ae278, 0xd70dd2ee, 0x4e048354, 0x3903b3c2, 0xa7672661, 0xd06016f7, 0x4969474d, 0x3e6e77db,
- 0xaed16a4a, 0xd9d65adc, 0x40df0b66, 0x37d83bf0, 0xa9bcae53, 0xdebb9ec5, 0x47b2cf7f, 0x30b5ffe9,
- 0xbdbdf21c, 0xcabac28a, 0x53b39330, 0x24b4a3a6, 0xbad03605, 0xcdd70693, 0x54de5729, 0x23d967bf,
- 0xb3667a2e, 0xc4614ab8, 0x5d681b02, 0x2a6f2b94, 0xb40bbe37, 0xc30c8ea1, 0x5a05df1b, 0x2d02ef8d ])
- crcpad = bytearray('\xff\xff\xff\xff')
-
- def __init__(self, path):
-
- # read the file
- f = open(path, "r")
- self.desc = json.load(f)
- f.close()
-
- self.image = bytearray(zlib.decompress(base64.b64decode(self.desc['image'])))
-
- # pad image to 4-byte length
- while ((len(self.image) % 4) != 0):
- self.image.append('\xff')
-
- def property(self, propname):
- return self.desc[propname]
-
- def __crc32(self, bytes, state):
- for byte in bytes:
- index = (state ^ byte) & 0xff
- state = self.crctab[index] ^ (state >> 8)
- return state
-
- def crc(self, padlen):
- state = self.__crc32(self.image, int(0))
- for i in range(len(self.image), (padlen - 1), 4):
- state = self.__crc32(self.crcpad, state)
- return state
-
-class uploader(object):
- '''Uploads a firmware file to the PX FMU bootloader'''
-
- # protocol bytes
- INSYNC = chr(0x12)
- EOC = chr(0x20)
-
- # reply bytes
- OK = chr(0x10)
- FAILED = chr(0x11)
- INVALID = chr(0x13) # rev3+
-
- # command bytes
- NOP = chr(0x00) # guaranteed to be discarded by the bootloader
- GET_SYNC = chr(0x21)
- GET_DEVICE = chr(0x22)
- CHIP_ERASE = chr(0x23)
- CHIP_VERIFY = chr(0x24) # rev2 only
- PROG_MULTI = chr(0x27)
- READ_MULTI = chr(0x28) # rev2 only
- GET_CRC = chr(0x29) # rev3+
- REBOOT = chr(0x30)
-
- INFO_BL_REV = chr(1) # bootloader protocol revision
- BL_REV_MIN = 2 # minimum supported bootloader protocol
- BL_REV_MAX = 3 # maximum supported bootloader protocol
- INFO_BOARD_ID = chr(2) # board type
- INFO_BOARD_REV = chr(3) # board revision
- INFO_FLASH_SIZE = chr(4) # max firmware size in bytes
-
- PROG_MULTI_MAX = 60 # protocol max is 255, must be multiple of 4
- READ_MULTI_MAX = 60 # protocol max is 255, something overflows with >= 64
-
- def __init__(self, portname, baudrate):
- # open the port, keep the default timeout short so we can poll quickly
- self.port = serial.Serial(portname, baudrate, timeout=0.25)
-
- def close(self):
- if self.port is not None:
- self.port.close()
-
- def __send(self, c):
-# print("send " + binascii.hexlify(c))
- self.port.write(str(c))
-
- def __recv(self, count = 1):
- c = self.port.read(count)
- if len(c) < 1:
- raise RuntimeError("timeout waiting for data")
-# print("recv " + binascii.hexlify(c))
- return c
-
- def __recv_int(self):
- raw = self.__recv(4)
- val = struct.unpack("<I", raw)
- return val[0]
-
- def __getSync(self):
- self.port.flush()
- c = self.__recv()
- if c is not self.INSYNC:
- raise RuntimeError("unexpected 0x%x instead of INSYNC" % ord(c))
- c = self.__recv()
- if c == self.INVALID:
- raise RuntimeError("bootloader reports INVALID OPERATION")
- if c == self.FAILED:
- raise RuntimeError("bootloader reports OPERATION FAILED")
- if c != self.OK:
- raise RuntimeError("unexpected response 0x%x instead of OK" % ord(c))
-
- # attempt to get back into sync with the bootloader
- def __sync(self):
- # send a stream of ignored bytes longer than the longest possible conversation
- # that we might still have in progress
-# self.__send(uploader.NOP * (uploader.PROG_MULTI_MAX + 2))
- self.port.flushInput()
- self.__send(uploader.GET_SYNC
- + uploader.EOC)
- self.__getSync()
-
-# def __trySync(self):
-# c = self.__recv()
-# if (c != self.INSYNC):
-# #print("unexpected 0x%x instead of INSYNC" % ord(c))
-# return False;
-# c = self.__recv()
-# if (c != self.OK):
-# #print("unexpected 0x%x instead of OK" % ord(c))
-# return False
-# return True
-
- # send the GET_DEVICE command and wait for an info parameter
- def __getInfo(self, param):
- self.__send(uploader.GET_DEVICE + param + uploader.EOC)
- value = self.__recv_int()
- self.__getSync()
- return value
-
- # send the CHIP_ERASE command and wait for the bootloader to become ready
- def __erase(self):
- self.__send(uploader.CHIP_ERASE
- + uploader.EOC)
- # erase is very slow, give it 10s
- deadline = time.time() + 10
- while time.time() < deadline:
- try:
- self.__getSync()
- return
- except RuntimeError as ex:
- # we timed out, that's OK
- continue
-
- raise RuntimeError("timed out waiting for erase")
-
- # send a PROG_MULTI command to write a collection of bytes
- def __program_multi(self, data):
- self.__send(uploader.PROG_MULTI
- + chr(len(data)))
- self.__send(data)
- self.__send(uploader.EOC)
- self.__getSync()
-
- # verify multiple bytes in flash
- def __verify_multi(self, data):
- self.__send(uploader.READ_MULTI
- + chr(len(data))
- + uploader.EOC)
- self.port.flush()
- programmed = self.__recv(len(data))
- if programmed != data:
- print("got " + binascii.hexlify(programmed))
- print("expect " + binascii.hexlify(data))
- return False
- self.__getSync()
- return True
-
- # send the reboot command
- def __reboot(self):
- self.__send(uploader.REBOOT
- + uploader.EOC)
- self.port.flush()
-
- # v3+ can report failure if the first word flash fails
- if self.bl_rev >= 3:
- self.__getSync()
-
- # split a sequence into a list of size-constrained pieces
- def __split_len(self, seq, length):
- return [seq[i:i+length] for i in range(0, len(seq), length)]
-
- # upload code
- def __program(self, fw):
- code = fw.image
- groups = self.__split_len(code, uploader.PROG_MULTI_MAX)
- for bytes in groups:
- self.__program_multi(bytes)
-
- # verify code
- def __verify_v2(self, fw):
- self.__send(uploader.CHIP_VERIFY
- + uploader.EOC)
- self.__getSync()
- code = fw.image
- groups = self.__split_len(code, uploader.READ_MULTI_MAX)
- for bytes in groups:
- if (not self.__verify_multi(bytes)):
- raise RuntimeError("Verification failed")
-
- def __verify_v3(self, fw):
- expect_crc = fw.crc(self.fw_maxsize)
- self.__send(uploader.GET_CRC
- + uploader.EOC)
- report_crc = self.__recv_int()
- self.__getSync()
- if report_crc != expect_crc:
- print("Expected 0x%x" % expect_crc)
- print("Got 0x%x" % report_crc)
- raise RuntimeError("Program CRC failed")
-
- # get basic data about the board
- def identify(self):
- # make sure we are in sync before starting
- self.__sync()
-
- # get the bootloader protocol ID first
- self.bl_rev = self.__getInfo(uploader.INFO_BL_REV)
- if (self.bl_rev < uploader.BL_REV_MIN) or (self.bl_rev > uploader.BL_REV_MAX):
- print("Unsupported bootloader protocol %d" % uploader.INFO_BL_REV)
- raise RuntimeError("Bootloader protocol mismatch")
-
- self.board_type = self.__getInfo(uploader.INFO_BOARD_ID)
- self.board_rev = self.__getInfo(uploader.INFO_BOARD_REV)
- self.fw_maxsize = self.__getInfo(uploader.INFO_FLASH_SIZE)
-
- # upload the firmware
- def upload(self, fw):
- # Make sure we are doing the right thing
- if self.board_type != fw.property('board_id'):
- raise RuntimeError("Firmware not suitable for this board (run 'make configure_px4fmu && make clean' or 'make configure_px4io && make clean' to reconfigure).")
- if self.fw_maxsize < fw.property('image_size'):
- raise RuntimeError("Firmware image is too large for this board")
-
- print("erase...")
- self.__erase()
-
- print("program...")
- self.__program(fw)
-
- print("verify...")
- if self.bl_rev == 2:
- self.__verify_v2(fw)
- else:
- self.__verify_v3(fw)
-
- print("done, rebooting.")
- self.__reboot()
- self.port.close()
-
-
-# Parse commandline arguments
-parser = argparse.ArgumentParser(description="Firmware uploader for the PX autopilot system.")
-parser.add_argument('--port', action="store", required=True, help="Serial port(s) to which the FMU may be attached")
-parser.add_argument('--baud', action="store", type=int, default=115200, help="Baud rate of the serial port (default is 115200), only required for true serial ports.")
-parser.add_argument('firmware', action="store", help="Firmware file to be uploaded")
-args = parser.parse_args()
-
-# Load the firmware file
-fw = firmware(args.firmware)
-print("Loaded firmware for %x,%x, waiting for the bootloader..." % (fw.property('board_id'), fw.property('board_revision')))
-
-# Spin waiting for a device to show up
-while True:
- for port in args.port.split(","):
-
- #print("Trying %s" % port)
-
- # create an uploader attached to the port
- try:
- if "linux" in _platform:
- # Linux, don't open Mac OS and Win ports
- if not "COM" in port and not "tty.usb" in port:
- up = uploader(port, args.baud)
- elif "darwin" in _platform:
- # OS X, don't open Windows and Linux ports
- if not "COM" in port and not "ACM" in port:
- up = uploader(port, args.baud)
- elif "win" in _platform:
- # Windows, don't open POSIX ports
- if not "/" in port:
- up = uploader(port, args.baud)
- except:
- # open failed, rate-limit our attempts
- time.sleep(0.05)
-
- # and loop to the next port
- continue
-
- # port is open, try talking to it
- try:
- # identify the bootloader
- up.identify()
- print("Found board %x,%x bootloader rev %x on %s" % (up.board_type, up.board_rev, up.bl_rev, port))
-
- except:
- # most probably a timeout talking to the port, no bootloader
- continue
-
- try:
- # ok, we have a bootloader, try flashing it
- up.upload(fw)
-
- except RuntimeError as ex:
-
- # print the error
- print("ERROR: %s" % ex.args)
-
- finally:
- # always close the port
- up.close()
-
- # we could loop here if we wanted to wait for more boards...
- sys.exit(0)
diff --git a/nuttx-configs/px4fmu-v1/tools/upload.sh b/nuttx-configs/px4fmu-v1/tools/upload.sh
deleted file mode 100755
index 4e6597b3a..000000000
--- a/nuttx-configs/px4fmu-v1/tools/upload.sh
+++ /dev/null
@@ -1,27 +0,0 @@
-#!/bin/sh
-#
-# Wrapper to upload a PX4 firmware binary
-#
-TOOLS=`dirname $0`
-MKFW=${TOOLS}/px_mkfw.py
-UPLOAD=${TOOLS}/px_uploader.py
-
-BINARY=nuttx.bin
-PAYLOAD=nuttx.px4
-PORTS="/dev/tty.usbmodemPX1,/dev/tty.usbmodemPX2,/dev/tty.usbmodemPX3,/dev/tty.usbmodemPX4,/dev/tty.usbmodem1,/dev/tty.usbmodem2,/dev/tty.usbmodem3,/dev/tty.usbmodem4"
-
-function abort() {
- echo "ABORT: $*"
- exit 1
-}
-
-if [ ! -f ${MKFW} -o ! -f ${UPLOAD} ]; then
- abort "Missing tools ${MKFW} and/or ${UPLOAD}"
-fi
-if [ ! -f ${BINARY} ]; then
- abort "Missing nuttx binary in current directory."
-fi
-
-rm -f ${PAYLOAD}
-${MKFW} --board_id 5 --image ${BINARY} > ${PAYLOAD}
-${UPLOAD} --port ${PORTS} ${PAYLOAD}