aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorMark Charlebois <charlebm@gmail.com>2015-03-10 17:36:20 -0700
committerMark Charlebois <charlebm@gmail.com>2015-04-20 10:46:43 -0700
commit520459062d567fe3f1725b602be37771bebaed20 (patch)
tree6d2b805d9463489664ba3649d7bca6558b6f12a8
parent838e9fc76943eabd78064a8f18effd3dcd0fd1bf (diff)
downloadpx4-firmware-520459062d567fe3f1725b602be37771bebaed20.tar.gz
px4-firmware-520459062d567fe3f1725b602be37771bebaed20.tar.bz2
px4-firmware-520459062d567fe3f1725b602be37771bebaed20.zip
Initial Linux support including execution shell
Uncomment the following line in setup.mk and comment out the line above to enable the Linux build. export PX4_TARGET_OS = linux The build uses the clang compiler by default. The final bundled executable is mainapp located in: Build/linux_default.build/mainapp When you run mainapp it will provide a list of the built-in apps. You can type in the commands to run such as: hello_main start Because the Linux build is threaded and does not support tasks or processes, it cannot call errx, exit() _exit(), etc. It also requires unique scoped variables to test if a thread is running or if an application should exit. The px4::AppMgr class was added in px4_app.h for this purpose. The hello sample app demonstrates how this is used. Signed-off-by: Mark Charlebois <charlebm@gmail.com>
-rwxr-xr-xTools/linux_apps.py84
-rw-r--r--makefiles/linux/config_linux_default.mk35
-rw-r--r--makefiles/module.mk1
-rw-r--r--makefiles/setup.mk4
-rw-r--r--src/platforms/linux/hello/hello_example.cpp61
-rw-r--r--src/platforms/linux/hello/hello_example.h53
-rw-r--r--src/platforms/linux/hello/hello_main.cpp55
-rw-r--r--src/platforms/linux/hello/hello_start_linux.cpp100
-rw-r--r--src/platforms/linux/hello/module.mk43
-rw-r--r--src/platforms/linux/include/arch/board/board.h0
-rw-r--r--src/platforms/linux/include/board_config.h1
-rw-r--r--src/platforms/linux/main.cpp98
-rw-r--r--src/platforms/linux/px4_layer/module.mk42
-rw-r--r--src/platforms/linux/px4_layer/px4_linux_impl.cpp51
-rw-r--r--src/platforms/linux/px4_layer/px4_linux_tasks.c186
-rw-r--r--src/platforms/nuttx/px4_layer/module.mk40
-rw-r--r--src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c118
-rw-r--r--src/platforms/px4_app.h83
-rw-r--r--src/platforms/px4_includes.h34
-rw-r--r--src/platforms/px4_middleware.h6
-rw-r--r--src/platforms/px4_posix.h76
-rw-r--r--src/platforms/px4_tasks.h82
22 files changed, 1229 insertions, 24 deletions
diff --git a/Tools/linux_apps.py b/Tools/linux_apps.py
new file mode 100755
index 000000000..9a380efd0
--- /dev/null
+++ b/Tools/linux_apps.py
@@ -0,0 +1,84 @@
+#!/usr/bin/env python
+############################################################################
+#
+# Copyright (C) 2015 Mark Charlebois. 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.
+#
+############################################################################
+
+import glob
+#builtins = glob.glob("../Build/linux_default.build/builtin_commands/COMMAND*")
+builtins = glob.glob("builtin_commands/COMMAND*")
+
+apps = []
+for f in builtins:
+ apps.append(f.split(".")[-1])
+
+print
+print """
+#include <string>
+#include <map>
+using namespace std;
+
+extern "C" {
+"""
+for app in apps:
+ print "extern int "+app+"(int argc, char *argv[]);"
+
+print """
+static int list_builtins(int argc, char *argv[]);
+}
+
+
+static map<string,px4_main_t> app_map(void);
+
+static map<string,px4_main_t> app_map(void)
+{
+ map<string,px4_main_t> apps;
+"""
+for app in apps:
+ print '\tapps["'+app+'"] = '+app+';'
+
+print '\tapps["list_builtins"] = list_builtins;'
+print """
+ return apps;
+}
+
+map<string,px4_main_t> apps = app_map();
+
+static int list_builtins(int argc, char *argv[])
+{
+ cout << "Builtin Commands:" << endl;
+ for (map<string,px4_main_t>::iterator it=apps.begin(); it!=apps.end(); ++it)
+ cout << '\t' << it->first << endl;
+
+ return 0;
+}
+"""
+
diff --git a/makefiles/linux/config_linux_default.mk b/makefiles/linux/config_linux_default.mk
index 57721c0db..fc5d7639c 100644
--- a/makefiles/linux/config_linux_default.mk
+++ b/makefiles/linux/config_linux_default.mk
@@ -5,18 +5,13 @@
#
# Use the configuration's ROMFS.
#
-ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
+#ROMFS_ROOT = $(PX4_BASE)/ROMFS/px4fmu_common
#
# Board support modules
#
-#MODULES += drivers/dxl
-#MODULES += drivers/i2c_pwm
-#MODULES += drivers/lemonrx
-#MODULES += drivers/mpu9x50
-#MODULES += drivers/um7
-MODULES += drivers/device
-MODULES += modules/sensors
+#MODULES += drivers/device
+#MODULES += modules/sensors
#
# System commands
@@ -27,38 +22,38 @@ MODULES += modules/sensors
# General system control
#
#MODULES += modules/mavlink
-MODULES += modules/mavlink
+#MODULES += modules/mavlink
#
# Estimation modules (EKF/ SO3 / other filters)
#
-MODULES += modules/attitude_estimator_ekf
+#MODULES += modules/attitude_estimator_ekf
#
# Vehicle Control
#
-MODULES += modules/mc_att_control
+#MODULES += modules/mc_att_control
#
# Library modules
#
-MODULES += modules/systemlib
-MODULES += modules/systemlib/mixer
-MODULES += modules/uORB
-MODULES += modules/dataman
+#MODULES += modules/systemlib
+#MODULES += modules/systemlib/mixer
+#MODULES += modules/uORB
+#MODULES += modules/dataman
#
# Libraries
#
-MODULES += lib/mathlib
-MODULES += lib/geo
-MODULES += lib/geo_lookup
-MODULES += lib/conversion
+#MODULES += lib/mathlib
+#MODULES += lib/geo
+#MODULES += lib/geo_lookup
+#MODULES += lib/conversion
#MODULES += lib/utils
#
# Linux port
#
MODULES += platforms/linux/px4_layer
-MODULES += platforms/linux/publisher
+MODULES += platforms/linux/hello
diff --git a/makefiles/module.mk b/makefiles/module.mk
index 9c1a828cc..3c9ca3502 100644
--- a/makefiles/module.mk
+++ b/makefiles/module.mk
@@ -144,6 +144,7 @@ MODULE_ENTRYPOINT ?= $(MODULE_COMMAND)_main
MODULE_STACKSIZE ?= CONFIG_PTHREAD_STACK_DEFAULT
MODULE_PRIORITY ?= SCHED_PRIORITY_DEFAULT
MODULE_COMMANDS += $(MODULE_COMMAND).$(MODULE_PRIORITY).$(MODULE_STACKSIZE).$(MODULE_ENTRYPOINT)
+CXXFLAGS += -DPX4_MAIN=$(MODULE_COMMAND)_app_main
endif
ifneq ($(MODULE_COMMANDS),)
diff --git a/makefiles/setup.mk b/makefiles/setup.mk
index 1c6e5c3a2..fd4cbb1a7 100644
--- a/makefiles/setup.mk
+++ b/makefiles/setup.mk
@@ -33,8 +33,8 @@
# Path and tool setup
#
-export PX4_TARGET_OS = nuttx
-#export PX4_TARGET_OS = linux
+#export PX4_TARGET_OS = nuttx
+export PX4_TARGET_OS = linux
#
# Some useful paths.
diff --git a/src/platforms/linux/hello/hello_example.cpp b/src/platforms/linux/hello/hello_example.cpp
new file mode 100644
index 000000000..7881b73d6
--- /dev/null
+++ b/src/platforms/linux/hello/hello_example.cpp
@@ -0,0 +1,61 @@
+
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file hello_example.cpp
+ * Example for Linux
+ *
+ * @author Mark Charlebois <charlebm@gmail.com>
+ */
+
+#include "hello_example.h"
+#include <unistd.h>
+#include <stdio.h>
+
+px4::AppMgr HelloExample::mgr;
+
+int HelloExample::main()
+{
+ mgr.setRunning(true);
+
+ int i=0;
+ while (!mgr.exitRequested() && i<5) {
+ sleep(2);
+
+ printf(" Doing work...\n");
+ ++i;
+ }
+
+ return 0;
+}
diff --git a/src/platforms/linux/hello/hello_example.h b/src/platforms/linux/hello/hello_example.h
new file mode 100644
index 000000000..b736f60bc
--- /dev/null
+++ b/src/platforms/linux/hello/hello_example.h
@@ -0,0 +1,53 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file hello_example.h
+ * Example app for Linux
+ *
+ * @author Mark Charlebois <charlebm@gmail.com>
+ */
+#pragma once
+
+#include <px4_app.h>
+
+class HelloExample {
+public:
+ HelloExample() {};
+
+ ~HelloExample() {};
+
+ int main();
+
+ static px4::AppMgr mgr; /* Manage requests to terminate app */
+};
diff --git a/src/platforms/linux/hello/hello_main.cpp b/src/platforms/linux/hello/hello_main.cpp
new file mode 100644
index 000000000..69e8c21ec
--- /dev/null
+++ b/src/platforms/linux/hello/hello_main.cpp
@@ -0,0 +1,55 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file hello_main.cpp
+ * Example for Linux
+ *
+ * @author Mark Charlebois <charlebm@gmail.com>
+ */
+#include <px4_middleware.h>
+#include <px4_app.h>
+#include "hello_example.h"
+#include <stdio.h>
+
+int PX4_MAIN(int argc, char **argv)
+{
+ px4::init(argc, argv, "hello");
+
+ printf("hello\n");
+ HelloExample hello;
+ hello.main();
+
+ printf("goodbye\n");
+ return 0;
+}
diff --git a/src/platforms/linux/hello/hello_start_linux.cpp b/src/platforms/linux/hello/hello_start_linux.cpp
new file mode 100644
index 000000000..027566261
--- /dev/null
+++ b/src/platforms/linux/hello/hello_start_linux.cpp
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file hello_start_linux.cpp
+ *
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ * @author Mark Charlebois <mcharleb@gmail.com>
+ */
+#include "hello_example.h"
+#include <px4_app.h>
+#include <px4_tasks.h>
+#include <stdio.h>
+#include <string.h>
+#include <sched.h>
+
+#define SCHED_DEFAULT SCHED_FIFO
+#define SCHED_PRIORITY_MAX sched_get_priority_max(SCHED_FIFO)
+#define SCHED_PRIORITY_DEFAULT sched_get_priority_max(SCHED_FIFO)
+
+static int daemon_task; /* Handle of deamon task / thread */
+
+//using namespace px4;
+
+extern "C" __EXPORT int hello_main(int argc, char *argv[]);
+int hello_main(int argc, char *argv[])
+{
+
+ if (argc < 2) {
+ printf("usage: hello {start|stop|status}\n");
+ return 1;
+ }
+
+ if (!strcmp(argv[1], "start")) {
+
+ if (HelloExample::mgr.isRunning()) {
+ printf("already running\n");
+ /* this is not an error */
+ return 0;
+ }
+
+ daemon_task = px4_task_spawn_cmd("hello",
+ SCHED_DEFAULT,
+ SCHED_PRIORITY_MAX - 5,
+ 2000,
+ PX4_MAIN,
+ (argv) ? (char* const*)&argv[2] : (char* const*)NULL);
+
+ return 0;
+ }
+
+ if (!strcmp(argv[1], "stop")) {
+ HelloExample::mgr.requestExit();
+ return 0;
+ }
+
+ if (!strcmp(argv[1], "status")) {
+ if (HelloExample::mgr.isRunning()) {
+ printf("is running\n");
+
+ } else {
+ printf("not started\n");
+ }
+
+ return 0;
+ }
+
+ printf("usage: hello {start|stop|status}\n");
+ return 1;
+}
diff --git a/src/platforms/linux/hello/module.mk b/src/platforms/linux/hello/module.mk
new file mode 100644
index 000000000..730f9189e
--- /dev/null
+++ b/src/platforms/linux/hello/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# Publisher Example Application
+#
+
+MODULE_COMMAND = hello
+
+SRCS = hello_main.cpp \
+ hello_start_linux.cpp \
+ hello_example.cpp
+
diff --git a/src/platforms/linux/include/arch/board/board.h b/src/platforms/linux/include/arch/board/board.h
new file mode 100644
index 000000000..e69de29bb
--- /dev/null
+++ b/src/platforms/linux/include/arch/board/board.h
diff --git a/src/platforms/linux/include/board_config.h b/src/platforms/linux/include/board_config.h
new file mode 100644
index 000000000..7bd465647
--- /dev/null
+++ b/src/platforms/linux/include/board_config.h
@@ -0,0 +1 @@
+#define UDID_START 0x1FFF7A10
diff --git a/src/platforms/linux/main.cpp b/src/platforms/linux/main.cpp
new file mode 100644
index 000000000..a0b210415
--- /dev/null
+++ b/src/platforms/linux/main.cpp
@@ -0,0 +1,98 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+/**
+ * @file main.cpp
+ * Basic shell to execute builtin "apps"
+ *
+ * @author Mark Charlebois <charlebm@gmail.com>
+ */
+
+#include <iostream>
+#include <fstream>
+#include <string>
+#include <sstream>
+
+using namespace std;
+
+typedef int (*px4_main_t)(int argc, char *argv[]);
+
+#include "apps.h"
+
+// FIXME - the code below only passes 1 arg for now
+void run_cmd(const string &command, const string &apparg);
+void run_cmd(const string &command, const string &apparg) {
+ const char *arg[3];
+
+ if (apps.find(command) != apps.end()) {
+ arg[0] = (char *)command.c_str();
+ arg[1] = (char *)apparg.c_str();
+ arg[2] = (char *)0;
+ apps[command](2,(char **)arg);
+ }
+ else
+ {
+ cout << "Invalid command" << endl;
+ }
+}
+
+int main(int argc, char **argv)
+{
+ string mystr;
+ string command;
+ string apparg;
+
+ // Execute a command list of provided
+ if (argc == 2) {
+ ifstream infile(argv[1]);
+
+ //vector<string> tokens;
+
+ for (string line; getline(infile, line, '\n'); ) {
+ stringstream(line) >> command >> apparg;
+ cout << "Command " << command << ", apparg " << apparg << endl;
+ run_cmd(command, apparg);
+ }
+ }
+
+ while(1) {
+ run_cmd("list_builtins", "");
+
+ cout << "Enter a command and its args:" << endl;
+ getline (cin,mystr);
+ stringstream(mystr) >> command >> apparg;
+ run_cmd(command, apparg);
+ mystr = "";
+ command = "";
+ apparg = "";
+ }
+}
diff --git a/src/platforms/linux/px4_layer/module.mk b/src/platforms/linux/px4_layer/module.mk
new file mode 100644
index 000000000..da247b8dd
--- /dev/null
+++ b/src/platforms/linux/px4_layer/module.mk
@@ -0,0 +1,42 @@
+############################################################################
+#
+# Copyright (c) 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.
+#
+############################################################################
+
+#
+# NuttX / uORB adapter library
+#
+
+SRCS = \
+ px4_linux_impl.cpp \
+ px4_linux_tasks.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/platforms/linux/px4_layer/px4_linux_impl.cpp b/src/platforms/linux/px4_layer/px4_linux_impl.cpp
new file mode 100644
index 000000000..c5ce67809
--- /dev/null
+++ b/src/platforms/linux/px4_layer/px4_linux_impl.cpp
@@ -0,0 +1,51 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4_linux_impl.cpp
+ *
+ * PX4 Middleware Wrapper Linux Implementation
+ */
+
+#include <stdint.h>
+#include <stdio.h>
+
+namespace px4
+{
+
+void init(int argc, char *argv[], const char *app_name)
+{
+ printf("App name: %s\n", app_name);
+}
+
+}
diff --git a/src/platforms/linux/px4_layer/px4_linux_tasks.c b/src/platforms/linux/px4_layer/px4_linux_tasks.c
new file mode 100644
index 000000000..a00d39b5b
--- /dev/null
+++ b/src/platforms/linux/px4_layer/px4_linux_tasks.c
@@ -0,0 +1,186 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2015 Mark Charlebois. All rights reserved.
+ * Author: @author Mark Charlebois <charlebm#gmail.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_linux_tasks.c
+ * Implementation of existing task API for Linux
+ */
+
+#include <unistd.h>
+#include <stdio.h>
+#include <stdlib.h>
+#include <errno.h>
+#include <stdbool.h>
+#include <fcntl.h>
+#include <sched.h>
+#include <signal.h>
+#include <unistd.h>
+#include <float.h>
+#include <string.h>
+
+#include <sys/stat.h>
+#include <sys/types.h>
+
+//#include <systemlib/systemlib.h>
+
+#include <px4_tasks.h>
+
+#define MAX_CMD_LEN 100
+
+#define PX4_MAX_TASKS 100
+static pthread_t taskmap[PX4_MAX_TASKS] = {};
+
+typedef struct
+{
+ px4_main_t entry;
+ int argc;
+ char *argv[];
+ // strings are allocated after the
+} pthdata_t;
+
+void entry_adapter ( void *ptr );
+void entry_adapter ( void *ptr )
+{
+ pthdata_t *data;
+ data = (pthdata_t *) ptr;
+
+ data->entry(data->argc, data->argv);
+ free(ptr);
+ pthread_exit(0);
+}
+
+void
+px4_systemreset(bool to_bootloader)
+{
+ printf("Called px4_system_reset\n");
+}
+
+px4_task_t px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, px4_main_t entry, char * const argv[])
+{
+ int rv = 0;
+ int argc = 0;
+ int i;
+ unsigned int len = 0;
+ unsigned long offset;
+ unsigned long structsize;
+ char * p = (char *)argv;
+
+ px4_task_t task;
+
+ // Calculate argc
+ while (p != (char *)0) {
+ p = argv[argc];
+ if (p == (char *)0)
+ break;
+ ++argc;
+ len += strlen(p)+1;
+ }
+ structsize = sizeof(pthdata_t)+(argc+1)*sizeof(char *);
+ pthdata_t *taskdata;
+
+ // not safe to pass stack data to the thread creation
+ taskdata = (pthdata_t *)malloc(structsize+len);
+ offset = ((unsigned long)taskdata)+structsize;
+
+ taskdata->entry = entry;
+ taskdata->argc = argc;
+
+ for (i=0; i<argc; i++) {
+ printf("arg %d %s\n", i, argv[i]);
+ taskdata->argv[i] = (char *)offset;
+ strcpy((char *)offset, argv[i]);
+ offset+=strlen(argv[i])+1;
+ }
+ // Must add NULL at end of argv
+ taskdata->argv[argc] = (char *)0;
+
+ //printf("Called px4_task_spawn_cmd\n");
+ // FIXME - add handling for scheduler and priority
+ rv = pthread_create (&task, NULL, (void *)&entry_adapter, (void *) taskdata);
+ //printf("pthread_create task=%d rv=%d\n",(int)task, rv);
+
+ for (i=0; i<PX4_MAX_TASKS; ++i) {
+ // FIXME - precludes pthread task to have an ID of 0
+ if (taskmap[i] == 0) {
+ taskmap[i] = task;
+ break;
+ }
+ }
+ if (i>=PX4_MAX_TASKS) {
+ return -ENOSPC;
+ }
+ return i;
+}
+
+int px4_task_delete(px4_task_t id)
+{
+ int rv = 0;
+ int i;
+ pthread_t pid;
+ //printf("Called px4_task_delete\n");
+
+ // Get pthread ID from the opaque ID
+ for (i=0; i<PX4_MAX_TASKS; ++i) {
+ // FIXME - precludes pthread task to have an ID of 0
+ if (taskmap[i] == id) {
+ pid = taskmap[i];
+ break;
+ }
+ }
+ if (i>=PX4_MAX_TASKS) {
+ return -EINVAL;
+ }
+ // If current thread then exit, otherwise cancel
+ if (pthread_self() == pid) {
+ pthread_exit(0);
+ } else {
+ rv = pthread_cancel(pid);
+ }
+
+ taskmap[id] = 0;
+
+ return rv;
+}
+
+void px4_killall(void)
+{
+ //printf("Called px4_killall\n");
+ for (int i=0; i<PX4_MAX_TASKS; ++i) {
+ // FIXME - precludes pthread task to have an ID of 0
+ if (taskmap[i] != 0) {
+ px4_task_delete(i);
+ }
+ }
+}
+
diff --git a/src/platforms/nuttx/px4_layer/module.mk b/src/platforms/nuttx/px4_layer/module.mk
new file mode 100644
index 000000000..1738063a5
--- /dev/null
+++ b/src/platforms/nuttx/px4_layer/module.mk
@@ -0,0 +1,40 @@
+############################################################################
+#
+# Copyright (c) 2015 Mark Charlebois. 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.
+#
+############################################################################
+
+#
+# NuttX porting layer
+#
+
+SRCS = px4_nuttx_tasks.c
+
+MAXOPTIMIZATION = -Os
diff --git a/src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c b/src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c
new file mode 100644
index 000000000..542aef5aa
--- /dev/null
+++ b/src/platforms/nuttx/px4_layer/px4_nuttx_tasks.c
@@ -0,0 +1,118 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * 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_nuttx_tasks.c
+ * Implementation of existing task API for NuttX
+ */
+
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <stdio.h>
+#include <fcntl.h>
+#include <sched.h>
+#include <signal.h>
+#include <unistd.h>
+#include <float.h>
+#include <string.h>
+
+#include <sys/stat.h>
+#include <sys/types.h>
+
+#include <stm32_pwr.h>
+
+#include <systemlib/systemlib.h>
+
+// Didn't seem right to include up_internal.h, so direct extern instead.
+extern void up_systemreset(void) noreturn_function;
+
+void
+px4_systemreset(bool to_bootloader)
+{
+ if (to_bootloader) {
+ stm32_pwr_enablebkp();
+
+ /* XXX wow, this is evil - write a magic number into backup register zero */
+ *(uint32_t *)0x40002850 = 0xb007b007;
+ }
+ up_systemreset();
+
+ /* lock up here */
+ while(true);
+}
+
+static void kill_task(FAR struct tcb_s *tcb, FAR void *arg);
+
+void px4_killall()
+{
+// printf("Sending SIGUSR1 to all processes now\n");
+
+ /* iterate through all tasks and send kill signal */
+ sched_foreach(kill_task, NULL);
+}
+
+static void kill_task(FAR struct tcb_s *tcb, FAR void *arg)
+{
+ kill(tcb->pid, SIGUSR1);
+}
+
+int px4_task_spawn_cmd(const char *name, int scheduler, int priority, int stack_size, main_t entry, char * const argv[])
+{
+ int pid;
+
+ sched_lock();
+
+ /* create the task */
+ pid = task_create(name, priority, stack_size, entry, argv);
+
+ if (pid > 0) {
+
+ /* configure the scheduler */
+ struct sched_param param;
+
+ param.sched_priority = priority;
+ sched_setscheduler(pid, scheduler, &param);
+
+ /* XXX do any other private task accounting here before the task starts */
+ }
+
+ sched_unlock();
+
+ return pid;
+}
+
+int px4_task_delete(int pid)
+{
+ return task_delete(pid);
+}
diff --git a/src/platforms/px4_app.h b/src/platforms/px4_app.h
new file mode 100644
index 000000000..1314397b5
--- /dev/null
+++ b/src/platforms/px4_app.h
@@ -0,0 +1,83 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+#pragma once
+
+namespace px4 {
+
+class AppMgr {
+public:
+ ~AppMgr() {}
+
+#if defined(__PX4_ROS)
+ AppMgr() {}
+
+ bool exitRequested() { return !ros::ok(); }
+ void requestExit() { ros::shutdown(); }
+#else
+ AppMgr() : _exitRequested(false), _isRunning(false) {}
+
+ bool exitRequested() { return _exitRequested; }
+ void requestExit() { _exitRequested = true; }
+
+ bool isRunning() { return _isRunning; }
+ void setRunning(bool running) { _isRunning = running; }
+
+protected:
+ bool _exitRequested;
+ bool _isRunning;
+#endif
+private:
+ AppMgr(const AppMgr&);
+ const AppMgr& operator=(const AppMgr&);
+};
+}
+
+// Task/process based build
+#if defined(__PX4_ROS) || defined(__PX4_NUTTX)
+
+#define PX4_MAIN main
+
+// Thread based build
+#else
+
+// The name passed must be globally unique
+// set PX4_APPMAIN in module.mk
+// EXTRADEFINES += -DPX4_MAIN=foo_app
+#ifdef PX4_MAIN
+
+extern int PX4_MAIN(int argc, char *argv[]);
+#endif
+
+#endif
+
diff --git a/src/platforms/px4_includes.h b/src/platforms/px4_includes.h
index 0e98783fd..8af93b2b2 100644
--- a/src/platforms/px4_includes.h
+++ b/src/platforms/px4_includes.h
@@ -70,7 +70,7 @@
#include <px4_vehicle_force_setpoint.h>
#endif
-#else
+#elif defined(__PX4_NUTTX)
/*
* Building for NuttX
*/
@@ -102,4 +102,36 @@
#include <systemlib/param/param.h>
#include <systemlib/systemlib.h>
+#elif defined(__PX4_LINUX)
+#include <string.h>
+#include <assert.h>
+#include <uORB/uORB.h>
+
+#define ASSERT(x) assert(x)
+
+#ifdef __cplusplus
+#include <platforms/linux/px4_messages/px4_rc_channels.h>
+#include <platforms/linux/px4_messages/px4_vehicle_attitude_setpoint.h>
+#include <platforms/linux/px4_messages/px4_manual_control_setpoint.h>
+#include <platforms/linux/px4_messages/px4_actuator_controls.h>
+#include <platforms/linux/px4_messages/px4_actuator_controls_0.h>
+#include <platforms/linux/px4_messages/px4_actuator_controls_1.h>
+#include <platforms/linux/px4_messages/px4_actuator_controls_2.h>
+#include <platforms/linux/px4_messages/px4_actuator_controls_3.h>
+#include <platforms/linux/px4_messages/px4_vehicle_rates_setpoint.h>
+#include <platforms/linux/px4_messages/px4_vehicle_attitude.h>
+#include <platforms/linux/px4_messages/px4_vehicle_control_mode.h>
+#include <platforms/linux/px4_messages/px4_actuator_armed.h>
+#include <platforms/linux/px4_messages/px4_parameter_update.h>
+#include <platforms/linux/px4_messages/px4_vehicle_status.h>
+#include <platforms/linux/px4_messages/px4_vehicle_local_position_setpoint.h>
+#include <platforms/linux/px4_messages/px4_vehicle_global_velocity_setpoint.h>
+#include <platforms/linux/px4_messages/px4_vehicle_local_position.h>
+#include <platforms/linux/px4_messages/px4_position_setpoint_triplet.h>
+#endif
+#include <systemlib/err.h>
+#include <systemlib/param/param.h>
+#include <systemlib/systemlib.h>
+#else
+#define "No target platform defined"
#endif
diff --git a/src/platforms/px4_middleware.h b/src/platforms/px4_middleware.h
index 735d34234..d86ddd664 100644
--- a/src/platforms/px4_middleware.h
+++ b/src/platforms/px4_middleware.h
@@ -54,12 +54,16 @@ __EXPORT uint64_t get_time_micros();
* Returns true if the app/task should continue to run
*/
inline bool ok() { return ros::ok(); }
-#else
+#elif defined(__PX4_NUTTX)
extern bool task_should_exit;
/**
* Returns true if the app/task should continue to run
*/
__EXPORT inline bool ok() { return !task_should_exit; }
+#else
+/**
+ * Linux needs to have globally unique checks for thread/task status
+ */
#endif
class Rate
diff --git a/src/platforms/px4_posix.h b/src/platforms/px4_posix.h
new file mode 100644
index 000000000..d08c8d238
--- /dev/null
+++ b/src/platforms/px4_posix.h
@@ -0,0 +1,76 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2015 Mark Charlebois. 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file px4_posix.h
+ *
+ * Includes POSIX-like functions for virtual character devices
+ */
+
+#pragma once
+
+#include <stdint.h>
+#include <poll.h>
+#include <semaphore.h>
+
+
+#define PX4_F_RDONLY 1
+#define PX4_F_WRONLY 2
+
+__BEGIN_DECLS
+
+extern int px4_errno;
+
+#ifndef __PX4_NUTTX
+typedef short pollevent_t;
+#endif
+
+typedef struct {
+ /* This part of the struct is POSIX-like */
+ int fd; /* The descriptor being polled */
+ pollevent_t events; /* The input event flags */
+ pollevent_t revents; /* The output event flags */
+
+ /* Required for PX4 compatability */
+ sem_t *sem; /* Pointer to semaphore used to post output event */
+ void *priv; /* For use by drivers */
+} px4_pollfd_struct_t;
+
+__EXPORT int px4_open(const char *path, int flags);
+__EXPORT int px4_close(int fd);
+__EXPORT ssize_t px4_read(int fd, void *buffer, size_t buflen);
+__EXPORT ssize_t px4_write(int fd, const void *buffer, size_t buflen);
+__EXPORT int px4_ioctl(int fd, int cmd, unsigned long arg);
+__EXPORT int px4_poll(px4_pollfd_struct_t *fds, nfds_t nfds, int timeout);
+
+__END_DECLS
diff --git a/src/platforms/px4_tasks.h b/src/platforms/px4_tasks.h
new file mode 100644
index 000000000..ac75126c4
--- /dev/null
+++ b/src/platforms/px4_tasks.h
@@ -0,0 +1,82 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Lorenz Meier <lm@inf.ethz.ch>
+ * Author: Mark Charlebois <charlebm@gmail.com> 2015
+ *
+ * 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_tasks.h
+ * Preserve existing task API call signature with OS abstraction
+ */
+
+#pragma once
+
+#include <stdbool.h>
+
+#ifdef __PX4_ROS
+#error "PX4 tasks not supported in ROS"
+#elif defined(__PX4_NUTTX)
+typedef int px4_task_t;
+#elif defined(__PX4_LINUX)
+#include <pthread.h>
+typedef pthread_t px4_task_t;
+
+typedef struct {
+ int argc;
+ char **argv;
+} px4_task_args_t;
+#else
+#error "No target OS defined"
+#endif
+
+typedef int (*px4_main_t)(int argc, char *argv[]);
+
+__BEGIN_DECLS
+
+/** Reboots the board */
+__EXPORT void px4_systemreset(bool to_bootloader) noreturn_function;
+
+/** Sends SIGUSR1 to all processes */
+__EXPORT void px4_killall(void);
+
+/** Starts a task and performs any specific accounting, scheduler setup, etc. */
+__EXPORT px4_task_t px4_task_spawn_cmd(const char *name,
+ int priority,
+ int scheduler,
+ int stack_size,
+ px4_main_t entry,
+ char * const argv[]);
+
+__EXPORT int px4_task_delete(px4_task_t pid);
+
+__END_DECLS
+