From 851a020461c99539afa0c34d6f05e9b33ee379f7 Mon Sep 17 00:00:00 2001 From: Mark Charlebois Date: Wed, 1 Jul 2015 09:48:50 -0700 Subject: [PATCH] Eagle: posix-arm and qurt changes to support Eagle HW platform The Eagle HW platform contains both a Krait (ARMv4hf compatible) cpu cluster and a Hexagon DSP running QuRT. These changes support the PX4 build for Eagle. Signed-off-by: Mark Charlebois --- Tools/qurt_apps.py | 16 ++++ makefiles/posix-arm/config_eagle_default.mk | 15 +--- makefiles/posix-arm/config_eagle_hil.mk | 86 ++++++++++++++++++ .../posix-arm/config_eagle_muorb_test.mk | 89 +++++++++++++++++++ makefiles/posix-arm/ld.script | 46 ++++++++++ .../toolchain_gnu-arm-linux-gnueabihf.mk | 13 +-- makefiles/qurt/config_qurt_hil.mk | 81 +++++++++++++++++ makefiles/qurt/config_qurt_muorb_test.mk | 79 ++++++++++++++++ makefiles/qurt/qurt_elf.mk | 6 +- makefiles/qurt/toolchain_hexagon.mk | 52 ++++++----- 10 files changed, 444 insertions(+), 39 deletions(-) create mode 100644 makefiles/posix-arm/config_eagle_hil.mk create mode 100644 makefiles/posix-arm/config_eagle_muorb_test.mk create mode 100644 makefiles/posix-arm/ld.script create mode 100644 makefiles/qurt/config_qurt_hil.mk create mode 100644 makefiles/qurt/config_qurt_muorb_test.mk diff --git a/Tools/qurt_apps.py b/Tools/qurt_apps.py index e5d75344be..b1f606c37a 100755 --- a/Tools/qurt_apps.py +++ b/Tools/qurt_apps.py @@ -48,6 +48,8 @@ print """ #include #include +#include +#include using namespace std; @@ -64,6 +66,7 @@ static int list_tasks_main(int argc, char *argv[]); static int list_files_main(int argc, char *argv[]); static int list_devices_main(int argc, char *argv[]); static int list_topics_main(int argc, char *argv[]); +static int sleep_main(int argc, char *argv[]); } @@ -78,6 +81,7 @@ print '\tapps["list_tasks"] = list_tasks_main;' print '\tapps["list_files"] = list_files_main;' print '\tapps["list_devices"] = list_devices_main;' print '\tapps["list_topics"] = list_topics_main;' +print '\tapps["sleep"] = sleep_main;' print """ } @@ -117,5 +121,17 @@ static int list_files_main(int argc, char *argv[]) px4_show_files(); return 0; } +static int sleep_main(int argc, char *argv[]) +{ + if (argc != 2) { + PX4_WARN( "Usage: sleep " ); + return 1; + } + + unsigned long usecs = ( (unsigned long) atol( argv[1] ) ) * 1000 * 1000; + PX4_WARN("Sleeping for %s, %ld",argv[1],usecs); + usleep( usecs ); + return 0; +} """ diff --git a/makefiles/posix-arm/config_eagle_default.mk b/makefiles/posix-arm/config_eagle_default.mk index d66cc5ed73..90afa155c0 100644 --- a/makefiles/posix-arm/config_eagle_default.mk +++ b/makefiles/posix-arm/config_eagle_default.mk @@ -18,7 +18,8 @@ MODULES += modules/sensors # MODULES += systemcmds/param MODULES += systemcmds/mixer -MODULES += systemcmds/topic_listener +MODULES += systemcmds/ver +#MODULES += systemcmds/topic_listener # # General system control @@ -34,7 +35,7 @@ MODULES += modules/ekf_att_pos_estimator # # Vehicle Control # -MODULES += modules/navigator +#MODULES += modules/navigator MODULES += modules/mc_pos_control MODULES += modules/mc_att_control @@ -48,7 +49,7 @@ MODULES += modules/dataman MODULES += modules/sdlog2 MODULES += modules/simulator MODULES += modules/commander -MODULES += modules/controllib +#MODULES += modules/controllib # # Libraries @@ -58,18 +59,10 @@ 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 diff --git a/makefiles/posix-arm/config_eagle_hil.mk b/makefiles/posix-arm/config_eagle_hil.mk new file mode 100644 index 0000000000..c70ef198a8 --- /dev/null +++ b/makefiles/posix-arm/config_eagle_hil.mk @@ -0,0 +1,86 @@ +# +# 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 +MODULES += systemcmds/ver + +# +# 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 += modules/muorb/krait diff --git a/makefiles/posix-arm/config_eagle_muorb_test.mk b/makefiles/posix-arm/config_eagle_muorb_test.mk new file mode 100644 index 0000000000..ec080c9195 --- /dev/null +++ b/makefiles/posix-arm/config_eagle_muorb_test.mk @@ -0,0 +1,89 @@ +# +# 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 + +# +# muorb fastrpc changes. +# +MODULES += modules/muorb/krait + + +# +# +# Unit tests +# +#MODULES += platforms/posix/tests/hello +#MODULES += platforms/posix/tests/vcdev_test +#MODULES += platforms/posix/tests/hrt_test +#MODULES += platforms/posix/tests/wqueue +MODULES += platforms/posix/tests/muorb + diff --git a/makefiles/posix-arm/ld.script b/makefiles/posix-arm/ld.script new file mode 100644 index 0000000000..32478e1e14 --- /dev/null +++ b/makefiles/posix-arm/ld.script @@ -0,0 +1,46 @@ +/**************************************************************************** + * ld.script + * + * Copyright (C) 2015 Mark Charlebois. All rights reserved. + * Author: Mark Charlebois + * + * 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. + * + ****************************************************************************/ + +SECTIONS +{ + /* + * Construction data for parameters. + */ + __param : ALIGN(8) { + __param_start = .; + KEEP(*(__param*)) + __param_end = .; + } +} diff --git a/makefiles/posix-arm/toolchain_gnu-arm-linux-gnueabihf.mk b/makefiles/posix-arm/toolchain_gnu-arm-linux-gnueabihf.mk index a5964e07d9..2811512ecd 100644 --- a/makefiles/posix-arm/toolchain_gnu-arm-linux-gnueabihf.mk +++ b/makefiles/posix-arm/toolchain_gnu-arm-linux-gnueabihf.mk @@ -57,6 +57,7 @@ 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 +EXT_MUORB_LIB_ROOT = /opt/muorb_libs # XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup @@ -156,12 +157,11 @@ ARCHWARNINGS = -Wall \ -Werror=reorder \ -Werror=uninitialized \ -Werror=init-self \ - -Wno-error=logical-op \ - -Wdouble-promotion \ + -Wno-error=logical-op \ -Wlogical-op \ -Wformat=1 \ -Werror=unused-but-set-variable \ - -Werror=double-promotion \ + -Wno-error=double-promotion \ -fno-strength-reduce \ -Wno-error=unused-value @@ -188,9 +188,11 @@ ARCHWARNINGSXX = $(ARCHWARNINGS) \ # 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 += -lpx4muorb -ladsprpc EXTRA_LIBS += -pthread -lm -lrt +LIB_DIRS += $(EXT_MUORB_LIB_ROOT)/krait/libs + # Flags we pass to the C compiler # CFLAGS = $(ARCHCFLAGS) \ @@ -226,7 +228,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \ $(EXTRADEFINES) \ $(EXTRAAFLAGS) -LDSCRIPT = $(PX4_BASE)/posix-configs/posixtest/scripts/ld.script +LDSCRIPT = $(PX4_BASE)/makefiles/posix-arm/ld.script # Flags we pass to the linker # LDFLAGS += $(EXTRALDFLAGS) \ @@ -323,6 +325,7 @@ endef define LINK @$(ECHO) "LINK: $1" @$(MKDIR) -p $(dir $1) + echo "$(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC)" $(Q) $(CXX) $(CXXFLAGS) $(LDFLAGS) -o $1 $2 $(LIBS) $(EXTRA_LIBS) $(LIBGCC) endef diff --git a/makefiles/qurt/config_qurt_hil.mk b/makefiles/qurt/config_qurt_hil.mk new file mode 100644 index 0000000000..9d4a48eeed --- /dev/null +++ b/makefiles/qurt/config_qurt_hil.mk @@ -0,0 +1,81 @@ +# +# Makefile for the Foo *default* configuration +# + +# +# Board support modules +# +MODULES += drivers/device +#MODULES += drivers/blinkm +MODULES += drivers/hil +MODULES += drivers/led +MODULES += drivers/rgbled +MODULES += modules/sensors +#MODULES += drivers/ms5611 + +# +# System commands +# +MODULES += systemcmds/param +MODULES += systemcmds/mixer + +# +# General system control +# +#MODULES += modules/mavlink + +# +# Estimation modules (EKF/ SO3 / other filters) +# +#MODULES += modules/attitude_estimator_ekf +MODULES += modules/ekf_att_pos_estimator +MODULES += modules/attitude_estimator_q +MODULES += modules/position_estimator_inav + +# +# Vehicle Control +# +MODULES += modules/mc_att_control +MODULES += modules/mc_pos_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 + +# +# Libraries +# +MODULES += lib/mathlib +MODULES += lib/mathlib/math/filter +MODULES += lib/geo +MODULES += lib/geo_lookup +MODULES += lib/conversion + +# +# QuRT port +# +MODULES += platforms/qurt/px4_layer +#MODULES += platforms/posix/drivers/accelsim +#MODULES += platforms/posix/drivers/gyrosim +#MODULES += platforms/posix/drivers/adcsim +#MODULES += platforms/posix/drivers/barosim + +# +# Unit tests +# +#MODULES += platforms/qurt/tests/muorb +#MODULES += platforms/posix/tests/vcdev_test +#MODULES += platforms/posix/tests/hrt_test +#MODULES += platforms/posix/tests/wqueue + +# +# sources for muorb over fastrpc +# +MODULES += modules/muorb/adsp/ diff --git a/makefiles/qurt/config_qurt_muorb_test.mk b/makefiles/qurt/config_qurt_muorb_test.mk new file mode 100644 index 0000000000..b503e44a69 --- /dev/null +++ b/makefiles/qurt/config_qurt_muorb_test.mk @@ -0,0 +1,79 @@ +# +# Makefile for the Foo *default* configuration +# + +# +# Board support modules +# +MODULES += drivers/device +#MODULES += drivers/blinkm +MODULES += drivers/hil +MODULES += drivers/led +MODULES += drivers/rgbled +MODULES += modules/sensors +#MODULES += drivers/ms5611 + +# +# System commands +# +MODULES += systemcmds/param +MODULES += systemcmds/mixer + +# +# 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/mc_att_control +MODULES += modules/mc_pos_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 + +# +# Libraries +# +MODULES += lib/mathlib +MODULES += lib/mathlib/math/filter +MODULES += lib/geo +MODULES += lib/geo_lookup +MODULES += lib/conversion + +# +# QuRT port +# +MODULES += platforms/qurt/px4_layer +MODULES += platforms/posix/drivers/accelsim +MODULES += platforms/posix/drivers/gyrosim +MODULES += platforms/posix/drivers/adcsim +MODULES += platforms/posix/drivers/barosim + +# +# Unit tests +# +MODULES += platforms/qurt/tests/muorb +#MODULES += platforms/posix/tests/vcdev_test +#MODULES += platforms/posix/tests/hrt_test +#MODULES += platforms/posix/tests/wqueue + +# +# sources for muorb over fastrpc +# +MODULES += modules/muorb/adsp/ diff --git a/makefiles/qurt/qurt_elf.mk b/makefiles/qurt/qurt_elf.mk index 281a1603d2..73f1cd4ece 100644 --- a/makefiles/qurt/qurt_elf.mk +++ b/makefiles/qurt/qurt_elf.mk @@ -41,12 +41,12 @@ # What we're going to build. # -EXTRALDFLAGS = -Wl,-soname=libdspal_client.so +EXTRALDFLAGS = -Wl,-soname=libpx4.so PRODUCT_SHARED_LIB = $(WORK_DIR)firmware.a PRODUCT_SHARED_PRELINK = $(WORK_DIR)firmware.o .PHONY: firmware -firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)libdspal_client.so $(WORK_DIR)mainapp +firmware: $(PRODUCT_SHARED_LIB) $(WORK_DIR)libpx4.so $(WORK_DIR)mainapp # # Built product rules @@ -65,7 +65,7 @@ $(WORK_DIR)apps.o: $(WORK_DIR)apps.cpp $(call COMPILEXX,$<, $@) mv $(WORK_DIR)apps.cpp $(WORK_DIR)apps.cpp_sav -$(WORK_DIR)libdspal_client.so: $(WORK_DIR)apps.o $(PRODUCT_SHARED_LIB) +$(WORK_DIR)libpx4.so: $(WORK_DIR)apps.o $(PRODUCT_SHARED_LIB) $(call LINK_SO,$@, $^) $(WORK_DIR)dspal_stub.o: $(PX4_BASE)/src/platforms/qurt/dspal/dspal_stub.c diff --git a/makefiles/qurt/toolchain_hexagon.mk b/makefiles/qurt/toolchain_hexagon.mk index 8b5bf5423e..d8e6427e4e 100644 --- a/makefiles/qurt/toolchain_hexagon.mk +++ b/makefiles/qurt/toolchain_hexagon.mk @@ -37,7 +37,8 @@ # Toolchain commands. Normally only used inside this file. # -HEXAGON_TOOLS_ROOT = /opt/6.4.05 +HEXAGON_TOOLS_ROOT = /opt/6.4.03 +#HEXAGON_TOOLS_ROOT = /opt/6.4.05 HEXAGON_SDK_ROOT = /opt/Hexagon_SDK/2.0 V_ARCH = v5 CROSSDEV = hexagon- @@ -84,7 +85,8 @@ DYNAMIC_LIBS = \ # Check if the right version of the toolchain is available # -CROSSDEV_VER_SUPPORTED = 6.4.05 +CROSSDEV_VER_SUPPORTED = 6.4.03 +#CROSSDEV_VER_SUPPORTED = 6.4.05 CROSSDEV_VER_FOUND = $(shell $(CC) --version | sed -n 's/^.*version \([\. 0-9]*\),.*$$/\1/p') ifeq (,$(findstring $(CROSSDEV_VER_FOUND), $(CROSSDEV_VER_SUPPORTED))) @@ -94,7 +96,7 @@ endif # XXX this is pulled pretty directly from the fmu Make.defs - needs cleanup -MAXOPTIMIZATION ?= -O0 +MAXOPTIMIZATION := -O0 # Base CPU flags for each of the supported architectures. # @@ -108,31 +110,38 @@ $(error Board config does not define CONFIG_BOARD) endif ARCHDEFINES += -DCONFIG_ARCH_BOARD_$(CONFIG_BOARD) \ -D__PX4_QURT -D__PX4_POSIX \ - -D__EXPORT= \ - -D__QDSP6_DINKUM_PTHREAD_TYPES__ \ + -D_PID_T -D_UID_T -D_TIMER_T\ -Dnoreturn_function= \ + -D__EXPORT= \ -Drestrict= \ + -D_DEBUG \ + -I$(PX4_BASE)/../dspal/include \ + -I$(PX4_BASE)/../dspal/sys \ -I$(HEXAGON_TOOLS_ROOT)/gnu/hexagon/include \ -I$(PX4_BASE)/src/lib/eigen \ -I$(PX4_BASE)/src/platforms/qurt/include \ - -I$(PX4_BASE)/../dspal/include \ - -I$(PX4_BASE)/../dspal/sys \ -I$(PX4_BASE)/mavlink/include/mavlink \ -I$(QURTLIB)/..//include \ -I$(HEXAGON_SDK_ROOT)/inc \ -I$(HEXAGON_SDK_ROOT)/inc/stddef \ -Wno-error=shadow + + # optimisation flags # -ARCHOPTIMIZATION = $(MAXOPTIMIZATION) \ - -g3 \ +ARCHOPTIMIZATION = \ + -O0 \ + -g \ -fno-strict-aliasing \ - -fomit-frame-pointer \ - -funsafe-math-optimizations \ - -ffunction-sections \ -fdata-sections \ - -fpic + -fpic \ + -fno-zero-initialized-in-bss + +#-fomit-frame-pointer \ +#-funsafe-math-optimizations \ +#-ffunction-sections +#$(MAXOPTIMIZATION) # enable precise stack overflow tracking # note - requires corresponding support in NuttX @@ -140,7 +149,7 @@ INSTRUMENTATIONDEFINES = $(ARCHINSTRUMENTATIONDEFINES_$(CONFIG_ARCH)) # Language-specific flags # -ARCHCFLAGS = -std=gnu99 +ARCHCFLAGS = -std=gnu99 -D__CUSTOM_FILE_IO__ ARCHCXXFLAGS = -fno-exceptions -fno-rtti -std=gnu++0x -fno-threadsafe-statics -D__CUSTOM_FILE_IO__ # Generic warnings @@ -186,9 +195,9 @@ CFLAGS = $(ARCHCFLAGS) \ $(ARCHDEFINES) \ $(EXTRADEFINES) \ $(EXTRACFLAGS) \ - -fno-common \ $(addprefix -I,$(INCLUDE_DIRS)) + #-fno-common # Flags we pass to the C++ compiler # CXXFLAGS = $(ARCHCXXFLAGS) \ @@ -212,8 +221,7 @@ AFLAGS = $(CFLAGS) -D__ASSEMBLY__ \ LDSCRIPT = $(PX4_BASE)/makefiles/posix/ld.script # Flags we pass to the linker # -LDFLAGS += -g -mv5 -nostdlib -mG0lib -G0 -fpic -shared \ - -nostartfiles \ +LDFLAGS += -g -mv5 -mG0lib -G0 -fpic -shared \ -Wl,-Bsymbolic \ -Wl,--wrap=malloc \ -Wl,--wrap=calloc \ @@ -254,7 +262,9 @@ define COMPILE @$(ECHO) "CC: $1" @$(MKDIR) -p $(dir $2) @echo $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) $(abspath $1) -o $2 - $(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) -D__V_DYNAMIC__ -fPIC $(abspath $1) -o $2 + #$(Q) $(CCACHE) $(CC) -MD -c $(CFLAGS) -D__V_DYNAMIC__ -fPIC $(abspath $1) -o $2 + #$(CCACHE) $(CC) -MD -c $(CFLAGS) -D__V_DYNAMIC__ -D__FILENAME__=\"$(notdir $1)\" -fPIC $(abspath $1) -o $2 + $(CCACHE) $(CC) -c $(CFLAGS) -D__V_DYNAMIC__ -D__FILENAME__=\"$(notdir $1)\" $(abspath $1) -o $2 endef # Compile C++ source $1 to $2 for use in shared library @@ -264,7 +274,9 @@ 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) -D__V_DYNAMIC__ -fPIC $(abspath $1) -o $2 + #$(Q) $(CCACHE) $(CXX) -MD -c $(CXXFLAGS) -D__V_DYNAMIC__ -fPIC $(abspath $1) -o $2 + #$(CCACHE) $(CXX) -MD -c $(CXXFLAGS) -D__V_DYNAMIC__ -D__FILENAME__=\"$(notdir $1)\" -fPIC $(abspath $1) -o $2 + $(CCACHE) $(CXX) -c $(CXXFLAGS) -D__V_DYNAMIC__ -D__FILENAME__=\"$(notdir $1)\" $(abspath $1) -o $2 endef # Assemble $1 into $2 @@ -319,7 +331,7 @@ endef define LINK_SO @$(ECHO) "LINK_SO: $1" @$(MKDIR) -p $(dir $1) - $(HEXAGON_GCC) $(LDFLAGS) -fPIC -shared -nostartfiles -o $1 -Wl,--whole-archive $2 -Wl,--no-whole-archive $(LIBS) $(DYNAMIC_LIBS) + $(HEXAGON_GCC) $(LDFLAGS) -o $1 -Wl,--whole-archive $2 -Wl,--no-whole-archive $(LIBS) $(DYNAMIC_LIBS) endef # Link the objects in $2 into the application $1