aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--.gitignore3
-rw-r--r--Makefile211
-rw-r--r--ROMFS/.gitignore1
-rw-r--r--ROMFS/Makefile122
-rwxr-xr-xROMFS/px4fmu_default/logging/logconv.m (renamed from ROMFS/logging/logconv.m)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_AERT.mix (renamed from ROMFS/mixers/FMU_AERT.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_AET.mix (renamed from ROMFS/mixers/FMU_AET.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_Q.mix (renamed from ROMFS/mixers/FMU_Q.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_RET.mix (renamed from ROMFS/mixers/FMU_RET.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_X5.mix (renamed from ROMFS/mixers/FMU_X5.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_delta.mix50
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_hex_+.mix (renamed from ROMFS/mixers/FMU_hex_+.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_hex_x.mix (renamed from ROMFS/mixers/FMU_hex_x.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_octo_+.mix (renamed from ROMFS/mixers/FMU_octo_+.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_octo_x.mix (renamed from ROMFS/mixers/FMU_octo_x.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_pass.mix (renamed from ROMFS/mixers/FMU_pass.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_quad_+.mix (renamed from ROMFS/mixers/FMU_quad_+.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/FMU_quad_x.mix (renamed from ROMFS/mixers/FMU_quad_x.mix)0
-rw-r--r--ROMFS/px4fmu_default/mixers/README (renamed from ROMFS/mixers/README)0
-rw-r--r--ROMFS/scripts/rc.FMU_quad_x67
-rw-r--r--ROMFS/scripts/rc.PX4IO80
-rw-r--r--ROMFS/scripts/rc.PX4IOAR98
-rw-r--r--ROMFS/scripts/rc.boarddetect66
-rw-r--r--ROMFS/scripts/rc.jig10
-rw-r--r--ROMFS/scripts/rc.logging9
-rw-r--r--ROMFS/scripts/rc.sensors34
-rw-r--r--ROMFS/scripts/rc.standalone13
-rwxr-xr-xROMFS/scripts/rcS79
-rw-r--r--apps/examples/nsh/Makefile2
-rw-r--r--apps/nshlib/Makefile2
-rw-r--r--apps/px4/tests/Makefile2
-rw-r--r--apps/system/i2c/Makefile3
-rw-r--r--apps/systemcmds/bl_update/Makefile2
-rw-r--r--apps/systemcmds/boardinfo/Makefile2
-rw-r--r--apps/systemcmds/calibration/Makefile2
-rw-r--r--apps/systemcmds/delay_test/Makefile2
-rw-r--r--apps/systemcmds/eeprom/Makefile3
-rw-r--r--apps/systemcmds/mixer/Makefile2
-rw-r--r--apps/systemcmds/param/Makefile2
-rw-r--r--apps/systemcmds/perf/Makefile2
-rw-r--r--apps/systemcmds/preflight_check/Makefile2
-rw-r--r--apps/systemcmds/reboot/Makefile2
-rw-r--r--apps/systemcmds/top/Makefile2
-rw-r--r--apps/systemlib/Makefile14
-rw-r--r--makefiles/board_px4fmu.mk10
-rw-r--r--makefiles/board_px4io.mk10
-rw-r--r--makefiles/config_px4fmu_default.mk65
-rw-r--r--makefiles/config_px4io_default.mk5
-rw-r--r--makefiles/firmware.mk424
-rw-r--r--makefiles/module.mk210
-rw-r--r--makefiles/nuttx.mk75
-rw-r--r--makefiles/setup.mk81
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk264
-rw-r--r--makefiles/upload.mk41
-rw-r--r--nuttx/configs/px4fmu/include/nsh_romfsimg.h42
-rw-r--r--nuttx/configs/px4io/common/Make.defs3
-rw-r--r--platforms/empty.c3
-rw-r--r--src/modules/test/foo.c4
-rw-r--r--src/modules/test/module.mk4
59 files changed, 1422 insertions, 708 deletions
diff --git a/.gitignore b/.gitignore
index 8e9075ba4..46b347f72 100644
--- a/.gitignore
+++ b/.gitignore
@@ -43,7 +43,6 @@ nuttx/nuttx.hex
.settings
Firmware.sublime-workspace
.DS_Store
-nsh_romfsimg.h
cscope.out
.configX-e
nuttx-export.zip
@@ -55,3 +54,5 @@ mavlink/include/mavlink/v0.9/
core
.gdbinit
mkdeps
+Archives
+Build
diff --git a/Makefile b/Makefile
index e9442afd2..8f9e81dce 100644
--- a/Makefile
+++ b/Makefile
@@ -1,43 +1,53 @@
#
-# Top-level Makefile for building PX4 firmware images.
-#
-#
-# Note that this is a transitional process; the eventual goal is for this
-# project to slim down and simply generate PX4 link kits via the NuttX
-# 'make export' mechanism.
-#
+# 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.
#
#
-# Some useful paths.
+# Top-level Makefile for building PX4 firmware images.
#
-export PX4BASE = $(realpath $(dir $(lastword $(MAKEFILE_LIST))))
-export NUTTX_SRC = $(PX4BASE)/nuttx
-export NUTTX_APPS = $(PX4BASE)/apps
-export MAVLINK_SRC = $(PX4BASE)/mavlink
-export ROMFS_SRC = $(PX4BASE)/ROMFS
-export IMAGE_DIR = $(PX4BASE)/Images
#
-# Tools
+# Get path and tool configuration
#
-MKFW = $(PX4BASE)/Tools/px_mkfw.py
-UPLOADER = $(PX4BASE)/Tools/px_uploader.py
+export PX4_BASE := $(realpath $(dir $(lastword $(MAKEFILE_LIST))))/
+include $(PX4_BASE)makefiles/setup.mk
#
-# What are we currently configured for?
+# Canned firmware configurations that we build.
#
-CONFIGURED = $(PX4BASE)/.configured
-ifneq ($(wildcard $(CONFIGURED)),)
-export TARGET := $(shell cat $(CONFIGURED))
-endif
+CONFIGS ?= px4fmu_default px4io_default
#
-# What we will build
+# Boards that we build NuttX export kits for.
#
-FIRMWARE_BUNDLE = $(IMAGE_DIR)/$(TARGET).px4
-FIRMWARE_BINARY = $(IMAGE_DIR)/$(TARGET).bin
-FIRMWARE_PROTOTYPE = $(IMAGE_DIR)/$(TARGET).prototype
+BOARDS = px4fmu px4io
#
# Debugging
@@ -45,120 +55,93 @@ FIRMWARE_PROTOTYPE = $(IMAGE_DIR)/$(TARGET).prototype
MQUIET = --no-print-directory
#MQUIET = --print-directory
-all: $(FIRMWARE_BUNDLE)
+################################################################################
+# No user-serviceable parts below
+################################################################################
#
-# Generate a wrapped .px4 file from the built binary
+# If the user has listed a config as a target, strip it out and override CONFIGS.
#
-$(FIRMWARE_BUNDLE): $(FIRMWARE_BINARY) $(MKFW) $(FIRMWARE_PROTOTYPE)
- @echo Generating $@
- @$(MKFW) --prototype $(FIRMWARE_PROTOTYPE) \
- --git_identity $(PX4BASE) \
- --image $(FIRMWARE_BINARY) > $@
-
-#
-# Build the firmware binary.
-#
-.PHONY: $(FIRMWARE_BINARY)
-$(FIRMWARE_BINARY): setup_$(TARGET) configure-check
- @echo Building $@ for $(TARGET)
- @make -C $(NUTTX_SRC) -r $(MQUIET) all
- @cp $(NUTTX_SRC)/nuttx.bin $@
+EXPLICIT_CONFIGS := $(filter $(CONFIGS),$(MAKECMDGOALS))
+ifneq ($(EXPLICIT_CONFIGS),)
+CONFIGS := $(EXPLICIT_CONFIGS)
+.PHONY: $(EXPLICIT_CONFIGS)
+$(EXPLICIT_CONFIGS): all
+endif
#
-# The 'configure' targets select one particular firmware configuration
-# and makes it current.
+# Built products
#
-configure_px4fmu:
- @echo Configuring for px4fmu
- @make -C $(PX4BASE) distclean
- @cd $(NUTTX_SRC)/tools && /bin/sh configure.sh px4fmu/nsh
- @echo px4fmu > $(CONFIGURED)
-
-configure_px4io:
- @echo Configuring for px4io
- @make -C $(PX4BASE) distclean
- @cd $(NUTTX_SRC)/tools && /bin/sh configure.sh px4io/io
- @echo px4io > $(CONFIGURED)
-
-configure-check:
-ifeq ($(wildcard $(CONFIGURED)),)
- @echo
- @echo "Not configured - use 'make configure_px4fmu' or 'make configure_px4io' first"
- @echo
- @exit 1
-endif
+STAGED_FIRMWARES = $(foreach config,$(CONFIGS),$(IMAGE_DIR)$(config).px4)
+FIRMWARES = $(foreach config,$(CONFIGS),$(BUILD_DIR)$(config).build/firmware.px4)
+all: $(STAGED_FIRMWARES)
#
-# Per-configuration additional targets
+# Copy FIRMWARES into the image directory.
#
-.PHONY: px4fmu_setup
-setup_px4fmu:
- @echo Generating ROMFS
- @make -C $(ROMFS_SRC) all
-
-setup_px4io:
-
-# fake target to make configure-check happy if TARGET is not set
-setup_:
+$(STAGED_FIRMWARES): $(IMAGE_DIR)%.px4: $(BUILD_DIR)%.build/firmware.px4
+ @echo %% Copying $@
+ $(Q) $(COPY) $< $@
#
-# Firmware uploading.
+# Generate FIRMWARES.
#
-
-# serial port defaults by operating system.
-SYSTYPE = $(shell uname)
-ifeq ($(SYSTYPE),Darwin)
-SERIAL_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"
-endif
-ifeq ($(SYSTYPE),Linux)
-SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
-endif
-ifeq ($(SERIAL_PORTS),)
-SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
-endif
-
-upload: $(FIRMWARE_BUNDLE) $(UPLOADER)
- $(UPLOADER) --port $(SERIAL_PORTS) $(FIRMWARE_BUNDLE)
+.PHONY: $(FIRMWARES)
+$(BUILD_DIR)%.build/firmware.px4: config = $(patsubst $(BUILD_DIR)%.build/firmware.px4,%,$@)
+$(BUILD_DIR)%.build/firmware.px4: work_dir = $(BUILD_DIR)$(config).build/
+$(FIRMWARES): $(BUILD_DIR)%.build/firmware.px4:
+ @echo %%%%
+ @echo %%%% Building $(config) in $(work_dir)
+ @echo %%%%
+ $(Q) mkdir -p $(work_dir)
+ $(Q) make -C $(work_dir) \
+ -f $(PX4_MK_DIR)firmware.mk \
+ CONFIG=$(config) \
+ WORK_DIR=$(work_dir) \
+ firmware
#
-# JTAG firmware uploading with OpenOCD
+# Build the NuttX export archives.
#
-ifeq ($(JTAGCONFIG),)
-JTAGCONFIG=interface/olimex-jtag-tiny.cfg
-endif
-
-upload-jtag-px4fmu:
- @echo Attempting to flash PX4FMU board via JTAG
- @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
-
-upload-jtag-px4io: all
- @echo Attempting to flash PX4IO board via JTAG
- @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown
-
+# Note that there are no explicit dependencies extended from these
+# archives. If NuttX is updated, the user is expected to rebuild the
+# archives/build area manually. Likewise, when the 'archives' target is
+# invoked, all archives are always rebuilt.
+#
+# XXX Should support fetching/unpacking from a separate directory to permit
+# downloads of the prebuilt archives as well...
#
-# Hacks and fixups
+# XXX PX4IO configuration name is bad - NuttX configs should probably all be "px4"
#
+NUTTX_ARCHIVES = $(foreach board,$(BOARDS),$(ARCHIVE_DIR)$(board).export)
+.PHONY: archives
+archives: $(NUTTX_ARCHIVES)
-ifeq ($(SYSTYPE),Darwin)
-# PATH inherited by Eclipse may not include toolchain install location
-export PATH := $(PATH):/usr/local/bin
-endif
+$(ARCHIVE_DIR)%.export: board = $(notdir $(basename $@))
+$(ARCHIVE_DIR)%.export: configuration = $(if $(filter $(board),px4io),io,nsh)
+$(NUTTX_ARCHIVES): $(ARCHIVE_DIR)%.export: $(NUTTX_SRC) $(NUTTX_APPS)
+ @echo %% Configuring NuttX for $(board)
+ $(Q) (cd $(NUTTX_SRC) && $(RMDIR) nuttx-export)
+ $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
+ @echo %% Exporting NuttX for $(board)
+ $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) export
+ $(Q) mkdir -p $(dir $@)
+ $(Q) $(COPY) $(NUTTX_SRC)nuttx-export.zip $@
#
# Cleanup targets. 'clean' should remove all built products and force
# a complete re-compilation, 'distclean' should remove everything
# that's generated leaving only files that are in source control.
#
-.PHONY: clean upload-jtag-px4fmu
+.PHONY: clean
clean:
- @make -C $(NUTTX_SRC) -r $(MQUIET) distclean
- @make -C $(ROMFS_SRC) -r $(MQUIET) clean
+ $(Q) $(RMDIR) $(BUILD_DIR)*.build
+ $(Q) $(REMOVE) -f $(IMAGE_DIR)*.px4
.PHONY: distclean
-distclean:
- @rm -f $(CONFIGURED)
- @make -C $(NUTTX_SRC) -r $(MQUIET) distclean
- @make -C $(ROMFS_SRC) -r $(MQUIET) distclean
+distclean: clean
+ $(Q) $(REMOVE) -f $(ARCHIVE_DIR)*.export
+ $(Q) make -C $(NUTTX_SRC) -r $(MQUIET) distclean
diff --git a/ROMFS/.gitignore b/ROMFS/.gitignore
deleted file mode 100644
index 30d3d7fe5..000000000
--- a/ROMFS/.gitignore
+++ /dev/null
@@ -1 +0,0 @@
-/img
diff --git a/ROMFS/Makefile b/ROMFS/Makefile
deleted file mode 100644
index ed39ab825..000000000
--- a/ROMFS/Makefile
+++ /dev/null
@@ -1,122 +0,0 @@
-#
-# Makefile to generate a PX4FMU ROMFS image.
-#
-# In normal use, 'make install' will generate a new ROMFS header and place it
-# into the px4fmu configuration in the appropriate location.
-#
-
-#
-# Directories of interest
-#
-SRCROOT ?= $(dir $(lastword $(MAKEFILE_LIST)))
-BUILDROOT ?= $(SRCROOT)/img
-ROMFS_HEADER ?= $(SRCROOT)/../nuttx/configs/px4fmu/include/nsh_romfsimg.h
-
-#
-# List of files to install in the ROMFS, specified as <source>~<destination>
-#
-ROMFS_FSSPEC := $(SRCROOT)/scripts/rcS~init.d/rcS \
- $(SRCROOT)/scripts/rc.sensors~init.d/rc.sensors \
- $(SRCROOT)/scripts/rc.logging~init.d/rc.logging \
- $(SRCROOT)/scripts/rc.standalone~init.d/rc.standalone \
- $(SRCROOT)/scripts/rc.PX4IO~init.d/rc.PX4IO \
- $(SRCROOT)/scripts/rc.PX4IOAR~init.d/rc.PX4IOAR \
- $(SRCROOT)/scripts/rc.FMU_quad_x~init.d/rc.FMU_quad_x \
- $(SRCROOT)/scripts/rc.usb~init.d/rc.usb \
- $(SRCROOT)/scripts/rc.hil~init.d/rc.hil \
- $(SRCROOT)/mixers/FMU_pass.mix~mixers/FMU_pass.mix \
- $(SRCROOT)/mixers/FMU_Q.mix~mixers/FMU_Q.mix \
- $(SRCROOT)/mixers/FMU_X5.mix~mixers/FMU_X5.mix \
- $(SRCROOT)/mixers/FMU_AERT.mix~mixers/FMU_AERT.mix \
- $(SRCROOT)/mixers/FMU_AET.mix~mixers/FMU_AET.mix \
- $(SRCROOT)/mixers/FMU_RET.mix~mixers/FMU_ERT.mix \
- $(SRCROOT)/mixers/FMU_quad_x.mix~mixers/FMU_quad_x.mix \
- $(SRCROOT)/mixers/FMU_quad_+.mix~mixers/FMU_quad_+.mix \
- $(SRCROOT)/mixers/FMU_hex_x.mix~mixers/FMU_hex_x.mix \
- $(SRCROOT)/mixers/FMU_hex_+.mix~mixers/FMU_hex_+.mix \
- $(SRCROOT)/mixers/FMU_octo_x.mix~mixers/FMU_octo_x.mix \
- $(SRCROOT)/mixers/FMU_octo_+.mix~mixers/FMU_octo_+.mix \
- $(SRCROOT)/logging/logconv.m~logging/logconv.m
-
-# the EXTERNAL_SCRIPTS variable is used to add out of tree scripts
-# to ROMFS.
-ROMFS_FSSPEC += $(EXTERNAL_SCRIPTS)
-
-#
-# Add the PX4IO firmware to the spec if someone has dropped it into the
-# source directory, or otherwise specified its location.
-#
-# Normally this is only something you'd do when working on PX4IO; most
-# users will upgrade with firmware off the microSD card.
-#
-PX4IO_FIRMWARE ?= $(SRCROOT)/px4io.bin
-ifneq ($(wildcard $(PX4IO_FIRMWARE)),)
-ROMFS_FSSPEC += $(PX4IO_FIRMWARE)~px4io.bin
-endif
-
-################################################################################
-# No user-serviceable parts below
-################################################################################
-
-#
-# Just the source files from the ROMFS spec, so that we can fail cleanly if they don't
-# exist
-#
-ROMFS_SRCFILES = $(foreach spec,$(ROMFS_FSSPEC),$(firstword $(subst ~, ,$(spec))))
-
-#
-# Just the destination directories from the ROMFS spec
-#
-ROMFS_DIRS = $(sort $(dir $(foreach spec,$(ROMFS_FSSPEC),$(lastword $(subst ~, ,$(spec))))))
-
-
-#
-# Intermediate products
-#
-ROMFS_IMG = $(BUILDROOT)/romfs.img
-ROMFS_WORKDIR = $(BUILDROOT)/romfs
-
-#
-# Convenience target for rebuilding the ROMFS header
-#
-all: $(ROMFS_HEADER)
-
-$(ROMFS_HEADER): $(ROMFS_IMG) $(dir $(ROMFS_HEADER))
- @echo Generating the ROMFS header...
- @(cd $(dir $(ROMFS_IMG)) && xxd -i $(notdir $(ROMFS_IMG))) | sed -e 's/char/const char/' > $@
-
-$(ROMFS_IMG): $(ROMFS_WORKDIR)
- @echo Generating the ROMFS image...
- @genromfs -f $@ -d $(ROMFS_WORKDIR) -V "NSHInitVol"
-
-$(ROMFS_WORKDIR): $(ROMFS_SRCFILES)
- @echo Rebuilding the ROMFS work area...
- @rm -rf $(ROMFS_WORKDIR)
- @mkdir -p $(ROMFS_WORKDIR)
- @for dir in $(ROMFS_DIRS) ; do mkdir -p $(ROMFS_WORKDIR)/$$dir; done
- @for spec in $(ROMFS_FSSPEC) ; do \
- echo $$spec | sed -e 's%^.*~% %' ;\
- `echo "cp $$spec" | sed -e 's%~% $(ROMFS_WORKDIR)/%'` ;\
- done
-
-$(BUILDROOT):
- @mkdir -p $(BUILDROOT)
-
-clean:
- @rm -rf $(BUILDROOT)
-
-distclean: clean
- @rm -f $(PX4IO_FIRMWARE) $(ROMFS_HEADER)
-
-.PHONY: all install clean distclean
-
-#
-# Hacks and fixups
-#
-SYSTYPE = $(shell uname)
-
-ifeq ($(SYSTYPE),Darwin)
-# PATH inherited by Eclipse may not include toolchain install location
-export PATH := $(PATH):/usr/local/bin
-endif
-
diff --git a/ROMFS/logging/logconv.m b/ROMFS/px4fmu_default/logging/logconv.m
index 92ee01413..92ee01413 100755
--- a/ROMFS/logging/logconv.m
+++ b/ROMFS/px4fmu_default/logging/logconv.m
diff --git a/ROMFS/mixers/FMU_AERT.mix b/ROMFS/px4fmu_default/mixers/FMU_AERT.mix
index 75e82bb00..75e82bb00 100644
--- a/ROMFS/mixers/FMU_AERT.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_AERT.mix
diff --git a/ROMFS/mixers/FMU_AET.mix b/ROMFS/px4fmu_default/mixers/FMU_AET.mix
index 20cb88b91..20cb88b91 100644
--- a/ROMFS/mixers/FMU_AET.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_AET.mix
diff --git a/ROMFS/mixers/FMU_Q.mix b/ROMFS/px4fmu_default/mixers/FMU_Q.mix
index ebcb66b24..ebcb66b24 100644
--- a/ROMFS/mixers/FMU_Q.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_Q.mix
diff --git a/ROMFS/mixers/FMU_RET.mix b/ROMFS/px4fmu_default/mixers/FMU_RET.mix
index 95beb8927..95beb8927 100644
--- a/ROMFS/mixers/FMU_RET.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_RET.mix
diff --git a/ROMFS/mixers/FMU_X5.mix b/ROMFS/px4fmu_default/mixers/FMU_X5.mix
index 9f81e1dc3..9f81e1dc3 100644
--- a/ROMFS/mixers/FMU_X5.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_X5.mix
diff --git a/ROMFS/px4fmu_default/mixers/FMU_delta.mix b/ROMFS/px4fmu_default/mixers/FMU_delta.mix
new file mode 100644
index 000000000..981466704
--- /dev/null
+++ b/ROMFS/px4fmu_default/mixers/FMU_delta.mix
@@ -0,0 +1,50 @@
+Delta-wing mixer for PX4FMU
+===========================
+
+This file defines mixers suitable for controlling a delta wing aircraft using
+PX4FMU. The configuration assumes the elevon servos are connected to PX4FMU
+servo outputs 0 and 1 and the motor speed control to output 3. Output 2 is
+assumed to be unused.
+
+Inputs to the mixer come from channel group 0 (vehicle attitude), channels 0
+(roll), 1 (pitch) and 3 (thrust).
+
+See the README for more information on the scaler format.
+
+Elevon mixers
+-------------
+Three scalers total (output, roll, pitch).
+
+On the assumption that the two elevon servos are physically reversed, the pitch
+input is inverted between the two servos.
+
+The scaling factor for roll inputs is adjusted to implement differential travel
+for the elevons.
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 3000 5000 0 -10000 10000
+S: 0 1 5000 5000 0 -10000 10000
+
+M: 2
+O: 10000 10000 0 -10000 10000
+S: 0 0 5000 3000 0 -10000 10000
+S: 0 1 -5000 -5000 0 -10000 10000
+
+Output 2
+--------
+This mixer is empty.
+
+Z:
+
+Motor speed mixer
+-----------------
+Two scalers total (output, thrust).
+
+This mixer generates a full-range output (-1 to 1) from an input in the (0 - 1)
+range. Inputs below zero are treated as zero.
+
+M: 1
+O: 10000 10000 0 -10000 10000
+S: 0 3 0 20000 -10000 -10000 10000
+
diff --git a/ROMFS/mixers/FMU_hex_+.mix b/ROMFS/px4fmu_default/mixers/FMU_hex_+.mix
index b5e38ce9e..b5e38ce9e 100644
--- a/ROMFS/mixers/FMU_hex_+.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_hex_+.mix
diff --git a/ROMFS/mixers/FMU_hex_x.mix b/ROMFS/px4fmu_default/mixers/FMU_hex_x.mix
index 8e8d122ad..8e8d122ad 100644
--- a/ROMFS/mixers/FMU_hex_x.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_hex_x.mix
diff --git a/ROMFS/mixers/FMU_octo_+.mix b/ROMFS/px4fmu_default/mixers/FMU_octo_+.mix
index 2cb70e814..2cb70e814 100644
--- a/ROMFS/mixers/FMU_octo_+.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_octo_+.mix
diff --git a/ROMFS/mixers/FMU_octo_x.mix b/ROMFS/px4fmu_default/mixers/FMU_octo_x.mix
index edc71f013..edc71f013 100644
--- a/ROMFS/mixers/FMU_octo_x.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_octo_x.mix
diff --git a/ROMFS/mixers/FMU_pass.mix b/ROMFS/px4fmu_default/mixers/FMU_pass.mix
index e9a81f2bb..e9a81f2bb 100644
--- a/ROMFS/mixers/FMU_pass.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_pass.mix
diff --git a/ROMFS/mixers/FMU_quad_+.mix b/ROMFS/px4fmu_default/mixers/FMU_quad_+.mix
index dfdf1d58e..dfdf1d58e 100644
--- a/ROMFS/mixers/FMU_quad_+.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_quad_+.mix
diff --git a/ROMFS/mixers/FMU_quad_x.mix b/ROMFS/px4fmu_default/mixers/FMU_quad_x.mix
index 12a3bee20..12a3bee20 100644
--- a/ROMFS/mixers/FMU_quad_x.mix
+++ b/ROMFS/px4fmu_default/mixers/FMU_quad_x.mix
diff --git a/ROMFS/mixers/README b/ROMFS/px4fmu_default/mixers/README
index 6649c53c2..6649c53c2 100644
--- a/ROMFS/mixers/README
+++ b/ROMFS/px4fmu_default/mixers/README
diff --git a/ROMFS/scripts/rc.FMU_quad_x b/ROMFS/scripts/rc.FMU_quad_x
deleted file mode 100644
index 8787443ea..000000000
--- a/ROMFS/scripts/rc.FMU_quad_x
+++ /dev/null
@@ -1,67 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU with PWM outputs.
-#
-
-# Disable the USB interface
-set USB no
-
-# Disable autostarting other apps
-set MODE custom
-
-echo "[init] doing PX4FMU Quad startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/parameters
-if [ -f /fs/microsd/parameters ]
-then
- param load /fs/microsd/parameters
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Start MAVLink
-#
-mavlink start -d /dev/ttyS0 -b 57600
-usleep 5000
-
-#
-# Start the sensors and test them.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
-echo "[init] starting PWM output"
-fmu mode_pwm
-mixer load /dev/pwm_output /etc/mixers/FMU_quad_x.mix
-
-#
-# Start attitude control
-#
-multirotor_att_control start
-
-echo "[init] startup done, exiting"
-exit \ No newline at end of file
diff --git a/ROMFS/scripts/rc.PX4IO b/ROMFS/scripts/rc.PX4IO
deleted file mode 100644
index 1e3963b9a..000000000
--- a/ROMFS/scripts/rc.PX4IO
+++ /dev/null
@@ -1,80 +0,0 @@
-#!nsh
-
-# Disable USB and autostart
-set USB no
-set MODE camflyer
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Load microSD params
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/parameters
-if [ -f /fs/microsd/parameters ]
-then
- param load /fs/microsd/parameters
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 1
-
-#
-# Start the sensors.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start MAVLink
-#
-mavlink start -d /dev/ttyS1 -b 57600
-usleep 5000
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start GPS interface
-#
-gps start
-
-#
-# Start the attitude estimator
-#
-kalman_demo start
-
-#
-# Start PX4IO interface
-#
-px4io start
-
-#
-# Load mixer and start controllers
-#
-mixer load /dev/pwm_output /etc/mixers/FMU_Q.mix
-control_demo start
-
-#
-# Start logging
-#
-sdlog start -s 10
-
-#
-# Start system state
-#
-if blinkm start
-then
- echo "using BlinkM for state indication"
- blinkm systemstate
-else
- echo "no BlinkM found, OK."
-fi
diff --git a/ROMFS/scripts/rc.PX4IOAR b/ROMFS/scripts/rc.PX4IOAR
deleted file mode 100644
index 72df68e35..000000000
--- a/ROMFS/scripts/rc.PX4IOAR
+++ /dev/null
@@ -1,98 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU on PX4IOAR carrier board.
-#
-
-# Disable the USB interface
-set USB no
-
-# Disable autostarting other apps
-set MODE ardrone
-
-echo "[init] doing PX4IOAR startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-#
-# Init the parameter storage
-#
-echo "[init] loading microSD params"
-param select /fs/microsd/parameters
-if [ -f /fs/microsd/parameters ]
-then
- param load /fs/microsd/parameters
-fi
-
-#
-# Force some key parameters to sane values
-# MAV_TYPE 1 = fixed wing, 2 = quadrotor, 13 = hexarotor
-# see https://pixhawk.ethz.ch/mavlink/
-#
-param set MAV_TYPE 2
-
-#
-# Start the sensors.
-#
-sh /etc/init.d/rc.sensors
-
-#
-# Start MAVLink
-#
-mavlink start -d /dev/ttyS0 -b 57600
-usleep 5000
-
-#
-# Start the commander.
-#
-commander start
-
-#
-# Start the attitude estimator
-#
-attitude_estimator_ekf start
-
-#
-# Configure PX4FMU for operation with PX4IOAR
-#
-fmu mode_gpio_serial
-
-#
-# Fire up the multi rotor attitude controller
-#
-multirotor_att_control start
-
-#
-# Fire up the AR.Drone interface.
-#
-ardrone_interface start -d /dev/ttyS1
-
-#
-# Start GPS capture
-#
-gps start
-
-#
-# Start logging
-#
-sdlog start -s 10
-
-#
-# Start system state
-#
-if blinkm start
-then
- echo "using BlinkM for state indication"
- blinkm systemstate
-else
- echo "no BlinkM found, OK."
-fi
-
-#
-# startup is done; we don't want the shell because we
-# use the same UART for telemetry
-#
-echo "[init] startup done"
-exit \ No newline at end of file
diff --git a/ROMFS/scripts/rc.boarddetect b/ROMFS/scripts/rc.boarddetect
deleted file mode 100644
index f233e51df..000000000
--- a/ROMFS/scripts/rc.boarddetect
+++ /dev/null
@@ -1,66 +0,0 @@
-#!nsh
-#
-# If we are still in flight mode, work out what airframe
-# configuration we have and start up accordingly.
-#
-if [ $MODE != autostart ]
-then
- echo "[init] automatic startup cancelled by user script"
-else
- echo "[init] detecting attached hardware..."
-
- #
- # Assume that we are PX4FMU in standalone mode
- #
- set BOARD PX4FMU
-
- #
- # Are we attached to a PX4IOAR (AR.Drone carrier board)?
- #
- if boardinfo test name PX4IOAR
- then
- set BOARD PX4IOAR
- if [ -f /etc/init.d/rc.PX4IOAR ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IOAR"
- usleep 500
- sh /etc/init.d/rc.PX4IOAR
- fi
- else
- echo "[init] PX4IOAR not detected"
- fi
-
- #
- # Are we attached to a PX4IO?
- #
- if boardinfo test name PX4IO
- then
- set BOARD PX4IO
- if [ -f /etc/init.d/rc.PX4IO ]
- then
- echo "[init] reading /etc/init.d/rc.PX4IO"
- usleep 500
- sh /etc/init.d/rc.PX4IO
- fi
- else
- echo "[init] PX4IO not detected"
- fi
-
- #
- # Looks like we are stand-alone
- #
- if [ $BOARD == PX4FMU ]
- then
- echo "[init] no expansion board detected"
- if [ -f /etc/init.d/rc.standalone ]
- then
- echo "[init] reading /etc/init.d/rc.standalone"
- sh /etc/init.d/rc.standalone
- fi
- fi
-
- #
- # We may not reach here if the airframe-specific script exits the shell.
- #
- echo "[init] startup done."
-fi \ No newline at end of file
diff --git a/ROMFS/scripts/rc.jig b/ROMFS/scripts/rc.jig
deleted file mode 100644
index e2b5d8f30..000000000
--- a/ROMFS/scripts/rc.jig
+++ /dev/null
@@ -1,10 +0,0 @@
-#!nsh
-#
-# Test jig startup script
-#
-
-echo "[testing] doing production test.."
-
-tests jig
-
-echo "[testing] testing done"
diff --git a/ROMFS/scripts/rc.logging b/ROMFS/scripts/rc.logging
deleted file mode 100644
index 09c2d00d1..000000000
--- a/ROMFS/scripts/rc.logging
+++ /dev/null
@@ -1,9 +0,0 @@
-#!nsh
-#
-# Initialise logging services.
-#
-
-if [ -d /fs/microsd ]
-then
- sdlog start
-fi
diff --git a/ROMFS/scripts/rc.sensors b/ROMFS/scripts/rc.sensors
deleted file mode 100644
index 42c2f52e9..000000000
--- a/ROMFS/scripts/rc.sensors
+++ /dev/null
@@ -1,34 +0,0 @@
-#!nsh
-#
-# Standard startup script for PX4FMU onboard sensor drivers.
-#
-
-#
-# Start sensor drivers here.
-#
-
-ms5611 start
-adc start
-
-if mpu6000 start
-then
- echo "using MPU6000 and HMC5883L"
- hmc5883 start
-else
- echo "using L3GD20 and LSM303D"
- l3gd20 start
- lsm303 start
-fi
-
-#
-# Start the sensor collection task.
-# IMPORTANT: this also loads param offsets
-# ALWAYS start this task before the
-# preflight_check.
-#
-sensors start
-
-#
-# Check sensors - run AFTER 'sensors start'
-#
-preflight_check \ No newline at end of file
diff --git a/ROMFS/scripts/rc.standalone b/ROMFS/scripts/rc.standalone
deleted file mode 100644
index 67e95215b..000000000
--- a/ROMFS/scripts/rc.standalone
+++ /dev/null
@@ -1,13 +0,0 @@
-#!nsh
-#
-# Flight startup script for PX4FMU standalone configuration.
-#
-
-echo "[init] doing standalone PX4FMU startup..."
-
-#
-# Start the ORB
-#
-uorb start
-
-echo "[init] startup done"
diff --git a/ROMFS/scripts/rcS b/ROMFS/scripts/rcS
deleted file mode 100755
index 89a767879..000000000
--- a/ROMFS/scripts/rcS
+++ /dev/null
@@ -1,79 +0,0 @@
-#!nsh
-#
-# PX4FMU startup script.
-#
-# This script is responsible for:
-#
-# - mounting the microSD card (if present)
-# - running the user startup script from the microSD card (if present)
-# - detecting the configuration of the system and picking a suitable
-# startup script to continue with
-#
-# Note: DO NOT add configuration-specific commands to this script;
-# add them to the per-configuration scripts instead.
-#
-
-#
-# Default to auto-start mode. An init script on the microSD card
-# can change this to prevent automatic startup of the flight script.
-#
-set MODE autostart
-set USB autoconnect
-
-#
-# Start playing the startup tune
-#
-tone_alarm start
-
-#
-# Try to mount the microSD card.
-#
-echo "[init] looking for microSD..."
-if mount -t vfat /dev/mmcsd0 /fs/microsd
-then
- echo "[init] card mounted at /fs/microsd"
-else
- echo "[init] no microSD card found"
-fi
-
-#
-# Look for an init script on the microSD card.
-#
-# To prevent automatic startup in the current flight mode,
-# the script should set MODE to some other value.
-#
-if [ -f /fs/microsd/etc/rc ]
-then
- echo "[init] reading /fs/microsd/etc/rc"
- sh /fs/microsd/etc/rc
-fi
-# Also consider rc.txt files
-if [ -f /fs/microsd/etc/rc.txt ]
-then
- echo "[init] reading /fs/microsd/etc/rc.txt"
- sh /fs/microsd/etc/rc.txt
-fi
-
-#
-# Check for USB host
-#
-if [ $USB != autoconnect ]
-then
- echo "[init] not connecting USB"
-else
- if sercon
- then
- echo "[init] USB interface connected"
- else
- echo "[init] No USB connected"
- fi
-fi
-
-# if this is an APM build then there will be a rc.APM script
-# from an EXTERNAL_SCRIPTS build option
-if [ -f /etc/init.d/rc.APM ]
-then
- echo Running rc.APM
- # if APM startup is successful then nsh will exit
- sh /etc/init.d/rc.APM
-fi
diff --git a/apps/examples/nsh/Makefile b/apps/examples/nsh/Makefile
index c7d212fc2..ad687958f 100644
--- a/apps/examples/nsh/Makefile
+++ b/apps/examples/nsh/Makefile
@@ -64,6 +64,8 @@ ROOTDEPPATH = --dep-path .
VPATH =
+MAXOPTIMIZATION = -Os
+
all: .built
.PHONY: clean depend distclean
diff --git a/apps/nshlib/Makefile b/apps/nshlib/Makefile
index 76cdac40d..4256a1091 100644
--- a/apps/nshlib/Makefile
+++ b/apps/nshlib/Makefile
@@ -107,6 +107,8 @@ endif
ROOTDEPPATH = --dep-path .
VPATH =
+MAXOPTIMIZATION = -Os
+
# Build targets
all: .built
diff --git a/apps/px4/tests/Makefile b/apps/px4/tests/Makefile
index cb1c3c618..e27222b9d 100644
--- a/apps/px4/tests/Makefile
+++ b/apps/px4/tests/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 12000
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os \ No newline at end of file
diff --git a/apps/system/i2c/Makefile b/apps/system/i2c/Makefile
index 1ed7a2fae..7f0e6005b 100644
--- a/apps/system/i2c/Makefile
+++ b/apps/system/i2c/Makefile
@@ -64,8 +64,9 @@ VPATH =
APPNAME = i2c
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
+MAXOPTIMIZATION = -Os
-# Build targets
+# Build Targets
all: .built
.PHONY: context .depend depend clean distclean
diff --git a/apps/systemcmds/bl_update/Makefile b/apps/systemcmds/bl_update/Makefile
index 9d0e156f6..d05493577 100644
--- a/apps/systemcmds/bl_update/Makefile
+++ b/apps/systemcmds/bl_update/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/boardinfo/Makefile b/apps/systemcmds/boardinfo/Makefile
index 753a6843e..6f1be149c 100644
--- a/apps/systemcmds/boardinfo/Makefile
+++ b/apps/systemcmds/boardinfo/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/calibration/Makefile b/apps/systemcmds/calibration/Makefile
index aa1aa7761..a1735962e 100644
--- a/apps/systemcmds/calibration/Makefile
+++ b/apps/systemcmds/calibration/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_MAX - 1
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/delay_test/Makefile b/apps/systemcmds/delay_test/Makefile
index d30fcba27..e54cf2f4e 100644
--- a/apps/systemcmds/delay_test/Makefile
+++ b/apps/systemcmds/delay_test/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/eeprom/Makefile b/apps/systemcmds/eeprom/Makefile
index 2f3db0fdc..58c8cb5ec 100644
--- a/apps/systemcmds/eeprom/Makefile
+++ b/apps/systemcmds/eeprom/Makefile
@@ -38,5 +38,8 @@
APPNAME = eeprom
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
+MAXOPTIMIZATION = -Os
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/mixer/Makefile b/apps/systemcmds/mixer/Makefile
index b016ddc57..3d8ac38cb 100644
--- a/apps/systemcmds/mixer/Makefile
+++ b/apps/systemcmds/mixer/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/param/Makefile b/apps/systemcmds/param/Makefile
index 603746a20..f19cadbb6 100644
--- a/apps/systemcmds/param/Makefile
+++ b/apps/systemcmds/param/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/perf/Makefile b/apps/systemcmds/perf/Makefile
index 0134c9948..f8bab41b6 100644
--- a/apps/systemcmds/perf/Makefile
+++ b/apps/systemcmds/perf/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/preflight_check/Makefile b/apps/systemcmds/preflight_check/Makefile
index f138e2640..98aadaa86 100644
--- a/apps/systemcmds/preflight_check/Makefile
+++ b/apps/systemcmds/preflight_check/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/reboot/Makefile b/apps/systemcmds/reboot/Makefile
index 9609a24fd..15dd19982 100644
--- a/apps/systemcmds/reboot/Makefile
+++ b/apps/systemcmds/reboot/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemcmds/top/Makefile b/apps/systemcmds/top/Makefile
index c45775f4b..f58f9212e 100644
--- a/apps/systemcmds/top/Makefile
+++ b/apps/systemcmds/top/Makefile
@@ -40,3 +40,5 @@ PRIORITY = SCHED_PRIORITY_DEFAULT - 10
STACKSIZE = 3000
include $(APPDIR)/mk/app.mk
+
+MAXOPTIMIZATION = -Os
diff --git a/apps/systemlib/Makefile b/apps/systemlib/Makefile
index 8240dbe43..b2e233a92 100644
--- a/apps/systemlib/Makefile
+++ b/apps/systemlib/Makefile
@@ -44,17 +44,9 @@ CSRCS = err.c \
cpuload.c \
getopt_long.c \
up_cxxinitialize.c \
- airspeed.c
-
-# ppm_decode.c \
-
-#
-# XXX this really should be a CONFIG_* test
-#
-ifeq ($(TARGET),px4fmu)
-CSRCS += systemlib.c \
pid/pid.c \
- geo/geo.c
-endif
+ geo/geo.c \
+ systemlib.c \
+ airspeed.c
include $(APPDIR)/mk/app.mk
diff --git a/makefiles/board_px4fmu.mk b/makefiles/board_px4fmu.mk
new file mode 100644
index 000000000..959e4ed26
--- /dev/null
+++ b/makefiles/board_px4fmu.mk
@@ -0,0 +1,10 @@
+#
+# Platform-specific definitions for the PX4FMU
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM4F
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/board_px4io.mk b/makefiles/board_px4io.mk
new file mode 100644
index 000000000..275014aba
--- /dev/null
+++ b/makefiles/board_px4io.mk
@@ -0,0 +1,10 @@
+#
+# Platform-specific definitions for the PX4IO
+#
+
+#
+# Configure the toolchain
+#
+CONFIG_ARCH = CORTEXM3
+
+include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
diff --git a/makefiles/config_px4fmu_default.mk b/makefiles/config_px4fmu_default.mk
new file mode 100644
index 000000000..a6d766511
--- /dev/null
+++ b/makefiles/config_px4fmu_default.mk
@@ -0,0 +1,65 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/$(CONFIG)
+
+#
+# Transitional support - add commands from the NuttX export archive.
+#
+# In general, these should move to modules over time.
+#
+# Each entry here is <command>.<priority>.<stacksize>.<entrypoint> but we use a helper macro
+# to make the table a bit more readable.
+#
+define _B
+ $(strip $1).$(or $(strip $2),SCHED_PRIORITY_DEFAULT).$(or $(strip $3),CONFIG_PTHREAD_STACK_DEFAULT).$(strip $4)
+endef
+
+# command priority stack entrypoint
+BUILTIN_COMMANDS := \
+ $(call _B, adc, , 2048, adc_main ) \
+ $(call _B, ardrone_interface, SCHED_PRIORITY_MAX-15, 2048, ardrone_interface_main ) \
+ $(call _B, attitude_estimator_ekf, , 2048, attitude_estimator_ekf_main) \
+ $(call _B, bl_update, , 4096, bl_update_main ) \
+ $(call _B, blinkm, , 2048, blinkm_main ) \
+ $(call _B, bma180, , 2048, bma180_main ) \
+ $(call _B, boardinfo, , 2048, boardinfo_main ) \
+ $(call _B, commander, SCHED_PRIORITY_MAX-30, 2048, commander_main ) \
+ $(call _B, control_demo, , 2048, control_demo_main ) \
+ $(call _B, delay_test, , 2048, delay_test_main ) \
+ $(call _B, eeprom, , 4096, eeprom_main ) \
+ $(call _B, fixedwing_att_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_att_control_main ) \
+ $(call _B, fixedwing_pos_control, SCHED_PRIORITY_MAX-30, 2048, fixedwing_pos_control_main ) \
+ $(call _B, fmu, , 2048, fmu_main ) \
+ $(call _B, gps, , 2048, gps_main ) \
+ $(call _B, hil, , 2048, hil_main ) \
+ $(call _B, hmc5883, , 4096, hmc5883_main ) \
+ $(call _B, hott_telemetry, , 2048, hott_telemetry_main ) \
+ $(call _B, kalman_demo, SCHED_PRIORITY_MAX-30, 2048, kalman_demo_main ) \
+ $(call _B, l3gd20, , 2048, l3gd20_main ) \
+ $(call _B, math_demo, , 8192, math_demo_main ) \
+ $(call _B, mavlink, , 2048, mavlink_main ) \
+ $(call _B, mavlink_onboard, , 2048, mavlink_onboard_main ) \
+ $(call _B, mixer, , 4096, mixer_main ) \
+ $(call _B, mpu6000, , 4096, mpu6000_main ) \
+ $(call _B, ms5611, , 2048, ms5611_main ) \
+ $(call _B, multirotor_att_control, SCHED_PRIORITY_MAX-15, 2048, multirotor_att_control_main) \
+ $(call _B, multirotor_pos_control, SCHED_PRIORITY_MAX-25, 2048, multirotor_pos_control_main) \
+ $(call _B, param, , 4096, param_main ) \
+ $(call _B, perf, , 2048, perf_main ) \
+ $(call _B, position_estimator, , 4096, position_estimator_main ) \
+ $(call _B, preflight_check, , 2048, preflight_check_main ) \
+ $(call _B, px4io, , 2048, px4io_main ) \
+ $(call _B, reboot, , 2048, reboot_main ) \
+ $(call _B, sdlog, SCHED_PRIORITY_MAX-30, 2048, sdlog_main ) \
+ $(call _B, sensors, SCHED_PRIORITY_MAX-5, 4096, sensors_main ) \
+ $(call _B, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main ) \
+ $(call _B, tests, , 12000, tests_main ) \
+ $(call _B, tone_alarm, , 2048, tone_alarm_main ) \
+ $(call _B, top, SCHED_PRIORITY_DEFAULT-10, 3000, top_main ) \
+ $(call _B, uorb, , 4096, uorb_main )
diff --git a/makefiles/config_px4io_default.mk b/makefiles/config_px4io_default.mk
new file mode 100644
index 000000000..dc774fe63
--- /dev/null
+++ b/makefiles/config_px4io_default.mk
@@ -0,0 +1,5 @@
+#
+# Makefile for the px4io_default configuration
+#
+
+# ... nothing here yet
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
new file mode 100644
index 000000000..dad57d531
--- /dev/null
+++ b/makefiles/firmware.mk
@@ -0,0 +1,424 @@
+#
+# 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.
+#
+
+#
+# Generic Makefile for PX4 firmware images.
+#
+# Requires:
+#
+# BOARD
+# Must be set to a board name known to the PX4 distribution (as
+# we need a corresponding NuttX export archive to link with).
+#
+# Optional:
+#
+# MODULES
+# Contains a list of module paths or path fragments used
+# to find modules. The names listed here are searched in
+# the following directories:
+# <absolute path>
+# $(MODULE_SEARCH_DIRS)
+# WORK_DIR
+# MODULE_SRC
+# PX4_MODULE_SRC
+#
+# Application directories are expected to contain a module.mk
+# file which provides build configuration for the module. See
+# makefiles/module.mk for more details.
+#
+# BUILTIN_COMMANDS
+# Contains a list of built-in commands not explicitly provided
+# by modules / libraries. Each entry in this list is formatted
+# as <command>.<priority>.<stacksize>.<entrypoint>
+#
+# PX4_BASE:
+# Points to a PX4 distribution. Normally determined based on the
+# path to this file.
+#
+# CONFIG:
+# Used to set the output filename; defaults to 'firmware'.
+#
+# WORK_DIR:
+# Sets the directory in which the firmware will be built. Defaults
+# to the directory 'build' under the directory containing the
+# parent Makefile.
+#
+# ROMFS_ROOT:
+# If set to the path to a directory, a ROMFS image will be generated
+# containing the files under the directory and linked into the final
+# image.
+#
+# MODULE_SEARCH_DIRS:
+# Extra directories to search first for MODULES before looking in the
+# usual places.
+#
+
+################################################################################
+# Paths and configuration
+################################################################################
+
+#
+# Work out where this file is, so we can find other makefiles in the
+# same directory.
+#
+# If PX4_BASE wasn't set previously, work out what it should be
+# and set it here now.
+#
+MK_DIR ?= $(dir $(lastword $(MAKEFILE_LIST)))
+ifeq ($(PX4_BASE),)
+export PX4_BASE := $(abspath $(MK_DIR)/..)
+endif
+$(info % PX4_BASE = $(PX4_BASE))
+
+#
+# Set a default target so that included makefiles or errors here don't
+# cause confusion.
+#
+# XXX We could do something cute here with $(DEFAULT_GOAL) if it's not one
+# of the maintenance targets and set CONFIG based on it.
+#
+all: firmware
+
+#
+# Get path and tool config
+#
+include $(MK_DIR)/setup.mk
+
+#
+# Locate the configuration file
+#
+ifeq ($(CONFIG),)
+$(error Missing configuration name or file (specify with CONFIG=<config>))
+endif
+CONFIG_FILE := $(firstword $(wildcard $(CONFIG)) $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk))
+ifeq ($(CONFIG_FILE),)
+$(error Can't find a config file called $(CONFIG) or $(PX4_MK_DIR)/config_$(CONFIG).mk)
+endif
+export CONFIG
+include $(CONFIG_FILE)
+$(info % CONFIG = $(CONFIG))
+
+#
+# Sanity-check the BOARD variable and then get the board config.
+# If BOARD was not set by the configuration, extract it automatically.
+#
+# The board config in turn will fetch the toolchain configuration.
+#
+ifeq ($(BOARD),)
+BOARD := $(firstword $(subst _, ,$(CONFIG)))
+endif
+BOARD_FILE := $(wildcard $(PX4_MK_DIR)/board_$(BOARD).mk)
+ifeq ($(BOARD_FILE),)
+$(error Config $(CONFIG) references board $(BOARD), but no board definition file found)
+endif
+export BOARD
+include $(BOARD_FILE)
+$(info % BOARD = $(BOARD))
+
+#
+# If WORK_DIR is not set, create a 'build' directory next to the
+# parent Makefile.
+#
+PARENT_MAKEFILE := $(lastword $(filter-out $(lastword $(MAKEFILE_LIST)),$(MAKEFILE_LIST)))
+ifeq ($(WORK_DIR),)
+export WORK_DIR := $(dir $(PARENT_MAKEFILE))build/
+endif
+$(info % WORK_DIR = $(WORK_DIR))
+
+#
+# Things that, if they change, might affect everything
+#
+GLOBAL_DEPS += $(MAKEFILE_LIST)
+
+#
+# Extra things we should clean
+#
+EXTRA_CLEANS =
+
+################################################################################
+# Modules
+################################################################################
+
+#
+# We don't actually know what a module is called; all we have is a path fragment
+# that we can search for, and where we expect to find a module.mk file.
+#
+# As such, we replicate the successfully-found path inside WORK_DIR for the
+# module's build products in order to keep modules separated from each other.
+#
+# XXX If this becomes unwieldy or breaks for other reasons, we will need to
+# move to allocating directory names and keeping tabs on makefiles via
+# the directory name. That will involve arithmetic (it'd probably be time
+# for GMSL).
+
+# where to look for modules
+MODULE_SEARCH_DIRS += $(WORK_DIR) $(MODULE_SRC) $(PX4_MODULE_SRC)
+
+# sort and unique the modules list
+MODULES := $(sort $(MODULES))
+
+# locate the first instance of a module by full path or by looking on the
+# module search path
+define MODULE_SEARCH
+ $(abspath $(firstword $(wildcard $(1)/module.mk) \
+ $(foreach search_dir,$(MODULE_SEARCH_DIRS),$(wildcard $(search_dir)/$(1)/module.mk)) \
+ MISSING_$1))
+endef
+
+# make a list of module makefiles and check that we found them all
+MODULE_MKFILES := $(foreach module,$(MODULES),$(call MODULE_SEARCH,$(module)))
+MISSING_MODULES := $(subst MISSING_,,$(filter MISSING_%,$(MODULE_MKFILES)))
+ifneq ($(MISSING_MODULES),)
+$(error Can't find module(s): $(MISSING_MODULES))
+endif
+
+# Make a list of the object files we expect to build from modules
+# Note that this path will typically contain a double-slash at the WORK_DIR boundary; this must be
+# preserved as it is used below to get the absolute path for the module.mk file correct.
+#
+MODULE_OBJS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)module.pre.o)
+
+# rules to build module objects
+.PHONY: $(MODULE_OBJS)
+$(MODULE_OBJS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
+$(MODULE_OBJS): mkfile = $(patsubst %module.pre.o,%module.mk,$(relpath))
+$(MODULE_OBJS): $(GLOBAL_DEPS) $(NUTTX_CONFIG_HEADER)
+ @$(ECHO) %%
+ @$(ECHO) %% Building module using $(mkfile)
+ @$(ECHO) %%
+ $(Q) $(MAKE) -f $(PX4_MK_DIR)module.mk \
+ MODULE_WORK_DIR=$(dir $@) \
+ MODULE_OBJ=$@ \
+ MODULE_MK=$(mkfile) \
+ MODULE_NAME=$(lastword $(subst /, ,$(@D))) \
+ module
+
+# make a list of phony clean targets for modules
+MODULE_CLEANS := $(foreach path,$(dir $(MODULE_MKFILES)),$(WORK_DIR)$(path)/clean)
+
+# rules to clean modules
+.PHONY: $(MODULE_CLEANS)
+$(MODULE_CLEANS): relpath = $(patsubst $(WORK_DIR)%,%,$@)
+$(MODULE_CLEANS): mkfile = $(patsubst %clean,%module.mk,$(relpath))
+$(MODULE_CLEANS):
+ @$(ECHO) %% cleaning using $(mkfile)
+ $(Q) $(MAKE) -f $(PX4_MK_DIR)module.mk \
+ MODULE_WORK_DIR=$(dir $@) \
+ MODULE_MK=$(mkfile) \
+ clean
+
+################################################################################
+# NuttX libraries and paths
+################################################################################
+
+include $(PX4_MK_DIR)/nuttx.mk
+
+################################################################################
+# ROMFS generation
+################################################################################
+
+ifneq ($(ROMFS_ROOT),)
+
+#
+# Note that there is no support for more than one root directory or constructing
+# a root from several templates. That would be a nice feature.
+#
+
+# Add dependencies on anything in the ROMFS root
+ROMFS_DEPS += $(wildcard \
+ (ROMFS_ROOT)/* \
+ (ROMFS_ROOT)/*/* \
+ (ROMFS_ROOT)/*/*/* \
+ (ROMFS_ROOT)/*/*/*/* \
+ (ROMFS_ROOT)/*/*/*/*/* \
+ (ROMFS_ROOT)/*/*/*/*/*/*)
+ROMFS_IMG = $(WORK_DIR)romfs.img
+ROMFS_CSRC = $(ROMFS_IMG:.img=.c)
+ROMFS_OBJ = $(ROMFS_CSRC:.c=.o)
+LIBS += $(ROMFS_OBJ)
+LINK_DEPS += $(ROMFS_OBJ)
+
+# Turn the ROMFS image into an object file
+$(ROMFS_OBJ): $(ROMFS_IMG) $(GLOBAL_DEPS)
+ $(call BIN_TO_OBJ,$<,$@,romfs_img)
+
+# Generate the ROMFS image from the root
+$(ROMFS_IMG): $(ROMFS_DEPS) $(GLOBAL_DEPS)
+ @$(ECHO) %% generating $@
+ $(Q) $(GENROMFS) -f $@ -d $(ROMFS_ROOT) -V "NSHInitVol"
+
+EXTRA_CLEANS += $(ROMGS_OBJ) $(ROMFS_IMG)
+
+endif
+
+################################################################################
+# Builtin command list generation
+################################################################################
+
+#
+# Builtin commands can be generated by the configuration, in which case they
+# must refer to commands that already exist, or indirectly generated by modules
+# when they are built.
+#
+# The configuration supplies builtin command information in the BUILTIN_COMMANDS
+# variable. Applications make empty files in $(WORK_DIR)/builtin_commands whose
+# filename contains the same information.
+#
+# In each case, the command information consists of four fields separated with a
+# period. These fields are the command's name, its thread priority, its stack size
+# and the name of the function to call when starting the thread.
+#
+BUILTIN_CSRC = $(WORK_DIR)builtin_commands.c
+
+# add command definitions from modules
+BUILTIN_COMMAND_FILES := $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)
+BUILTIN_COMMANDS += $(subst COMMAND.,,$(notdir $(BUILTIN_COMMAND_FILES)))
+
+ifneq ($(BUILTIN_COMMANDS),)
+
+# (BUILTIN_PROTO,<cmdspec>,<outputfile>)
+define BUILTIN_PROTO
+ $(ECHO) 'extern int $(word 4,$1)(int argc, char *argv[]);' >> $2;
+endef
+
+# (BUILTIN_DEF,<cmdspec>,<outputfile>)
+define BUILTIN_DEF
+ $(ECHO) ' {"$(word 1,$1)", $(word 2,$1), $(word 3,$1), $(word 4,$1)},' >> $2;
+endef
+
+# Don't generate until modules have updated their command files
+$(BUILTIN_CSRC): $(GLOBAL_DEPS) $(BUILTIN_COMMAND_FILES)
+ @$(ECHO) %% generating $@
+ $(Q) $(ECHO) '/* builtin command list - automatically generated, do not edit */' > $@
+ $(Q) $(ECHO) '#include <nuttx/config.h>' >> $@
+ $(Q) $(ECHO) '#include <nuttx/binfmt/builtin.h>' >> $@
+ $(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_PROTO,$(subst ., ,$(spec)),$@))
+ $(Q) $(ECHO) 'const struct builtin_s g_builtins[] = {' >> $@
+ $(Q) $(foreach spec,$(BUILTIN_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
+ $(Q) $(ECHO) ' {NULL, 0, 0, NULL}' >> $@
+ $(Q) $(ECHO) '};' >> $@
+ $(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS));' >> $@
+
+SRCS += $(BUILTIN_CSRC)
+
+EXTRA_CLEANS += $(BUILTIN_CSRC)
+
+endif
+
+################################################################################
+# Default SRCS generation
+################################################################################
+
+#
+# If there are no SRCS, the build will fail; in that case, generate an empty
+# source file.
+#
+ifeq ($(SRCS),)
+EMPTY_SRC = $(WORK_DIR)empty.c
+$(EMPTY_SRC):
+ $(Q) $(ECHO) '/* this is an empty file */' > $@
+
+SRCS += $(EMPTY_SRC)
+endif
+
+################################################################################
+# Build rules
+################################################################################
+
+#
+# What we're going to build.
+#
+PRODUCT_BUNDLE = $(WORK_DIR)firmware.px4
+PRODUCT_BIN = $(WORK_DIR)firmware.bin
+PRODUCT_SYM = $(WORK_DIR)firmware.sym
+
+.PHONY: firmware
+firmware: $(PRODUCT_BUNDLE)
+
+#
+# Object files we will generate from sources
+#
+OBJS := $(foreach src,$(SRCS),$(WORK_DIR)$(src).o)
+
+#
+# SRCS -> OBJS rules
+#
+
+$(OBJS): $(GLOBAL_DEPS)
+
+$(filter %.c.o,$(OBJS)): $(WORK_DIR)%.c.o: %.c $(GLOBAL_DEPS)
+ $(call COMPILE,$<,$@)
+
+$(filter %.cpp.o,$(OBJS)): $(WORK_DIR)%.cpp.o: %.cpp $(GLOBAL_DEPS)
+ $(call COMPILEXX,$<,$@)
+
+$(filter %.S.o,$(OBJS)): $(WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
+ $(call ASSEMBLE,$<,$@)
+
+#
+# Built product rules
+#
+
+$(PRODUCT_BUNDLE): $(PRODUCT_BIN)
+ @$(ECHO) %% Generating $@
+ $(Q) $(MKFW) --prototype $(IMAGE_DIR)/$(BOARD).prototype \
+ --git_identity $(PX4_BASE) \
+ --image $< > $@
+
+$(PRODUCT_BIN): $(PRODUCT_SYM)
+ $(call SYM_TO_BIN,$<,$@)
+
+$(PRODUCT_SYM): $(OBJS) $(MODULE_OBJS) $(GLOBAL_DEPS) $(LINK_DEPS) $(MODULE_MKFILES)
+ $(call LINK,$@,$(OBJS) $(MODULE_OBJS))
+
+#
+# Utility rules
+#
+
+.PHONY: upload
+upload: $(PRODUCT_BUNDLE) $(PRODUCT_BIN)
+ $(Q) $(MAKE) -f $(PX4_MK_DIR)/upload.mk \
+ METHOD=serial \
+ PRODUCT=$(PRODUCT) \
+ BUNDLE=$(PRODUCT_BUNDLE) \
+ BIN=$(PRODUCT_BIN)
+
+.PHONY: clean
+clean: $(MODULE_CLEANS)
+ @$(ECHO) %% cleaning
+ $(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_SYM)
+ $(Q) $(REMOVE) $(OBJS) $(DEP_INCLUDES) $(EXTRA_CLEANS)
+ $(Q) $(RMDIR) $(NUTTX_EXPORT_DIR)
+
+#
+# DEP_INCLUDES is defined by the toolchain include in terms of $(OBJS)
+#
+-include $(DEP_INCLUDES)
diff --git a/makefiles/module.mk b/makefiles/module.mk
new file mode 100644
index 000000000..8b01d0a12
--- /dev/null
+++ b/makefiles/module.mk
@@ -0,0 +1,210 @@
+#
+# 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.
+#
+
+#
+# Framework makefile for PX4 modules
+#
+# This makefile is invoked by firmware.mk to build each of the modules
+# that will subsequently be linked into the firmware image.
+#
+# Applications are built as prelinked objects with a limited set of exported
+# symbols, as the global namespace is shared between all modules. Normally an
+# module will just export one or more <command>_main functions.
+#
+
+#
+# Variables that can be set by the module's module.mk:
+#
+#
+# SRCS (required)
+#
+# Lists the .c, cpp and .S files that should be compiled/assembled to
+# produce the module.
+#
+# MODULE_COMMAND (optional)
+# MODULE_ENTRYPOINT (optional if MODULE_COMMAND is set)
+# MODULE_STACKSIZE (optional if MODULE_COMMAND is set)
+# MODULE_PRIORITY (optional if MODULE_COMMAND is set)
+#
+# Defines a single builtin command exported by the module.
+# MODULE_COMMAND must be unique for any configuration, but need not be the
+# same as the module directory name.
+#
+# If MODULE_ENTRYPOINT is set, it names the function (which must be exported)
+# that will be the entrypoint for the builtin command. It defaults to
+# $(MODULE_COMMAND)_main.
+#
+# If MODULE_STACKSIZE is set, it is the size in bytes of the stack to be
+# allocated for the builtin command. If it is not set, it defaults
+# to CONFIG_PTHREAD_STACK_DEFAULT.
+#
+# If MODULE_PRIORITY is set, it is the thread priority for the builtin
+# command. If it is not set, it defaults to SCHED_PRIORITY_DEFAULT.
+#
+# MODULE_COMMANDS (optional if MODULE_COMMAND is not set)
+#
+# Defines builtin commands exported by the module. Each word in
+# the list should be formatted as:
+# <command>.<priority>.<stacksize>.<entrypoint>
+#
+#
+
+#
+# Variables visible to the module's module.mk:
+#
+# CONFIG
+# BOARD
+# MODULE_WORK_DIR
+# MODULE_OBJ
+# MODULE_MK
+# Anything set in setup.mk, board_$(BOARD).mk and the toolchain file.
+# Anything exported from config_$(CONFIG).mk
+#
+
+################################################################################
+# No user-serviceable parts below.
+################################################################################
+
+ifeq ($(MODULE_MK),)
+$(error No module makefile specified)
+endif
+$(info % MODULE_MK = $(MODULE_MK))
+
+#
+# Get path and tool config
+#
+include $(PX4_BASE)/makefiles/setup.mk
+
+#
+# Get the board/toolchain config
+#
+include $(PX4_MK_DIR)/board_$(BOARD).mk
+
+#
+# Get the module's config
+#
+include $(MODULE_MK)
+MODULE_SRC := $(dir $(MODULE_MK))
+$(info % MODULE_NAME = $(MODULE_NAME))
+$(info % MODULE_SRC = $(MODULE_SRC))
+$(info % MODULE_OBJ = $(MODULE_OBJ))
+$(info % MODULE_WORK_DIR = $(MODULE_WORK_DIR))
+
+#
+# Things that, if they change, might affect everything
+#
+GLOBAL_DEPS += $(MAKEFILE_LIST)
+
+################################################################################
+# Builtin command definitions
+################################################################################
+
+ifneq ($(MODULE_COMMAND),)
+MODULE_ENTRYPOINT ?= $(MODULE_COMMAND)_main
+MODULE_STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
+MODULE_PRIORITY ?= SCHED_PRIORITY_DEFAULT
+MODULE_COMMANDS += $(MODULE_COMMAND).$(MODULE_PRIORITY).$(MODULE_STACKSIZE).$(MODULE_ENTRYPOINT)
+endif
+
+ifneq ($(MODULE_COMMANDS),)
+MODULE_COMMAND_FILES := $(addprefix $(WORK_DIR)/builtin_commands/COMMAND.,$(MODULE_COMMANDS))
+
+# Create the command files
+# Ensure that there is only one entry for each command
+#
+.PHONY: $(MODULE_COMMAND_FILES)
+$(MODULE_COMMAND_FILES): command = $(word 2,$(subst ., ,$(notdir $(@))))
+$(MODULE_COMMAND_FILES): exclude = $(dir $@)COMMAND.$(command).*
+$(MODULE_COMMAND_FILES): $(GLOBAL_DEPS)
+ @$(ECHO) COMMAND: $(command)
+ @$(REMOVE) -f $(exclude)
+ @$(MKDIR) -p $(dir $@)
+ $(Q) $(TOUCH) $@
+endif
+
+################################################################################
+# Build rules
+################################################################################
+
+#
+# What we're going to build
+#
+module: $(MODULE_OBJ) $(MODULE_COMMAND_FILES)
+
+#
+# Locate sources (allows relative source paths in module.mk)
+#
+define SRC_SEARCH
+ $(abspath $(firstword $(wildcard $(MODULE_SRC)/$1) MISSING_$1))
+endef
+
+ABS_SRCS := $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src)))
+MISSING_SRCS := $(subst MISSING_,,$(filter MISSING_%,$(ABS_SRCS)))
+ifneq ($(MISSING_SRCS),)
+$(error $(MODULE_MK): missing in SRCS: $(MISSING_SRCS))
+endif
+ifeq ($(ABS_SRCS),)
+$(error $(MODULE_MK): nothing to compile in SRCS)
+endif
+
+#
+# Object files we will generate from sources
+#
+OBJS := $(foreach src,$(ABS_SRCS),$(MODULE_WORK_DIR)$(src).o)
+
+#
+# SRCS -> OBJS rules
+#
+
+$(OBJS): $(GLOBAL_DEPS)
+
+$(filter %.c.o,$(OBJS)): $(MODULE_WORK_DIR)%.c.o: %.c $(GLOBAL_DEPS)
+ $(call COMPILE,$<,$@)
+
+$(filter %.cpp.o,$(OBJS)): $(MODULE_WORK_DIR)%.cpp.o: %.cpp $(GLOBAL_DEPS)
+ $(call COMPILEXX,$<,$@)
+
+$(filter %.S.o,$(OBJS)): $(MODULE_WORK_DIR)%.S.o: %.S $(GLOBAL_DEPS)
+ $(call ASSEMBLE,$<,$@)
+
+#
+# Built product rules
+#
+
+$(MODULE_OBJ): $(OBJS) $(GLOBAL_DEPS)
+ $(call PRELINK,$@,$(OBJS))
+
+#
+# Utility rules
+#
+
+clean:
+ $(Q) $(REMOVE) $(MODULE_PRELINK) $(OBJS)
diff --git a/makefiles/nuttx.mk b/makefiles/nuttx.mk
new file mode 100644
index 000000000..c6e2c86d1
--- /dev/null
+++ b/makefiles/nuttx.mk
@@ -0,0 +1,75 @@
+#
+# 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.
+#
+
+#
+# Rules and definitions related to handling the NuttX export archives when
+# building firmware.
+#
+
+#
+# Check that the NuttX archive for the selected board is available.
+#
+NUTTX_ARCHIVE := $(wildcard $(ARCHIVE_DIR)$(BOARD).export)
+ifeq ($(NUTTX_ARCHIVE),)
+$(error The NuttX export archive for $(BOARD) is missing from $(ARCHIVE_DIR) - try 'make archives' in $(PX4_BASE))
+endif
+
+#
+# The NuttX config header should always be present in the NuttX archive, and
+# if it changes, everything should be rebuilt. So, use it as the trigger to
+# unpack the NuttX archive.
+#
+NUTTX_EXPORT_DIR = $(WORK_DIR)nuttx-export/
+NUTTX_CONFIG_HEADER = $(NUTTX_EXPORT_DIR)include/nuttx/config.h
+$(info % NUTTX_EXPORT_DIR = $(NUTTX_EXPORT_DIR))
+$(info % NUTTX_CONFIG_HEADER = $(NUTTX_CONFIG_HEADER))
+
+
+GLOBAL_DEPS += $(NUTTX_CONFIG_HEADER)
+
+#
+# Use the linker script from the NuttX export
+#
+LDSCRIPT += $(NUTTX_EXPORT_DIR)build/ld.script
+
+#
+# Add directories from the NuttX export to the relevant search paths
+#
+INCLUDE_DIRS += $(NUTTX_EXPORT_DIR)include
+LIB_DIRS += $(NUTTX_EXPORT_DIR)libs
+LIBS += -lapps -lnuttx
+LINK_DEPS += $(NUTTX_EXPORT_DIR)libs/libapps.a \
+ $(NUTTX_EXPORT_DIR)libs/libnuttx.a
+
+$(NUTTX_CONFIG_HEADER): $(NUTTX_ARCHIVE)
+ @$(ECHO) %% Unpacking $(NUTTX_ARCHIVE)
+ $(Q) $(UNZIP) -q -o -d $(WORK_DIR) $(NUTTX_ARCHIVE)
+ $(Q) $(TOUCH) $@
diff --git a/makefiles/setup.mk b/makefiles/setup.mk
new file mode 100644
index 000000000..8e7a00ef4
--- /dev/null
+++ b/makefiles/setup.mk
@@ -0,0 +1,81 @@
+#
+# 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.
+#
+
+#
+# Path and tool setup
+#
+
+#
+# Some useful paths.
+#
+# Note that in general we always keep directory paths with the separator
+# at the end, and join paths without explicit separators. This reduces
+# the number of duplicate slashes we have lying around in paths,
+# and is consistent with joining the results of $(dir) and $(notdir).
+#
+export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src/modules)/
+export PX4_MK_DIR = $(abspath $(PX4_BASE)/makefiles)/
+export NUTTX_SRC = $(abspath $(PX4_BASE)/nuttx)/
+export NUTTX_APP_SRC = $(abspath $(PX4_BASE)/apps)/
+export MAVLINK_SRC = $(abspath $(PX4_BASE)/mavlink)/
+export ROMFS_SRC = $(abspath $(PX4_BASE)/ROMFS)/
+export IMAGE_DIR = $(abspath $(PX4_BASE)/Images)/
+export BUILD_DIR = $(abspath $(PX4_BASE)/Build)/
+export ARCHIVE_DIR = $(abspath $(PX4_BASE)/Archives)/
+
+#
+# Tools
+#
+MKFW = $(PX4_BASE)/Tools/px_mkfw.py
+UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
+COPY = cp
+REMOVE = rm -f
+RMDIR = rm -rf
+GENROMFS = genromfs
+TOUCH = touch
+MKDIR = mkdir
+ECHO = echo
+UNZIP = unzip
+
+#
+# Host-specific paths, hacks and fixups
+#
+SYSTYPE := $(shell uname -s)
+
+ifeq ($(SYSTYPE),Darwin)
+# Eclipse may not have the toolchain on its path.
+export PATH := $(PATH):/usr/local/bin
+endif
+
+#
+# Makefile debugging.
+#
+export Q := $(if $(V),,@)
diff --git a/makefiles/toolchain_gnu-arm-eabi.mk b/makefiles/toolchain_gnu-arm-eabi.mk
new file mode 100644
index 000000000..d214006be
--- /dev/null
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -0,0 +1,264 @@
+#
+# 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.
+#
+
+#
+# Definitions for a generic GNU ARM-EABI toolchain
+#
+
+#$(info TOOLCHAIN gnu-arm-eabi)
+
+# Toolchain commands. Normally only used inside this file.
+#
+CROSSDEV = arm-none-eabi-
+
+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
+
+# XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup
+
+MAXOPTIMIZATION = -O3
+
+# Base CPU flags for each of the supported architectures.
+#
+ARCHCPUFLAGS_CORTEXM4F = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfpu=fpv4-sp-d16 \
+ -mfloat-abi=hard
+
+ARCHCPUFLAGS_CORTEXM4 = -mcpu=cortex-m4 \
+ -mthumb \
+ -march=armv7e-m \
+ -mfloat-abi=soft
+
+ARCHCPUFLAGS_CORTEXM3 = -mcpu=cortex-m3 \
+ -mthumb \
+ -march=armv7-m \
+ -mfloat-abi=soft
+
+# Pick the right set of flags for the architecture.
+#
+ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH))
+ifeq ($(ARCHCPUFLAGS),)
+$(error Must set CONFIG_ARCH to one of CORTEXM4F, CORTEXM4 or CORTEXM3)
+endif
+
+# optimisation flags
+#
+ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
+ -g \
+ -fno-strict-aliasing \
+ -fno-strength-reduce \
+ -fomit-frame-pointer \
+ -funsafe-math-optimizations \
+ -fno-builtin-printf \
+ -ffunction-sections \
+ -fdata-sections
+
+# enable precise stack overflow tracking
+# note - requires corresponding support in NuttX
+INSTRUMENTATIONDEFINES = -finstrument-functions \
+ -ffixed-r10
+# Language-specific flags
+#
+ARCHCFLAGS = -std=gnu99
+ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x
+
+# Generic warnings
+#
+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
+
+# C-specific warnings
+#
+ARCHCWARNINGS = $(ARCHWARNINGS) \
+ -Wbad-function-cast \
+ -Wstrict-prototypes \
+ -Wold-style-declaration \
+ -Wmissing-parameter-type \
+ -Wmissing-prototypes \
+ -Wnested-externs \
+ -Wunsuffixed-float-constants
+
+# C++-specific warnings
+#
+ARCHWARNINGSXX = $(ARCHWARNINGS)
+
+# pull in *just* libm from the toolchain ... this is grody
+LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
+EXTRA_LIBS += $(LIBM)
+
+# Flags we pass to the C compiler
+#
+CFLAGS = $(ARCHCFLAGS) \
+ $(ARCHCWARNINGS) \
+ $(ARCHOPTIMIZATION) \
+ $(ARCHCPUFLAGS) \
+ $(ARCHINCLUDES) \
+ $(INSTRUMENTATIONDEFINES) \
+ $(ARCHDEFINES) \
+ $(EXTRADEFINES) \
+ -fno-common \
+ $(addprefix -I,$(INCLUDE_DIRS))
+
+# Flags we pass to the C++ compiler
+#
+CXXFLAGS = $(ARCHCXXFLAGS) \
+ $(ARCHWARNINGSXX) \
+ $(ARCHOPTIMIZATION) \
+ $(ARCHCPUFLAGS) \
+ $(ARCHXXINCLUDES) \
+ $(INSTRUMENTATIONDEFINES) \
+ $(ARCHDEFINES) \
+ $(EXTRADEFINES) \
+ $(addprefix -I,$(INCLUDE_DIRS))
+
+# Flags we pass to the assembler
+#
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__
+
+# Flags we pass to the linker
+#
+LDFLAGS += --warn-common \
+ --gc-sections \
+ $(addprefix -T,$(LDSCRIPT)) \
+ $(addprefix -L,$(LIB_DIRS))
+
+# Compiler support library
+#
+LIBGCC := $(shell $(CC) $(ARCHCPUFLAGS) -print-libgcc-file-name)
+
+# Files that the final link depends on
+#
+LINK_DEPS += $(LDSCRIPT)
+
+# Files to include to get automated dependencies
+#
+DEP_INCLUDES = $(subst .o,.d,$(OBJS))
+
+# Compile C source $1 to object $2
+# as a side-effect, generate a dependency file
+#
+define COMPILE
+ @$(ECHO) "CC: $1"
+ @$(MKDIR) -p $(dir $2)
+ $(Q) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2
+endef
+
+# Compile C++ source $1 to $2
+# as a side-effect, generate a dependency file
+#
+define COMPILEXX
+ @$(ECHO) "CXX: $1"
+ @$(MKDIR) -p $(dir $2)
+ $(Q) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
+endef
+
+# Assemble $1 into $2
+#
+define ASSEMBLE
+ @$(ECHO) "AS: $1"
+ @$(MKDIR) -p $(dir $2)
+ $(Q) $(CC) -c $(AFLAGS) $(abspath $1) -o $2
+endef
+
+# Produce partially-linked $1 from files in $2
+#
+define PRELINK
+ @$(ECHO) "PRELINK: $1"
+ @$(MKDIR) -p $(dir $1)
+ $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
+endef
+
+# Update the archive $1 with the files in $2
+#
+define ARCHIVE
+ @$(ECHO) "AR: $2"
+ @$(MKDIR) -p $(dir $1)
+ $(Q) $(AR) $1 $2
+endef
+
+# Link the objects in $2 into the binary $1
+#
+define LINK
+ @$(ECHO) "LINK: $1"
+ @$(MKDIR) -p $(dir $1)
+ $(Q) $(LD) $(LDFLAGS) -o $1 --start-group $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) --end-group
+endef
+
+# Convert $1 from a linked object to a raw binary in $2
+#
+define SYM_TO_BIN
+ @$(ECHO) "BIN: $2"
+ @$(MKDIR) -p $(dir $2)
+ $(Q) $(OBJCOPY) -O binary $1 $2
+endef
+
+# Take the raw binary $1 and make it into an object file $2.
+# The symbol $3 points to the beginning of the file, and $3_len
+# gives its length.
+#
+# - compile an empty file to generate a suitable object file
+# - relink the object and insert the binary file
+# - edit symbol names to suit
+#
+define BIN_SYM_PREFIX
+ _binary_$(subst /,_,$(subst .,_,$1))
+endef
+define BIN_TO_OBJ
+ @$(ECHO) "OBJ: $2"
+ @$(MKDIR) -p $(dir $2)
+ $(Q) $(ECHO) > $2.c
+ $(call COMPILE,$2.c,$2.c.o)
+ $(Q) $(LD) -r -o $2 $2.c.o -b binary $1
+ $(Q) $(OBJCOPY) $2 \
+ --redefine-sym $(call BIN_SYM_PREFIX,$1)_start=$3 \
+ --redefine-sym $(call BIN_SYM_PREFIX,$1)_size=$3_len \
+ --strip-symbol $(call BIN_SYM_PREFIX,$1)_end
+endef
diff --git a/makefiles/upload.mk b/makefiles/upload.mk
new file mode 100644
index 000000000..5308aaa3e
--- /dev/null
+++ b/makefiles/upload.mk
@@ -0,0 +1,41 @@
+#
+# Rules and tools for uploading firmware to various PX4 boards.
+#
+
+UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
+
+SYSTYPE := $(shell uname -s)
+
+#
+# Serial port defaults.
+#
+# XXX The uploader should be smarter than this.
+#
+ifeq ($(SYSTYPE),Darwin)
+SERIAL_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"
+endif
+ifeq ($(SYSTYPE),Linux)
+SERIAL_PORTS ?= "/dev/ttyACM5,/dev/ttyACM4,/dev/ttyACM3,/dev/ttyACM2,/dev/ttyACM1,/dev/ttyACM0"
+endif
+ifeq ($(SERIAL_PORTS),)
+SERIAL_PORTS = "\\\\.\\COM32,\\\\.\\COM31,\\\\.\\COM30,\\\\.\\COM29,\\\\.\\COM28,\\\\.\\COM27,\\\\.\\COM26,\\\\.\\COM25,\\\\.\\COM24,\\\\.\\COM23,\\\\.\\COM22,\\\\.\\COM21,\\\\.\\COM20,\\\\.\\COM19,\\\\.\\COM18,\\\\.\\COM17,\\\\.\\COM16,\\\\.\\COM15,\\\\.\\COM14,\\\\.\\COM13,\\\\.\\COM12,\\\\.\\COM11,\\\\.\\COM10,\\\\.\\COM9,\\\\.\\COM8,\\\\.\\COM7,\\\\.\\COM6,\\\\.\\COM5,\\\\.\\COM4,\\\\.\\COM3,\\\\.\\COM2,\\\\.\\COM1,\\\\.\\COM0"
+endif
+
+.PHONY: all upload-$(METHOD)-$(PRODUCT)
+all: upload-$(METHOD)-$(PRODUCT)
+
+upload-serial-px4fmu: $(BUNDLE) $(UPLOADER)
+ @python -u $(UPLOADER) --port $(SERIAL_PORTS) $(PRODUCT_BUNDLE)
+
+#
+# JTAG firmware uploading with OpenOCD
+#
+JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg
+
+upload-jtag-px4fmu: all
+ @echo Attempting to flash PX4FMU board via JTAG
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f4x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4fmu_bl.elf" -c "reset run" -c shutdown
+
+upload-jtag-px4io: all
+ @echo Attempting to flash PX4IO board via JTAG
+ @openocd -f $(JTAGCONFIG) -f ../Bootloader/stm32f1x.cfg -c init -c "reset halt" -c "flash write_image erase nuttx/nuttx" -c "flash write_image erase ../Bootloader/px4io_bl.elf" -c "reset run" -c shutdown
diff --git a/nuttx/configs/px4fmu/include/nsh_romfsimg.h b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
new file mode 100644
index 000000000..15e4e7a8d
--- /dev/null
+++ b/nuttx/configs/px4fmu/include/nsh_romfsimg.h
@@ -0,0 +1,42 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 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.
+ *
+ ****************************************************************************/
+
+/**
+ * nsh_romfsetc.h
+ *
+ * This file is a stub for 'make export' purposes; the actual ROMFS
+ * must be supplied by the library client.
+ */
+
+extern unsigned char romfs_img[];
+extern unsigned int romfs_img_len;
diff --git a/nuttx/configs/px4io/common/Make.defs b/nuttx/configs/px4io/common/Make.defs
index 4958f7092..7f782b5b2 100644
--- a/nuttx/configs/px4io/common/Make.defs
+++ b/nuttx/configs/px4io/common/Make.defs
@@ -112,7 +112,6 @@ ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
ifeq ("${CONFIG_DEBUG_SYMBOLS}","y")
ARCHOPTIMIZATION += -g
-ARCHSCRIPT += -g
endif
ARCHCFLAGS = -std=gnu99
@@ -145,7 +144,7 @@ ARCHDEFINES =
ARCHPICFLAGS = -fpic -msingle-pic-base -mpic-register=r10
# this seems to be the only way to add linker flags
-ARCHSCRIPT += --warn-common \
+EXTRA_LIBS += --warn-common \
--gc-sections
CFLAGS = $(ARCHCFLAGS) $(ARCHCWARNINGS) $(ARCHOPTIMIZATION) $(ARCHCPUFLAGS) $(ARCHINCLUDES) $(INSTRUMENTATIONDEFINES) $(ARCHDEFINES) $(EXTRADEFINES) -pipe -fno-common
diff --git a/platforms/empty.c b/platforms/empty.c
new file mode 100644
index 000000000..139531354
--- /dev/null
+++ b/platforms/empty.c
@@ -0,0 +1,3 @@
+/*
+ * This is an empty C source file, used when building default firmware configurations.
+ */
diff --git a/src/modules/test/foo.c b/src/modules/test/foo.c
new file mode 100644
index 000000000..ff6af031f
--- /dev/null
+++ b/src/modules/test/foo.c
@@ -0,0 +1,4 @@
+int test_main(void)
+{
+ return 0;
+} \ No newline at end of file
diff --git a/src/modules/test/module.mk b/src/modules/test/module.mk
new file mode 100644
index 000000000..abf80eedf
--- /dev/null
+++ b/src/modules/test/module.mk
@@ -0,0 +1,4 @@
+
+MODULE_NAME = test
+SRCS = foo.c
+