Added posix-arm target and refactored toolchain_* files

The toolchain_* files are target OS specific so they were moved to
the target OS subdir.

The gcc_version.* files are only cleared once per make instantiation so
a build that creates multiple HW targets will try to link with an
incompatible .o file (i.e. x86 build linking ARM .o).  I created
posix-arm as a separate target to fix this problem.

Signed-off-by: Mark Charlebois <charlebm@gmail.com>
This commit is contained in:
Mark Charlebois 2015-06-07 14:40:54 -07:00
parent 59ad47003a
commit 58e263d534
19 changed files with 485 additions and 10 deletions

1
.gitignore vendored
View File

@ -49,4 +49,5 @@ unittests/build
*.pretty
xcode
src/platforms/posix/px4_messages/
src/platforms/posix-arm/px4_messages/
src/platforms/qurt/px4_messages/

View File

@ -33,7 +33,7 @@
# Top-level Makefile for building PX4 firmware images.
#
TARGETS := nuttx posix qurt
TARGETS := nuttx posix posix-arm qurt
EXPLICIT_TARGET := $(filter $(TARGETS),$(MAKECMDGOALS))
ifneq ($(EXPLICIT_TARGET),)
export PX4_TARGET_OS=$(EXPLICIT_TARGET)
@ -241,6 +241,9 @@ endif
ifeq ($(PX4_TARGET_OS),posix)
include $(PX4_BASE)makefiles/firmware_posix.mk
endif
ifeq ($(PX4_TARGET_OS),posix-arm)
include $(PX4_BASE)makefiles/firmware_posix.mk
endif
ifeq ($(PX4_TARGET_OS),qurt)
include $(PX4_BASE)makefiles/firmware_qurt.mk
endif
@ -285,7 +288,7 @@ testbuild:
$(Q) (cd $(PX4_BASE) && $(MAKE) distclean && $(MAKE) archives && $(MAKE) -j8)
$(Q) (zip -r Firmware.zip $(PX4_BASE)/Images)
nuttx posix qurt:
nuttx posix posix-arm qurt:
ifeq ($(GOALS),)
make PX4_TARGET_OS=$@ $(GOALS)
else

View File

@ -548,6 +548,9 @@ endif
ifeq ($(PX4_TARGET_OS),posix)
include $(MK_DIR)/posix_elf.mk
endif
ifeq ($(PX4_TARGET_OS),posix-arm)
include $(MK_DIR)/posix_elf.mk
endif
ifeq ($(PX4_TARGET_OS),qurt)
include $(MK_DIR)/qurt_elf.mk
endif

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = AEROCORE
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = PX4_STM32F4DISCOVERY
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = PX4FMU_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM4F
CONFIG_BOARD = PX4FMU_V2
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM3
CONFIG_BOARD = PX4IO_V1
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = CORTEXM3
CONFIG_BOARD = PX4IO_V2
include $(PX4_MK_DIR)/toolchain_gnu-arm-eabi.mk
include $(PX4_MK_DIR)/nuttx/toolchain_gnu-arm-eabi.mk

40
makefiles/posix-arm.mk Normal file
View File

@ -0,0 +1,40 @@
#
# 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 Linux specific impl when
# building firmware.
#
MODULES += \
platforms/common \
platforms/posix/px4_layer

View File

@ -0,0 +1,11 @@
#
# Board-specific definitions for the POSIX port of PX4
#
#
# Configure the toolchain
#
CONFIG_ARCH = CORTEXA8
CONFIG_BOARD = EAGLE
include $(PX4_MK_DIR)/posix-arm/toolchain_gnu-arm-linux-gnueabihf.mk

View File

@ -0,0 +1,85 @@
#
# Makefile for the POSIXTEST *default* configuration
#
#
# Board support modules
#
MODULES += drivers/device
MODULES += drivers/blinkm
MODULES += drivers/hil
MODULES += drivers/rgbled
MODULES += drivers/led
MODULES += modules/sensors
#MODULES += drivers/ms5611
#
# System commands
#
MODULES += systemcmds/param
MODULES += systemcmds/mixer
MODULES += systemcmds/topic_listener
#
# General system control
#
MODULES += modules/mavlink
#
# Estimation modules (EKF/ SO3 / other filters)
#
MODULES += modules/attitude_estimator_ekf
MODULES += modules/ekf_att_pos_estimator
#
# Vehicle Control
#
MODULES += modules/navigator
MODULES += modules/mc_pos_control
MODULES += modules/mc_att_control
#
# Library modules
#
MODULES += modules/systemlib
MODULES += modules/systemlib/mixer
MODULES += modules/uORB
MODULES += modules/dataman
MODULES += modules/sdlog2
MODULES += modules/simulator
MODULES += modules/commander
MODULES += modules/controllib
#
# Libraries
#
MODULES += lib/mathlib
MODULES += lib/mathlib/math/filter
MODULES += lib/geo
MODULES += lib/geo_lookup
MODULES += lib/conversion
#
# Linux port
#
MODULES += platforms/posix/px4_layer
MODULES += platforms/posix/drivers/accelsim
MODULES += platforms/posix/drivers/gyrosim
MODULES += platforms/posix/drivers/adcsim
MODULES += platforms/posix/drivers/barosim
MODULES += platforms/posix/drivers/tonealrmsim
MODULES += platforms/posix/drivers/airspeedsim
MODULES += platforms/posix/drivers/gpssim
#
# Unit tests
#
#MODULES += platforms/posix/tests/hello
#MODULES += platforms/posix/tests/vcdev_test
#MODULES += platforms/posix/tests/hrt_test
#MODULES += platforms/posix/tests/wqueue
#
# muorb fastrpc changes.
#
#MODULES += $(PX4_BASE)../muorb_krait

View File

@ -0,0 +1,329 @@
#
# Copyright (C) 2012-2014 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 arm-linux-gnueabihf)
# Toolchain commands. Normally only used inside this file.
#
CROSSDEV = arm-linux-gnueabihf-
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
# Check if the right version of the toolchain is available
#
CROSSDEV_VER_SUPPORTED = 4.7.4 4.7.5 4.7.6 4.8.2 4.8.4 4.9.3
CROSSDEV_VER_FOUND = $(shell $(CC) -dumpversion)
ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED)))
$(error Unsupported version of $(CC), found: $(CROSSDEV_VER_FOUND) instead of one in: $(CROSSDEV_VER_SUPPORTED))
endif
# 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_CORTEXA8 = -mtune=cortex-a8 \
-mthumb-interwork \
-march=armv7-a \
-mfloat-abi=hard \
-mfpu=neon
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
# Enabling stack checks if OS was build with them
#
TEST_FILE_STACKCHECK=$(WORK_DIR)nuttx-export/include/nuttx/config.h
TEST_VALUE_STACKCHECK=CONFIG_ARMV7M_STACKCHECK\ 1
ENABLE_STACK_CHECKS=$(shell $(GREP) -q "$(TEST_VALUE_STACKCHECK)" $(TEST_FILE_STACKCHECK); echo $$?;)
ifeq ("$(ENABLE_STACK_CHECKS)","0")
ARCHINSTRUMENTATIONDEFINES_CORTEXM4F = -finstrument-functions -ffixed-r10
ARCHINSTRUMENTATIONDEFINES_CORTEXM4 = -finstrument-functions -ffixed-r10
ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
else
ARCHINSTRUMENTATIONDEFINES_CORTEXM4F =
ARCHINSTRUMENTATIONDEFINES_CORTEXM4 =
ARCHINSTRUMENTATIONDEFINES_CORTEXM3 =
endif
# Pick the right set of flags for the architecture.
#
ARCHCPUFLAGS = $(ARCHCPUFLAGS_$(CONFIG_ARCH))
ifeq ($(ARCHCPUFLAGS),)
$(error Must set CONFIG_ARCH to one of CORTEXA8 CORTEXM4F, CORTEXM4 or CORTEXM3)
endif
# Set the board flags
#
ifeq ($(CONFIG_BOARD),)
$(error Board config does not define CONFIG_BOARD)
endif
ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \
-D__PX4_LINUX -D__PX4_POSIX \
-Dnoreturn_function= \
-I$(PX4_BASE)/src/modules/systemlib \
-I$(PX4_BASE)/src/lib/eigen \
-I$(PX4_BASE)/src/platforms/posix/include \
-I$(PX4_BASE)/mavlink/include/mavlink \
-Wno-error=shadow
# optimisation flags
#
ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \
-g3 \
-fno-strict-aliasing \
-fomit-frame-pointer \
-funsafe-math-optimizations \
-fno-builtin-printf \
-ffunction-sections \
-fdata-sections
# Language-specific flags
#
ARCHCFLAGS = -std=gnu99
ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=c++0x -fno-threadsafe-statics -D__CUSTOM_FILE_IO__
# Generic warnings
#
ARCHWARNINGS = -Wall \
-Wextra \
-Werror \
-Wfloat-equal \
-Wpointer-arith \
-Wmissing-declarations \
-Wpacked \
-Wno-unused-parameter \
-Wno-packed \
-Werror=format-security \
-Werror=array-bounds \
-Wfatal-errors \
-Werror=unused-variable \
-Werror=reorder \
-Werror=uninitialized \
-Werror=init-self \
-Wno-error=logical-op \
-Wdouble-promotion \
-Wlogical-op \
-Wformat=1 \
-Werror=unused-but-set-variable \
-Werror=double-promotion \
-fno-strength-reduce \
-Wno-error=unused-value
ARCHOPTIMIZATION += -fno-strength-reduce
# -Werror=float-conversion - works, just needs to be phased in with some effort and needs GCC 4.9+
# -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 \
-Wmissing-prototypes \
-Wnested-externs
# C++-specific warnings
#
ARCHWARNINGSXX = $(ARCHWARNINGS) \
-Wno-missing-field-initializers
# pull in *just* libm from the toolchain ... this is grody
LIBM := $(shell $(CC) $(ARCHCPUFLAGS) -print-file-name=libm.a)
#EXTRA_LIBS += $(LIBM)
#EXTRA_LIBS += ${PX4_BASE}../muorb_krait/lib/libmuorb.so
EXTRA_LIBS += -pthread -lm -lrt
# 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) \
-Wno-effc++ \
$(addprefix -I,$(INCLUDE_DIRS))
# Flags we pass to the assembler
#
AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \
$(EXTRADEFINES) \
$(EXTRAAFLAGS)
LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script
# Flags we pass to the linker
#
LDFLAGS += $(EXTRALDFLAGS) \
$(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)
LINK_DEPS +=
# 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) $(CCACHE) $(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)
@echo $(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) $(abspath $1) -o $2
$(Q) $(CCACHE) $(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
#
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
define PRELINK
@$(ECHO) "PRELINK: $1"
@$(MKDIR) -p $(dir $1)
$(Q) $(LD) -Ur -o $1 $2
endef
# Produce partially-linked $1 from files in $2
#
#$(Q) $(LD) -Ur -o $1 $2 # -Ur not supported in ld.gold
define PRELINKF
@$(ECHO) "PRELINK: $1"
@$(MKDIR) -p $(dir $1)
$(Q) $(LD) -Ur -T$(LDSCRIPT) -o $1 $2
endef
# $(Q) $(LD) -Ur -o $1 $2 && $(OBJCOPY) --localize-hidden $1
# 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 shared library $1
#
define LINK_A
@$(ECHO) "LINK_A: $1"
@$(MKDIR) -p $(dir $1)
echo "$(Q) $(AR) $1 $2"
$(Q) $(AR) $1 $2
endef
# Link the objects in $2 into the shared library $1
#
define LINK_SO
@$(ECHO) "LINK_SO: $1"
@$(MKDIR) -p $(dir $1)
echo "$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) $(EXTRA_LIBS)"
$(Q) $(CXX) $(LDFLAGS) -shared -Wl,-soname,`basename $1`.1 -o $1 $2 $(LIBS) -pthread -lc
endef
# Link the objects in $2 into the application $1
#
define LINK
@$(ECHO) "LINK: $1"
@$(MKDIR) -p $(dir $1)
$(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC)
endef

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = NATIVE
CONFIG_BOARD = POSIXTEST
include $(PX4_MK_DIR)/toolchain_native.mk
include $(PX4_MK_DIR)/posix/toolchain_native.mk

View File

@ -8,4 +8,4 @@
CONFIG_ARCH = HEXAGON
CONFIG_BOARD = QURTTEST
include $(PX4_MK_DIR)/toolchain_hexagon.mk
include $(PX4_MK_DIR)/qurt/toolchain_hexagon.mk

View File

@ -52,6 +52,9 @@ endif
ifeq ($(PX4_TARGET_OS),posix)
SRCS += uORBTest_UnitTest.cpp
endif
ifeq ($(PX4_TARGET_OS),posix-arm)
SRCS += uORBTest_UnitTest.cpp
endif
SRCS += objects_common.cpp \
Publication.cpp \