Merged export-build

This commit is contained in:
Lorenz Meier 2013-04-28 10:40:00 +02:00
commit 6aefe5fddf
431 changed files with 148 additions and 1402 deletions

View File

@ -1,42 +0,0 @@
############################################################################
#
# 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.
#
############################################################################
#
# Basic example application
#
APPNAME = px4_mavlink_debug
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
include $(APPDIR)/mk/app.mk

View File

@ -1,237 +0,0 @@
############################################################################
#
# 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.
#
############################################################################
#
# Common Makefile for nsh command modules and utility libraries; should be
# included by the module-specific Makefile.
#
# To build an app that appears as an nsh external command, the caller
# must define:
#
# APPNAME - the name of the application, defaults to the name
# of the parent directory.
#
# If APPNAME is not defined, a utility library is built instead. The library
# name is normally automatically determined, but it can be overridden by
# setting:
#
# LIBNAME - the name of the library, defaults to the name of the
# directory
#
# The calling makefile may also set:
#
# ASRCS - list of assembly source files, defaults to all .S
# files in the directory
#
# CSRCS - list of C source files, defaults to all .c files
# in the directory
#
# CXXSRCS - list of C++ source files, defaults to all .cpp
# files in the directory
#
# INCLUDES - list of directories to be added to the include
# search path
#
# PRIORITY - thread priority for the command (defaults to
# SCHED_PRIORITY_DEFAULT)
#
# STACKSIZE - stack size for the command (defaults to
# CONFIG_PTHREAD_STACK_DEFAULT)
#
# Symbols in the module are private to the module unless deliberately exported
# using the __EXPORT tag, or DEFAULT_VISIBILITY is set
#
############################################################################
# No user-serviceable parts below
############################################################################
############################################################################
# Work out who included us so we can report decent errors
#
THIS_MAKEFILE := $(lastword $(MAKEFILE_LIST))
ifeq ($(APP_MAKEFILE),)
APP_MAKEFILE := $(lastword $(filter-out $(THIS_MAKEFILE),$(MAKEFILE_LIST)))
endif
############################################################################
# Get configuration
#
-include $(TOPDIR)/.config
-include $(TOPDIR)/Make.defs
include $(APPDIR)/Make.defs
############################################################################
# Sanity-check the information we've been given and set any defaults
#
SRCDIR ?= $(dir $(APP_MAKEFILE))
PRIORITY ?= SCHED_PRIORITY_DEFAULT
STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
INCLUDES += $(APPDIR)
ASRCS ?= $(wildcard $(SRCDIR)/*.S)
CSRCS ?= $(wildcard $(SRCDIR)/*.c)
CHDRS ?= $(wildcard $(SRCDIR)/*.h)
CXXSRCS ?= $(wildcard $(SRCDIR)/*.cpp)
CXXHDRS ?= $(wildcard $(SRCDIR)/*.hpp)
# if APPNAME is not set, this is a library
ifeq ($(APPNAME),)
LIBNAME ?= $(lastword $(subst /, ,$(realpath $(SRCDIR))))
endif
# there has to be a source file
ifeq ($(ASRCS)$(CSRCS)$(CXXSRCS),)
$(error $(realpath $(APP_MAKEFILE)): at least one of ASRCS, CSRCS or CXXSRCS must be set)
endif
# check that C++ is configured if we have C++ source files and we are building
ifneq ($(CXXSRCS),)
ifneq ($(CONFIG_HAVE_CXX),y)
ifeq ($(MAKECMDGOALS),build)
$(error $(realpath $(APP_MAKEFILE)): cannot set CXXSRCS if CONFIG_HAVE_CXX not set in configuration)
endif
endif
endif
############################################################################
# Adjust compilation flags to implement EXPORT
#
ifeq ($(DEFAULT_VISIBILITY),)
DEFAULT_VISIBILITY = hidden
else
DEFAULT_VISIBILITY = default
endif
CFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(APPDIR)/systemlib/visibility.h
CXXFLAGS += -fvisibility=$(DEFAULT_VISIBILITY) -include $(APPDIR)/systemlib/visibility.h
############################################################################
# Add extra include directories
#
CFLAGS += $(addprefix -I,$(INCLUDES))
CXXFLAGS += $(addprefix -I,$(INCLUDES))
############################################################################
# Things we are going to build
#
SRCS = $(ASRCS) $(CSRCS) $(CXXSRCS)
AOBJS = $(patsubst %.S,%.o,$(ASRCS))
COBJS = $(patsubst %.c,%.o,$(CSRCS))
CXXOBJS = $(patsubst %.cpp,%.o,$(CXXSRCS))
OBJS = $(AOBJS) $(COBJS) $(CXXOBJS)
# Automatic depdendency generation
DEPS = $(OBJS:$(OBJEXT)=.d)
CFLAGS += -MD
CXXFLAGS += -MD
# The prelinked object that we are ultimately going to build
ifneq ($(APPNAME),)
PRELINKOBJ = $(APPNAME).pre.o
else
PRELINKOBJ = $(LIBNAME).pre.o
endif
# The archive the prelinked object will be linked into
# XXX does WINTOOL ever get set?
ifeq ($(WINTOOL),y)
INCDIROPT = -w
BIN = "$(shell cygpath -w $(APPDIR)/libapps$(LIBEXT))"
else
BIN = "$(APPDIR)/libapps$(LIBEXT)"
endif
############################################################################
# Rules for building things
#
all: .built
.PHONY: clean depend distclean
#
# Top-level build; add prelinked object to the apps archive
#
.built: $(PRELINKOBJ)
@$(call ARCHIVE, $(BIN), $(PRELINKOBJ))
@touch $@
#
# Source dependencies
#
depend:
@exit 0
ifneq ($(APPNAME),)
#
# App registration
#
context: .context
.context: $(MAKEFILE_LIST)
$(call REGISTER,$(APPNAME),$(PRIORITY),$(STACKSIZE),$(APPNAME)_main)
@touch $@
else
context:
@exit 0
endif
#
# Object files
#
$(PRELINKOBJ): $(OBJS)
$(call PRELINK, $@, $(OBJS))
$(AOBJS): %.o : %.S $(MAKEFILE_LIST)
$(call ASSEMBLE, $<, $@)
$(COBJS): %.o : %.c $(MAKEFILE_LIST)
$(call COMPILE, $<, $@)
$(CXXOBJS): %.o : %.cpp $(MAKEFILE_LIST)
$(call COMPILEXX, $<, $@)
#
# Tidying up
#
clean:
@rm -f $(OBJS) $(DEPS) $(PRELINKOBJ) .built
$(call CLEAN)
distclean: clean
@rm -f Make.dep .depend
-include $(DEPS)

View File

@ -10,6 +10,7 @@ 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
@ -75,6 +76,32 @@ MODULES += modules/multirotor_pos_control
#
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.
#

View File

@ -186,7 +186,7 @@ define SRC_SEARCH
$(abspath $(firstword $(wildcard $(MODULE_SRC)/$1) MISSING_$1))
endef
ABS_SRCS := $(foreach src,$(SRCS),$(call SRC_SEARCH,$(src)))
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))

View File

@ -56,6 +56,7 @@ export ARCHIVE_DIR = $(abspath $(PX4_BASE)/Archives)/
# Default include paths
#
export INCLUDE_DIRS := $(PX4_MODULE_SRC) \
$(PX4_MODULE_SRC)/modules/ \
$(PX4_INCLUDE_DIR)
# Include from legacy app/library path

View File

@ -41,93 +41,6 @@ CONFIGURED_APPS += examples/nsh
CONFIGURED_APPS += nshlib
CONFIGURED_APPS += system/readline
# System library - utility functions
CONFIGURED_APPS += systemlib
CONFIGURED_APPS += systemlib/mixer
# Math library
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += mathlib
CONFIGURED_APPS += mathlib/CMSIS
CONFIGURED_APPS += examples/math_demo
endif
# Control library
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += controllib
CONFIGURED_APPS += examples/control_demo
CONFIGURED_APPS += examples/kalman_demo
endif
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
CONFIGURED_APPS += systemcmds/perf
CONFIGURED_APPS += systemcmds/top
CONFIGURED_APPS += systemcmds/boardinfo
CONFIGURED_APPS += systemcmds/mixer
CONFIGURED_APPS += systemcmds/param
CONFIGURED_APPS += systemcmds/pwm
CONFIGURED_APPS += systemcmds/bl_update
CONFIGURED_APPS += systemcmds/preflight_check
CONFIGURED_APPS += systemcmds/delay_test
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/hello_sky
# CONFIGURED_APPS += examples/px4_simple_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/deamon
# CONFIGURED_APPS += examples/px4_deamon_app
# Tutorial code from
# https://pixhawk.ethz.ch/px4/dev/debug_values
# CONFIGURED_APPS += examples/px4_mavlink_debug
# Shared object broker; required by many parts of the system.
CONFIGURED_APPS += uORB
CONFIGURED_APPS += mavlink
CONFIGURED_APPS += mavlink_onboard
CONFIGURED_APPS += commander
CONFIGURED_APPS += sdlog
CONFIGURED_APPS += sensors
ifneq ($(CONFIG_APM),y)
CONFIGURED_APPS += ardrone_interface
CONFIGURED_APPS += multirotor_att_control
CONFIGURED_APPS += multirotor_pos_control
CONFIGURED_APPS += position_estimator_mc
CONFIGURED_APPS += fixedwing_att_control
CONFIGURED_APPS += fixedwing_pos_control
CONFIGURED_APPS += position_estimator
CONFIGURED_APPS += attitude_estimator_ekf
CONFIGURED_APPS += hott_telemetry
endif
# Hacking tools
#CONFIGURED_APPS += system/i2c
CONFIGURED_APPS += systemcmds/i2c
# Communication and Drivers
#CONFIGURED_APPS += drivers/boards/px4fmu
CONFIGURED_APPS += drivers/device
CONFIGURED_APPS += drivers/ms5611
CONFIGURED_APPS += drivers/hmc5883
CONFIGURED_APPS += drivers/mpu6000
CONFIGURED_APPS += drivers/bma180
CONFIGURED_APPS += drivers/px4io
CONFIGURED_APPS += drivers/stm32
#CONFIGURED_APPS += drivers/led
CONFIGURED_APPS += drivers/blinkm
CONFIGURED_APPS += drivers/stm32/tone_alarm
CONFIGURED_APPS += drivers/stm32/adc
CONFIGURED_APPS += drivers/hil
CONFIGURED_APPS += drivers/gps
CONFIGURED_APPS += drivers/mb12xx
# Testing stuff
CONFIGURED_APPS += px4/sensors_bringup
ifeq ($(CONFIG_CAN),y)
#CONFIGURED_APPS += examples/can
endif

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -35,4 +35,8 @@
# Build the device driver framework.
#
include $(APPDIR)/mk/app.mk
SRCS = cdev.cpp \
device.cpp \
i2c.cpp \
pio.cpp \
spi.cpp

View File

@ -43,7 +43,7 @@
#include <stdint.h>
/* XXX for ORB_DECLARE used in many drivers */
#include "../uORB/uORB.h"
#include "../modules/uORB/uORB.h"
/*
* ioctl() definitions

View File

@ -1,7 +1,7 @@
/****************************************************************************
*
* Copyright (C) 2012 PX4 Development Team. All rights reserved.
* Author: @author Example User <mail@example.com>
* Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
* Author: James Goppert
*
* Redistribution and use in source and binary forms, with or without
* modification, are permitted provided that the following conditions
@ -34,6 +34,7 @@
/**
* @file math_demo.cpp
* @author James Goppert
* Demonstration of math library
*/

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -32,11 +32,10 @@
############################################################################
#
# Makefile to build uORB
# Mathlib / operations demo application
#
APPNAME = uorb
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 4096
MODULE_COMMAND = math_demo
MODULE_STACKSIZE = 12000
include $(APPDIR)/mk/app.mk
SRCS = math_demo.cpp

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -32,8 +32,9 @@
############################################################################
#
# mixer library
# Daemon application
#
LIBNAME = mixerlib
include $(APPDIR)/mk/app.mk
MODULE_COMMAND = px4_daemon_app
SRCS = px4_daemon_app.c

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -35,8 +35,6 @@
# Basic example application
#
APPNAME = math_demo
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 8192
MODULE_COMMAND = px4_mavlink_debug
include $(APPDIR)/mk/app.mk
SRCS = px4_mavlink_debug.c

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -35,8 +35,6 @@
# Basic example application
#
APPNAME = px4_deamon_app
PRIORITY = SCHED_PRIORITY_DEFAULT
STACKSIZE = 2048
MODULE_COMMAND = px4_simple_app
include $(APPDIR)/mk/app.mk
SRCS = px4_simple_app.c

View File

@ -1,6 +1,6 @@
############################################################################
#
# Copyright (C) 2012 PX4 Development Team. All rights reserved.
# 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
@ -34,13 +34,10 @@
#
# Control library
#
CSRCS = test_params.c
CXXSRCS = block/Block.cpp \
SRCS = test_params.c \
block/Block.cpp \
block/BlockParam.cpp \
block/UOrbPublication.cpp \
block/UOrbSubscription.cpp \
blocks.cpp \
fixedwing.cpp
include $(APPDIR)/mk/app.mk

Some files were not shown because too many files have changed in this diff Show More