aboutsummaryrefslogtreecommitdiff
path: root/Makefile
diff options
context:
space:
mode:
Diffstat (limited to 'Makefile')
-rw-r--r--Makefile263
1 files changed, 152 insertions, 111 deletions
diff --git a/Makefile b/Makefile
index e9442afd2..224910e0f 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, 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.
#
#
-# 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 ?= $(subst config_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)config_*.mk))))
#
-# 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 := $(subst board_,,$(basename $(notdir $(wildcard $(PX4_MK_DIR)board_*.mk))))
#
# Debugging
@@ -45,120 +55,151 @@ 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) > $@
+FIRMWARE_GOAL = firmware
+EXPLICIT_CONFIGS := $(filter $(CONFIGS),$(MAKECMDGOALS))
+ifneq ($(EXPLICIT_CONFIGS),)
+CONFIGS := $(EXPLICIT_CONFIGS)
+.PHONY: $(EXPLICIT_CONFIGS)
+$(EXPLICIT_CONFIGS): all
#
-# Build the firmware binary.
+# If the user has asked to upload, they must have also specified exactly one
+# config.
#
-.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 $@
+ifneq ($(filter upload,$(MAKECMDGOALS)),)
+ifneq ($(words $(EXPLICIT_CONFIGS)),1)
+$(error In order to upload, exactly one board config must be specified)
+endif
+FIRMWARE_GOAL = upload
+.PHONY: upload
+upload:
+ @:
+endif
+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 -r -C $(work_dir) \
+ -f $(PX4_MK_DIR)firmware.mk \
+ CONFIG=$(config) \
+ WORK_DIR=$(work_dir) \
+ $(FIRMWARE_GOAL)
#
-# 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.
#
-# Hacks and fixups
+# XXX Should support fetching/unpacking from a separate directory to permit
+# downloads of the prebuilt archives as well...
#
+# 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
+# We cannot build these parallel; note that we also force -j1 for the
+# sub-make invocations.
+ifneq ($(filter archives,$(MAKECMDGOALS)),)
+.NOTPARALLEL:
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 -r -j1 -C $(NUTTX_SRC) -r $(MQUIET) distclean
+ $(Q) (cd $(NUTTX_SRC)tools && ./configure.sh $(board)/$(configuration))
+ @echo %% Exporting NuttX for $(board)
+ $(Q) make -r -j1 -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
+
+#
+# Print some help text
+#
+.PHONY: help
+help:
+ @echo ""
+ @echo " PX4 firmware builder"
+ @echo " ===================="
+ @echo ""
+ @echo " Available targets:"
+ @echo " ------------------"
+ @echo ""
+ @echo " archives"
+ @echo " Build the NuttX RTOS archives that are used by the firmware build."
+ @echo ""
+ @echo " all"
+ @echo " Build all firmware configs: $(CONFIGS)"
+ @echo " A limited set of configs can be built with CONFIGS=<list-of-configs>"
+ @echo ""
+ @for config in $(CONFIGS); do \
+ echo " $$config"; \
+ echo " Build just the $$config firmware configuration."; \
+ echo ""; \
+ done
+ @echo " clean"
+ @echo " Remove all firmware build pieces."
+ @echo ""
+ @echo " distclean"
+ @echo " Remove all compilation products, including NuttX RTOS archives."
+ @echo ""
+ @echo " Common options:"
+ @echo " ---------------"
+ @echo ""
+ @echo " V=1"
+ @echo " If V is set, more verbose output is printed during the build. This can"
+ @echo " help when diagnosing issues with the build or toolchain."
+ @echo ""