aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
-rw-r--r--apps/controllib/Makefile51
-rw-r--r--apps/controllib/block/Block.cpp (renamed from apps/systemlib/control/block/Block.cpp)0
-rw-r--r--apps/controllib/block/Block.hpp (renamed from apps/systemlib/control/block/Block.hpp)0
-rw-r--r--apps/controllib/block/BlockParam.cpp (renamed from apps/systemlib/control/block/BlockParam.cpp)0
-rw-r--r--apps/controllib/block/BlockParam.hpp (renamed from apps/systemlib/control/block/BlockParam.hpp)0
-rw-r--r--apps/controllib/block/List.hpp (renamed from apps/systemlib/control/block/List.hpp)0
-rw-r--r--apps/controllib/block/UOrbPublication.cpp (renamed from apps/systemlib/control/block/UOrbPublication.cpp)0
-rw-r--r--apps/controllib/block/UOrbPublication.hpp (renamed from apps/systemlib/control/block/UOrbPublication.hpp)0
-rw-r--r--apps/controllib/block/UOrbSubscription.cpp (renamed from apps/systemlib/control/block/UOrbSubscription.cpp)0
-rw-r--r--apps/controllib/block/UOrbSubscription.hpp (renamed from apps/systemlib/control/block/UOrbSubscription.hpp)0
-rw-r--r--apps/controllib/blocks.cpp (renamed from apps/systemlib/control/blocks.cpp)0
-rw-r--r--apps/controllib/blocks.hpp (renamed from apps/systemlib/control/blocks.hpp)2
-rw-r--r--apps/controllib/fixedwing.cpp (renamed from apps/systemlib/control/fixedwing.cpp)0
-rw-r--r--apps/controllib/fixedwing.hpp (renamed from apps/systemlib/control/fixedwing.hpp)0
-rw-r--r--apps/controllib/test_params.c (renamed from apps/systemlib/control/test_params.c)0
-rw-r--r--apps/examples/control_demo/control_demo.cpp2
-rw-r--r--apps/examples/math_demo/math_demo.cpp7
-rw-r--r--apps/mathlib/Makefile5
-rw-r--r--apps/mathlib/math/Dcm.cpp2
-rw-r--r--apps/mathlib/math/EulerAngles.cpp2
-rw-r--r--apps/mathlib/math/Matrix.cpp2
-rw-r--r--apps/mathlib/math/Quaternion.cpp2
-rw-r--r--apps/mathlib/math/Vector.cpp2
-rw-r--r--apps/mathlib/math/Vector3.cpp2
-rw-r--r--apps/mathlib/mathlib.h55
-rw-r--r--nuttx/configs/px4fmu/nsh/appconfig8
26 files changed, 121 insertions, 21 deletions
diff --git a/apps/controllib/Makefile b/apps/controllib/Makefile
new file mode 100644
index 000000000..07a7ce81d
--- /dev/null
+++ b/apps/controllib/Makefile
@@ -0,0 +1,51 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Control library
+#
+CXXSRCS += block/Block.cpp \
+ block/BlockParam.cpp \
+ block/UOrbPublication.cpp \
+ block/UOrbSubscription.cpp \
+ blocks.cpp \
+ fixedwing.cpp
+
+CXXHDRS += block/Block.hpp \
+ block/BlockParam.hpp \
+ block/UOrbPublication.hpp \
+ block/UOrbSubscription.hpp \
+ blocks.hpp \
+ fixedwing.hpp
+
+include $(APPDIR)/mk/app.mk
diff --git a/apps/systemlib/control/block/Block.cpp b/apps/controllib/block/Block.cpp
index 5994d2315..5994d2315 100644
--- a/apps/systemlib/control/block/Block.cpp
+++ b/apps/controllib/block/Block.cpp
diff --git a/apps/systemlib/control/block/Block.hpp b/apps/controllib/block/Block.hpp
index 258701f27..258701f27 100644
--- a/apps/systemlib/control/block/Block.hpp
+++ b/apps/controllib/block/Block.hpp
diff --git a/apps/systemlib/control/block/BlockParam.cpp b/apps/controllib/block/BlockParam.cpp
index b3f49f7db..b3f49f7db 100644
--- a/apps/systemlib/control/block/BlockParam.cpp
+++ b/apps/controllib/block/BlockParam.cpp
diff --git a/apps/systemlib/control/block/BlockParam.hpp b/apps/controllib/block/BlockParam.hpp
index 7f86d1717..7f86d1717 100644
--- a/apps/systemlib/control/block/BlockParam.hpp
+++ b/apps/controllib/block/BlockParam.hpp
diff --git a/apps/systemlib/control/block/List.hpp b/apps/controllib/block/List.hpp
index 96b0b94d1..96b0b94d1 100644
--- a/apps/systemlib/control/block/List.hpp
+++ b/apps/controllib/block/List.hpp
diff --git a/apps/systemlib/control/block/UOrbPublication.cpp b/apps/controllib/block/UOrbPublication.cpp
index f69b39d90..f69b39d90 100644
--- a/apps/systemlib/control/block/UOrbPublication.cpp
+++ b/apps/controllib/block/UOrbPublication.cpp
diff --git a/apps/systemlib/control/block/UOrbPublication.hpp b/apps/controllib/block/UOrbPublication.hpp
index a36f4429f..a36f4429f 100644
--- a/apps/systemlib/control/block/UOrbPublication.hpp
+++ b/apps/controllib/block/UOrbPublication.hpp
diff --git a/apps/systemlib/control/block/UOrbSubscription.cpp b/apps/controllib/block/UOrbSubscription.cpp
index 022cadd24..022cadd24 100644
--- a/apps/systemlib/control/block/UOrbSubscription.cpp
+++ b/apps/controllib/block/UOrbSubscription.cpp
diff --git a/apps/systemlib/control/block/UOrbSubscription.hpp b/apps/controllib/block/UOrbSubscription.hpp
index 22cc2e114..22cc2e114 100644
--- a/apps/systemlib/control/block/UOrbSubscription.hpp
+++ b/apps/controllib/block/UOrbSubscription.hpp
diff --git a/apps/systemlib/control/blocks.cpp b/apps/controllib/blocks.cpp
index c6c374300..c6c374300 100644
--- a/apps/systemlib/control/blocks.cpp
+++ b/apps/controllib/blocks.cpp
diff --git a/apps/systemlib/control/blocks.hpp b/apps/controllib/blocks.hpp
index 95f2021ce..7a785d12e 100644
--- a/apps/systemlib/control/blocks.hpp
+++ b/apps/controllib/blocks.hpp
@@ -42,7 +42,7 @@
#include <assert.h>
#include <time.h>
#include <stdlib.h>
-#include <systemlib/test/test.hpp>
+#include <mathlib/math/test/test.hpp>
#include "block/Block.hpp"
#include "block/BlockParam.hpp"
diff --git a/apps/systemlib/control/fixedwing.cpp b/apps/controllib/fixedwing.cpp
index 695653714..695653714 100644
--- a/apps/systemlib/control/fixedwing.cpp
+++ b/apps/controllib/fixedwing.cpp
diff --git a/apps/systemlib/control/fixedwing.hpp b/apps/controllib/fixedwing.hpp
index ea742641c..ea742641c 100644
--- a/apps/systemlib/control/fixedwing.hpp
+++ b/apps/controllib/fixedwing.hpp
diff --git a/apps/systemlib/control/test_params.c b/apps/controllib/test_params.c
index 7c609cad3..7c609cad3 100644
--- a/apps/systemlib/control/test_params.c
+++ b/apps/controllib/test_params.c
diff --git a/apps/examples/control_demo/control_demo.cpp b/apps/examples/control_demo/control_demo.cpp
index c60c5e8b9..d9c773c05 100644
--- a/apps/examples/control_demo/control_demo.cpp
+++ b/apps/examples/control_demo/control_demo.cpp
@@ -43,7 +43,7 @@
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
-#include <systemlib/control/fixedwing.hpp>
+#include <controllib/fixedwing.hpp>
#include <systemlib/param/param.h>
#include <drivers/drv_hrt.h>
#include <math.h>
diff --git a/apps/examples/math_demo/math_demo.cpp b/apps/examples/math_demo/math_demo.cpp
index 0dc4b3750..a9c556748 100644
--- a/apps/examples/math_demo/math_demo.cpp
+++ b/apps/examples/math_demo/math_demo.cpp
@@ -43,12 +43,7 @@
#include <stdlib.h>
#include <string.h>
#include <systemlib/systemlib.h>
-#include <mathlib/math/Vector.hpp>
-#include <mathlib/math/Matrix.hpp>
-#include <mathlib/math/Quaternion.hpp>
-#include <mathlib/math/Vector3.hpp>
-#include <mathlib/math/Dcm.hpp>
-#include <mathlib/math/EulerAngles.hpp>
+#include <mathlib/mathlib.h>
/**
* Management function.
diff --git a/apps/mathlib/Makefile b/apps/mathlib/Makefile
index 5c4861bbc..fe9b691b3 100644
--- a/apps/mathlib/Makefile
+++ b/apps/mathlib/Makefile
@@ -32,9 +32,8 @@
############################################################################
#
-# System math library
+# Math library
#
-
CXXSRCS = math/test/test.cpp \
math/Vector.cpp \
math/Vector3.cpp \
@@ -51,9 +50,7 @@ CXXHDRS = math/test/test.hpp \
math/Dcm.hpp \
math/Matrix.hpp
-#
# XXX this really should be a CONFIG_* test
-#
ifeq ($(TARGET),px4fmu)
INCLUDES += math/arm
CXXSRCS += math/arm/Vector.cpp \
diff --git a/apps/mathlib/math/Dcm.cpp b/apps/mathlib/math/Dcm.cpp
index 4c2067aff..59f3d88ab 100644
--- a/apps/mathlib/math/Dcm.cpp
+++ b/apps/mathlib/math/Dcm.cpp
@@ -37,7 +37,7 @@
* math direction cosine matrix
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include "Dcm.hpp"
#include "Quaternion.hpp"
diff --git a/apps/mathlib/math/EulerAngles.cpp b/apps/mathlib/math/EulerAngles.cpp
index b6c1a0669..8991d5623 100644
--- a/apps/mathlib/math/EulerAngles.cpp
+++ b/apps/mathlib/math/EulerAngles.cpp
@@ -37,7 +37,7 @@
* math vector
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include "EulerAngles.hpp"
#include "Quaternion.hpp"
diff --git a/apps/mathlib/math/Matrix.cpp b/apps/mathlib/math/Matrix.cpp
index ebd1aeda3..981732370 100644
--- a/apps/mathlib/math/Matrix.cpp
+++ b/apps/mathlib/math/Matrix.cpp
@@ -37,7 +37,7 @@
* matrix code
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include <math.h>
#include "Matrix.hpp"
diff --git a/apps/mathlib/math/Quaternion.cpp b/apps/mathlib/math/Quaternion.cpp
index 7c4b0593a..68fe85300 100644
--- a/apps/mathlib/math/Quaternion.cpp
+++ b/apps/mathlib/math/Quaternion.cpp
@@ -37,7 +37,7 @@
* math vector
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include "Quaternion.hpp"
diff --git a/apps/mathlib/math/Vector.cpp b/apps/mathlib/math/Vector.cpp
index 35158a396..d58e719db 100644
--- a/apps/mathlib/math/Vector.cpp
+++ b/apps/mathlib/math/Vector.cpp
@@ -37,7 +37,7 @@
* math vector
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include "Vector.hpp"
diff --git a/apps/mathlib/math/Vector3.cpp b/apps/mathlib/math/Vector3.cpp
index 61fcc442f..9c57506da 100644
--- a/apps/mathlib/math/Vector3.cpp
+++ b/apps/mathlib/math/Vector3.cpp
@@ -37,7 +37,7 @@
* math vector
*/
-#include "test/test.hpp"
+#include "math/test/test.hpp"
#include "Vector3.hpp"
diff --git a/apps/mathlib/mathlib.h b/apps/mathlib/mathlib.h
new file mode 100644
index 000000000..b919d53db
--- /dev/null
+++ b/apps/mathlib/mathlib.h
@@ -0,0 +1,55 @@
+/****************************************************************************
+ *
+ * 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.
+ *
+ ****************************************************************************/
+
+/**
+ * @file mathlib.h
+ *
+ * Common header for mathlib exports.
+ */
+
+#ifdef __cplusplus
+
+#include "math/Dcm.hpp"
+#include "math/EulerAngles.hpp"
+#include "math/Matrix.hpp"
+#include "math/Quaternion.hpp"
+#include "math/Vector.hpp"
+#include "math/Vector3.hpp"
+
+#endif
+
+#ifdef CONFIG_ARCH_ARM
+
+#include "CMSIS/Include/arm_math.h"
+
+#endif \ No newline at end of file
diff --git a/nuttx/configs/px4fmu/nsh/appconfig b/nuttx/configs/px4fmu/nsh/appconfig
index 381cf0f44..8937533b7 100644
--- a/nuttx/configs/px4fmu/nsh/appconfig
+++ b/nuttx/configs/px4fmu/nsh/appconfig
@@ -48,6 +48,11 @@ CONFIGURED_APPS += systemlib/mixer
# Math library
CONFIGURED_APPS += mathlib
CONFIGURED_APPS += mathlib/CMSIS
+CONFIGURED_APPS += examples/math_demo
+
+# Control library
+CONFIGURED_APPS += controllib
+CONFIGURED_APPS += examples/control_demo
# System utility commands
CONFIGURED_APPS += systemcmds/reboot
@@ -69,9 +74,6 @@ CONFIGURED_APPS += systemcmds/delay_test
# https://pixhawk.ethz.ch/px4/dev/deamon
# CONFIGURED_APPS += examples/px4_deamon_app
-# Math library
-CONFIGURED_APPS += examples/math_demo
-
# Shared object broker; required by many parts of the system.
CONFIGURED_APPS += uORB