aboutsummaryrefslogtreecommitdiff
path: root/apps/mathlib
diff options
context:
space:
mode:
authorpx4dev <px4@purgatory.org>2013-01-06 15:04:30 -0800
committerpx4dev <px4@purgatory.org>2013-01-06 15:04:30 -0800
commitfaced6bfe3826a4fdcfcd72171edbb501226814a (patch)
tree42714ce675153555255e30894408ece40f4d26c9 /apps/mathlib
parent950d104c8d7e335b88c0a7944628c14293a0f676 (diff)
downloadpx4-firmware-faced6bfe3826a4fdcfcd72171edbb501226814a.tar.gz
px4-firmware-faced6bfe3826a4fdcfcd72171edbb501226814a.tar.bz2
px4-firmware-faced6bfe3826a4fdcfcd72171edbb501226814a.zip
Merge James's controllib bits into a separate library module.
Add a top-level mathlib header to avoid having to dig around for specific headers.
Diffstat (limited to 'apps/mathlib')
-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
8 files changed, 62 insertions, 10 deletions
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