aboutsummaryrefslogtreecommitdiff
path: root/apps
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-04-28 10:37:07 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-04-28 10:37:07 +0200
commit25612cebc2c4ecfc131e545c926f6ff581e11030 (patch)
treee364911002eea58f0d8706e1747c97b57175fba4 /apps
parent13fc6703862862f4263d8d5d085b7a16b87190e1 (diff)
downloadpx4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.tar.gz
px4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.tar.bz2
px4-firmware-25612cebc2c4ecfc131e545c926f6ff581e11030.zip
Cleaned up NuttX appconfig, added examples to config
Diffstat (limited to 'apps')
-rw-r--r--apps/examples/px4_deamon_app/Makefile42
-rw-r--r--apps/examples/px4_deamon_app/px4_deamon_app.c137
-rw-r--r--apps/examples/px4_mavlink_debug/Makefile42
-rw-r--r--apps/examples/px4_mavlink_debug/px4_mavlink_debug.c74
-rw-r--r--apps/examples/px4_simple_app/Makefile42
-rw-r--r--apps/examples/px4_simple_app/px4_simple_app.c115
-rw-r--r--apps/mk/app.mk237
7 files changed, 0 insertions, 689 deletions
diff --git a/apps/examples/px4_deamon_app/Makefile b/apps/examples/px4_deamon_app/Makefile
deleted file mode 100644
index e4c169872..000000000
--- a/apps/examples/px4_deamon_app/Makefile
+++ /dev/null
@@ -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_deamon_app
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/examples/px4_deamon_app/px4_deamon_app.c b/apps/examples/px4_deamon_app/px4_deamon_app.c
deleted file mode 100644
index a5d847777..000000000
--- a/apps/examples/px4_deamon_app/px4_deamon_app.c
+++ /dev/null
@@ -1,137 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
- *
- * 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.
- *
- ****************************************************************************/
-
-/**
- * @file px4_deamon_app.c
- * Deamon application example for PX4 autopilot
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdio.h>
-
-static bool thread_should_exit = false; /**< Deamon exit flag */
-static bool thread_running = false; /**< Deamon status flag */
-static int deamon_task; /**< Handle of deamon task / thread */
-
-/**
- * Deamon management function.
- */
-__EXPORT int px4_deamon_app_main(int argc, char *argv[]);
-
-/**
- * Mainloop of deamon.
- */
-int px4_deamon_thread_main(int argc, char *argv[]);
-
-/**
- * Print the correct usage.
- */
-static void usage(const char *reason);
-
-static void
-usage(const char *reason)
-{
- if (reason)
- fprintf(stderr, "%s\n", reason);
- fprintf(stderr, "usage: deamon {start|stop|status} [-p <additional params>]\n\n");
- exit(1);
-}
-
-/**
- * The deamon app only briefly exists to start
- * the background job. The stack size assigned in the
- * Makefile does only apply to this management task.
- *
- * The actual stack size should be set in the call
- * to task_create().
- */
-int px4_deamon_app_main(int argc, char *argv[])
-{
- if (argc < 1)
- usage("missing command");
-
- if (!strcmp(argv[1], "start")) {
-
- if (thread_running) {
- printf("deamon already running\n");
- /* this is not an error */
- exit(0);
- }
-
- thread_should_exit = false;
- deamon_task = task_spawn("deamon",
- SCHED_DEFAULT,
- SCHED_PRIORITY_DEFAULT,
- 4096,
- px4_deamon_thread_main,
- (argv) ? (const char **)&argv[2] : (const char **)NULL);
- exit(0);
- }
-
- if (!strcmp(argv[1], "stop")) {
- thread_should_exit = true;
- exit(0);
- }
-
- if (!strcmp(argv[1], "status")) {
- if (thread_running) {
- printf("\tdeamon app is running\n");
- } else {
- printf("\tdeamon app not started\n");
- }
- exit(0);
- }
-
- usage("unrecognized command");
- exit(1);
-}
-
-int px4_deamon_thread_main(int argc, char *argv[]) {
-
- printf("[deamon] starting\n");
-
- thread_running = true;
-
- while (!thread_should_exit) {
- printf("Hello Deamon!\n");
- sleep(10);
- }
-
- printf("[deamon] exiting.\n");
-
- thread_running = false;
-
- return 0;
-}
diff --git a/apps/examples/px4_mavlink_debug/Makefile b/apps/examples/px4_mavlink_debug/Makefile
deleted file mode 100644
index f59aef16f..000000000
--- a/apps/examples/px4_mavlink_debug/Makefile
+++ /dev/null
@@ -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
diff --git a/apps/examples/px4_mavlink_debug/px4_mavlink_debug.c b/apps/examples/px4_mavlink_debug/px4_mavlink_debug.c
deleted file mode 100644
index aa1eb5ed8..000000000
--- a/apps/examples/px4_mavlink_debug/px4_mavlink_debug.c
+++ /dev/null
@@ -1,74 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
- *
- * 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.
- *
- ****************************************************************************/
-
-/**
- * @file px4_mavlink_debug.c
- * Debug application example for PX4 autopilot
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdio.h>
-#include <poll.h>
-
-#include <systemlib/err.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/debug_key_value.h>
-
-__EXPORT int px4_mavlink_debug_main(int argc, char *argv[]);
-
-int px4_mavlink_debug_main(int argc, char *argv[])
-{
- printf("Hello Debug!\n");
-
- /* advertise debug value */
- struct debug_key_value_s dbg = { .key = "velx", .value = 0.0f };
- orb_advert_t pub_dbg = orb_advertise(ORB_ID(debug_key_value), &dbg);
-
- int value_counter = 0;
-
- while (value_counter < 100) {
- /* send one value */
- dbg.value = value_counter;
- orb_publish(ORB_ID(debug_key_value), pub_dbg, &dbg);
-
- warnx("sent one more value..");
-
- value_counter++;
- usleep(500000);
- }
-
- return 0;
-}
diff --git a/apps/examples/px4_simple_app/Makefile b/apps/examples/px4_simple_app/Makefile
deleted file mode 100644
index 102f51fd4..000000000
--- a/apps/examples/px4_simple_app/Makefile
+++ /dev/null
@@ -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_simple_app
-PRIORITY = SCHED_PRIORITY_DEFAULT
-STACKSIZE = 2048
-
-include $(APPDIR)/mk/app.mk
diff --git a/apps/examples/px4_simple_app/px4_simple_app.c b/apps/examples/px4_simple_app/px4_simple_app.c
deleted file mode 100644
index 7f655964d..000000000
--- a/apps/examples/px4_simple_app/px4_simple_app.c
+++ /dev/null
@@ -1,115 +0,0 @@
-/****************************************************************************
- *
- * Copyright (C) 2012 PX4 Development Team. All rights reserved.
- * Author: @author Example User <mail@example.com>
- *
- * 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.
- *
- ****************************************************************************/
-
-/**
- * @file px4_simple_app.c
- * Minimal application example for PX4 autopilot
- */
-
-#include <nuttx/config.h>
-#include <unistd.h>
-#include <stdio.h>
-#include <poll.h>
-
-#include <uORB/uORB.h>
-#include <uORB/topics/sensor_combined.h>
-#include <uORB/topics/vehicle_attitude.h>
-
-__EXPORT int px4_simple_app_main(int argc, char *argv[]);
-
-int px4_simple_app_main(int argc, char *argv[])
-{
- printf("Hello Sky!\n");
-
- /* subscribe to sensor_combined topic */
- int sensor_sub_fd = orb_subscribe(ORB_ID(sensor_combined));
- orb_set_interval(sensor_sub_fd, 1000);
-
- /* advertise attitude topic */
- struct vehicle_attitude_s att;
- memset(&att, 0, sizeof(att));
- orb_advert_t att_pub = orb_advertise(ORB_ID(vehicle_attitude), &att);
-
- /* one could wait for multiple topics with this technique, just using one here */
- struct pollfd fds[] = {
- { .fd = sensor_sub_fd, .events = POLLIN },
- /* there could be more file descriptors here, in the form like:
- * { .fd = other_sub_fd, .events = POLLIN },
- */
- };
-
- int error_counter = 0;
-
- while (true) {
- /* wait for sensor update of 1 file descriptor for 1000 ms (1 second) */
- int poll_ret = poll(fds, 1, 1000);
-
- /* handle the poll result */
- if (poll_ret == 0) {
- /* this means none of our providers is giving us data */
- printf("[px4_simple_app] Got no data within a second\n");
- } else if (poll_ret < 0) {
- /* this is seriously bad - should be an emergency */
- if (error_counter < 10 || error_counter % 50 == 0) {
- /* use a counter to prevent flooding (and slowing us down) */
- printf("[px4_simple_app] ERROR return value from poll(): %d\n"
- , poll_ret);
- }
- error_counter++;
- } else {
-
- if (fds[0].revents & POLLIN) {
- /* obtained data for the first file descriptor */
- struct sensor_combined_s raw;
- /* copy sensors raw data into local buffer */
- orb_copy(ORB_ID(sensor_combined), sensor_sub_fd, &raw);
- printf("[px4_simple_app] Accelerometer:\t%8.4f\t%8.4f\t%8.4f\n",
- (double)raw.accelerometer_m_s2[0],
- (double)raw.accelerometer_m_s2[1],
- (double)raw.accelerometer_m_s2[2]);
-
- /* set att and publish this information for other apps */
- att.roll = raw.accelerometer_m_s2[0];
- att.pitch = raw.accelerometer_m_s2[1];
- att.yaw = raw.accelerometer_m_s2[2];
- orb_publish(ORB_ID(vehicle_attitude), att_pub, &att);
- }
- /* there could be more file descriptors here, in the form like:
- * if (fds[1..n].revents & POLLIN) {}
- */
- }
- }
-
- return 0;
-}
diff --git a/apps/mk/app.mk b/apps/mk/app.mk
deleted file mode 100644
index fa4a12cab..000000000
--- a/apps/mk/app.mk
+++ /dev/null
@@ -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)