aboutsummaryrefslogtreecommitdiff
path: root/makefiles
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-05-09 22:41:09 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-05-09 22:41:09 +0400
commit9a9e41f7a2dc3ff545aa6d2e7072a9abef0b5a59 (patch)
tree7389637e61c2c466a063acf152349cbe4855766e /makefiles
parent0489595e7f34f4bacc1b63f31eed5e64fe55c7e6 (diff)
parent15aae728e5bba7ac255e2f0266d39c5e9d95fc6a (diff)
downloadpx4-firmware-9a9e41f7a2dc3ff545aa6d2e7072a9abef0b5a59.tar.gz
px4-firmware-9a9e41f7a2dc3ff545aa6d2e7072a9abef0b5a59.tar.bz2
px4-firmware-9a9e41f7a2dc3ff545aa6d2e7072a9abef0b5a59.zip
Merge branch 'master' into gpio_led
Diffstat (limited to 'makefiles')
-rw-r--r--makefiles/board_px4fmu.mk10
-rw-r--r--makefiles/board_px4io.mk10
-rw-r--r--makefiles/config_px4fmu_default.mk124
-rw-r--r--makefiles/config_px4io_default.mk10
-rw-r--r--makefiles/firmware.mk443
-rw-r--r--makefiles/module.mk230
-rw-r--r--makefiles/nuttx.mk78
-rw-r--r--makefiles/setup.mk91
-rw-r--r--makefiles/toolchain_gnu-arm-eabi.mk270
-rw-r--r--makefiles/upload.mk44
10 files changed, 1310 insertions, 0 deletions
diff --git a/makefiles/board_px4fmu.mk b/makefiles/board_px4fmu.mk
new file mode 100644
index 000000000..837069644
--- /dev/null
+++ b/makefiles/board_px4fmu.mk
@@ -0,0 +1,10 @@
+#
+# Board-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..b0eb2dae7
--- /dev/null
+++ b/makefiles/board_px4io.mk
@@ -0,0 +1,10 @@
+#
+# Board-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..441ac3aac
--- /dev/null
+++ b/makefiles/config_px4fmu_default.mk
@@ -0,0 +1,124 @@
+#
+# Makefile for the px4fmu_default configuration
+#
+
+#
+# Use the configuration's ROMFS.
+#
+ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+
+#
+# Board support modules
+#
+MODULES += drivers/device
+MODULES += drivers/stm32
+MODULES += drivers/stm32/adc
+MODULES += drivers/stm32/tone_alarm
+MODULES += drivers/led
+MODULES += drivers/px4io
+MODULES += drivers/px4fmu
+MODULES += drivers/boards/px4fmu
+MODULES += drivers/ardrone_interface
+MODULES += drivers/l3gd20
+MODULES += drivers/bma180
+MODULES += drivers/mpu6000
+MODULES += drivers/hmc5883
+MODULES += drivers/ms5611
+MODULES += drivers/mb12xx
+MODULES += drivers/gps
+MODULES += drivers/hil
+MODULES += drivers/hott_telemetry
+MODULES += drivers/blinkm
+MODULES += drivers/mkblctrl
+MODULES += drivers/md25
+MODULES += drivers/ets_airspeed
+MODULES += modules/sensors
+
+#
+# System commands
+#
+MODULES += systemcmds/eeprom
+MODULES += systemcmds/bl_update
+MODULES += systemcmds/boardinfo
+MODULES += systemcmds/i2c
+MODULES += systemcmds/mixer
+MODULES += systemcmds/param
+MODULES += systemcmds/perf
+MODULES += systemcmds/preflight_check
+MODULES += systemcmds/pwm
+MODULES += systemcmds/reboot
+MODULES += systemcmds/top
+MODULES += systemcmds/tests
+
+#
+# General system control
+#
+MODULES += modules/commander
+MODULES += modules/mavlink
+MODULES += modules/mavlink_onboard
+MODULES += modules/gpio_led
+
+#
+# Estimation modules (EKF / other filters)
+#
+MODULES += modules/attitude_estimator_ekf
+MODULES += modules/position_estimator_mc
+MODULES += modules/position_estimator
+MODULES += modules/att_pos_estimator_ekf
+
+#
+# Vehicle Control
+#
+MODULES += modules/fixedwing_backside
+MODULES += modules/fixedwing_att_control
+MODULES += modules/fixedwing_pos_control
+MODULES += modules/multirotor_att_control
+MODULES += modules/multirotor_pos_control
+
+#
+# Logging
+#
+MODULES += modules/sdlog
+
+#
+# Libraries
+#
+MODULES += modules/systemlib
+MODULES += modules/systemlib/mixer
+MODULES += modules/mathlib
+MODULES += modules/mathlib/CMSIS
+MODULES += modules/controllib
+MODULES += modules/uORB
+
+#
+# Demo apps
+#
+#MODULES += examples/math_demo
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/hello_sky
+#MODULES += examples/px4_simple_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/daemon
+#MODULES += examples/px4_daemon_app
+
+# Tutorial code from
+# https://pixhawk.ethz.ch/px4/dev/debug_values
+#MODULES += examples/px4_mavlink_debug
+
+#
+# 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, sercon, , 2048, sercon_main ) \
+ $(call _B, serdis, , 2048, serdis_main )
diff --git a/makefiles/config_px4io_default.mk b/makefiles/config_px4io_default.mk
new file mode 100644
index 000000000..cf70391bc
--- /dev/null
+++ b/makefiles/config_px4io_default.mk
@@ -0,0 +1,10 @@
+#
+# Makefile for the px4io_default configuration
+#
+
+#
+# Board support modules
+#
+MODULES += drivers/stm32
+MODULES += drivers/boards/px4io
+MODULES += modules/px4iofirmware \ No newline at end of file
diff --git a/makefiles/firmware.mk b/makefiles/firmware.mk
new file mode 100644
index 000000000..b63aa28d7
--- /dev/null
+++ b/makefiles/firmware.mk
@@ -0,0 +1,443 @@
+#
+# 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 when searching for the configuration file, and available
+# to module Makefiles to select optional features.
+# If not set, CONFIG_FILE must be set and CONFIG will be derived
+# automatically from it.
+#
+# CONFIG_FILE:
+# If set, overrides the configuration file search logic. Sets
+# CONFIG to the name of the configuration file, strips any
+# leading config_ prefix and any suffix. e.g. config_board_foo.mk
+# results in CONFIG being set to 'board_foo'.
+#
+# 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))
+ifneq ($(words $(PX4_BASE)),1)
+$(error Cannot build when the PX4_BASE path contains one or more space characters.)
+endif
+
+#
+# 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
+#
+ifneq ($(CONFIG_FILE),)
+CONFIG := $(subst config_,,$(basename $(notdir $(CONFIG_FILE))))
+else
+CONFIG_FILE := $(wildcard $(PX4_MK_DIR)/config_$(CONFIG).mk)
+endif
+ifeq ($(CONFIG),)
+$(error Missing configuration name or file (specify with CONFIG=<config>))
+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)
+ $(Q) $(MAKE) -r -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) -r -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),)
+ifeq ($(wildcard $(ROMFS_ROOT)),)
+$(error ROMFS_ROOT specifies a directory that does not exist)
+endif
+
+#
+# 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) "ROMFS: $@"
+ $(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
+
+# command definitions from modules (may be empty at Makefile parsing time...)
+MODULE_COMMANDS = $(subst COMMAND.,,$(notdir $(wildcard $(WORK_DIR)builtin_commands/COMMAND.*)))
+
+# We must have at least one pre-defined builtin command in order to generate
+# any of this.
+#
+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) $(MODULE_OBJS) $(BUILTIN_COMMAND_FILES)
+ @$(ECHO) "CMDS: $@"
+ $(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) $(foreach spec,$(MODULE_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) $(foreach spec,$(MODULE_COMMANDS),$(call BUILTIN_DEF,$(subst ., ,$(spec)),$@))
+ $(Q) $(ECHO) ' {NULL, 0, 0, NULL}' >> $@
+ $(Q) $(ECHO) '};' >> $@
+ $(Q) $(ECHO) 'const int g_builtin_count = $(words $(BUILTIN_COMMANDS) $(MODULE_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_ELF = $(WORK_DIR)firmware.elf
+
+.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_ELF)
+ $(call SYM_TO_BIN,$<,$@)
+
+$(PRODUCT_ELF): $(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 \
+ CONFIG=$(CONFIG) \
+ BOARD=$(BOARD) \
+ BUNDLE=$(PRODUCT_BUNDLE) \
+ BIN=$(PRODUCT_BIN)
+
+.PHONY: clean
+clean: $(MODULE_CLEANS)
+ @$(ECHO) %% cleaning
+ $(Q) $(REMOVE) $(PRODUCT_BUNDLE) $(PRODUCT_BIN) $(PRODUCT_ELF)
+ $(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..0fe6f0ffe
--- /dev/null
+++ b/makefiles/module.mk
@@ -0,0 +1,230 @@
+#
+# Copyright (c) 2012, 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.
+#
+
+#
+# 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>
+#
+# INCLUDE_DIRS (optional, must be appended)
+#
+# The list of directories searched for include files. If non-standard
+# includes (e.g. those from another module) are required, paths to search
+# can be added here.
+#
+# DEFAULT_VISIBILITY (optional)
+#
+# If not set, global symbols defined in a module will not be visible
+# outside the module. Symbols that should be globally visible must be
+# marked __EXPORT.
+# If set, global symbols defined in a module will be globally visible.
+#
+
+#
+# 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 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)
+ @$(REMOVE) -f $(exclude)
+ @$(MKDIR) -p $(dir $@)
+ @$(ECHO) "CMD: $(command)"
+ $(Q) $(TOUCH) $@
+endif
+
+################################################################################
+# Adjust compilation flags to implement EXPORT
+################################################################################
+
+ifeq ($(DEFAULT_VISIBILITY),)
+DEFAULT_VISIBILITY = hidden
+else
+DEFAULT_VISIBILITY = default
+endif
+
+CFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
+CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(PX4_INCLUDE_DIR)visibility.h
+
+################################################################################
+# 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 $1) $(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..346735a02
--- /dev/null
+++ b/makefiles/nuttx.mk
@@ -0,0 +1,78 @@
+#
+# 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 \
+ $(NUTTX_EXPORT_DIR)arch/chip \
+ $(NUTTX_EXPORT_DIR)arch/common
+
+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_CMD) -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..111193093
--- /dev/null
+++ b/makefiles/setup.mk
@@ -0,0 +1,91 @@
+#
+# 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_INCLUDE_DIR = $(abspath $(PX4_BASE)/src/include)/
+export PX4_MODULE_SRC = $(abspath $(PX4_BASE)/src)/
+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)/
+
+#
+# Default include paths
+#
+export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
+ $(PX4_MODULE_SRC)/modules/ \
+ $(PX4_INCLUDE_DIR)
+
+#
+# Tools
+#
+export MKFW = $(PX4_BASE)/Tools/px_mkfw.py
+export UPLOADER = $(PX4_BASE)/Tools/px_uploader.py
+export COPY = cp
+export REMOVE = rm -f
+export RMDIR = rm -rf
+export GENROMFS = genromfs
+export TOUCH = touch
+export MKDIR = mkdir
+export ECHO = echo
+export UNZIP_CMD = unzip
+export PYTHON = python
+export OPENOCD = openocd
+
+#
+# Host-specific paths, hacks and fixups
+#
+export 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..0e651e53c
--- /dev/null
+++ b/makefiles/toolchain_gnu-arm-eabi.mk
@@ -0,0 +1,270 @@
+#
+# 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) \
+ $(EXTRACFLAGS) \
+ -fno-common \
+ $(addprefix -I,$(INCLUDE_DIRS))
+
+# Flags we pass to the C++ compiler
+#
+CXXFLAGS = $(ARCHCXXFLAGS) \
+ $(ARCHWARNINGSXX) \
+ $(ARCHOPTIMIZATION) \
+ $(ARCHCPUFLAGS) \
+ $(ARCHXXINCLUDES) \
+ $(INSTRUMENTATIONDEFINES) \
+ $(ARCHDEFINES) \
+ -DCONFIG_WCHAR_BUILTIN \
+ $(EXTRADEFINES) \
+ $(EXTRACXXFLAGS) \
+ $(addprefix -I,$(INCLUDE_DIRS))
+
+# Flags we pass to the assembler
+#
+AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
+ $(EXTRADEFINES) \
+ $(EXTRAAFLAGS)
+
+# Flags we pass to the linker
+#
+LDFLAGS += --warn-common \
+ --gc-sections \
+ $(EXTRALDFLAGS) \
+ $(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..5ef92728f
--- /dev/null
+++ b/makefiles/upload.mk
@@ -0,0 +1,44 @@
+#
+# 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)-$(BOARD)
+all: upload-$(METHOD)-$(BOARD)
+
+upload-serial-px4fmu: $(BUNDLE) $(UPLOADER)
+ $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
+
+upload-serial-px4fmuv2: $(BUNDLE) $(UPLOADER)
+ $(Q) $(PYTHON) -u $(UPLOADER) --port $(SERIAL_PORTS) $(BUNDLE)
+
+#
+# JTAG firmware uploading with OpenOCD
+#
+JTAGCONFIG ?= interface/olimex-jtag-tiny.cfg
+
+upload-jtag-px4fmu: all
+ @$(ECHO) Attempting to flash PX4FMU board via JTAG
+ $(Q) $(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
+ $(Q) $(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