aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorAnton Babushkin <anton.babushkin@me.com>2013-11-08 21:56:11 +0400
committerAnton Babushkin <anton.babushkin@me.com>2013-11-08 21:56:11 +0400
commite8224376ca4d32e948cbee75bfecf8a30f3e98ea (patch)
tree65290003878c65247d99ad21849a6f3cbeac2e35 /src/lib
parent28bf8e238e35a7bbba81f86e63cd0a49226673a4 (diff)
parentc63995e91c188b476aa2608b42a366f68dced423 (diff)
downloadpx4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.tar.gz
px4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.tar.bz2
px4-firmware-e8224376ca4d32e948cbee75bfecf8a30f3e98ea.zip
Merge branch 'master' into vector_control
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/conversion/module.mk38
-rw-r--r--src/lib/conversion/rotation.cpp62
-rw-r--r--src/lib/conversion/rotation.h121
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp149
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h115
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp129
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h108
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp75
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h89
-rw-r--r--src/lib/ecl/ecl.h44
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp366
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.h268
-rw-r--r--src/lib/ecl/module.mk41
-rw-r--r--src/lib/external_lgpl/module.mk48
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp534
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h357
-rw-r--r--src/lib/geo/geo.c468
-rw-r--r--src/lib/geo/geo.h129
-rw-r--r--src/lib/geo/module.mk38
-rw-r--r--src/lib/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h264
-rw-r--r--src/lib/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h265
-rw-r--r--src/lib/mathlib/CMSIS/Include/arm_common_tables.h93
-rw-r--r--src/lib/mathlib/CMSIS/Include/arm_const_structs.h85
-rw-r--r--src/lib/mathlib/CMSIS/Include/arm_math.h7318
-rw-r--r--src/lib/mathlib/CMSIS/Include/core_cm3.h1627
-rw-r--r--src/lib/mathlib/CMSIS/Include/core_cm4.h1772
-rw-r--r--src/lib/mathlib/CMSIS/Include/core_cm4_simd.h673
-rw-r--r--src/lib/mathlib/CMSIS/Include/core_cmFunc.h636
-rw-r--r--src/lib/mathlib/CMSIS/Include/core_cmInstr.h688
-rw-r--r--src/lib/mathlib/CMSIS/libarm_cortexM3l_math.abin0 -> 3039508 bytes
-rwxr-xr-xsrc/lib/mathlib/CMSIS/libarm_cortexM4l_math.abin0 -> 3049684 bytes
-rwxr-xr-xsrc/lib/mathlib/CMSIS/libarm_cortexM4lf_math.abin0 -> 2989192 bytes
-rw-r--r--src/lib/mathlib/CMSIS/library.mk46
-rw-r--r--src/lib/mathlib/CMSIS/license.txt27
-rw-r--r--src/lib/mathlib/math/Dcm.cpp179
-rw-r--r--src/lib/mathlib/math/Dcm.hpp113
-rw-r--r--src/lib/mathlib/math/EulerAngles.cpp126
-rw-r--r--src/lib/mathlib/math/EulerAngles.hpp74
-rw-r--r--src/lib/mathlib/math/Limits.cpp146
-rw-r--r--src/lib/mathlib/math/Limits.hpp87
-rw-r--r--src/lib/mathlib/math/Matrix.cpp193
-rw-r--r--src/lib/mathlib/math/Matrix.hpp61
-rw-r--r--src/lib/mathlib/math/Quaternion.cpp174
-rw-r--r--src/lib/mathlib/math/Quaternion.hpp115
-rw-r--r--src/lib/mathlib/math/Vector.cpp100
-rw-r--r--src/lib/mathlib/math/Vector.hpp57
-rw-r--r--src/lib/mathlib/math/Vector2f.cpp103
-rw-r--r--src/lib/mathlib/math/Vector2f.hpp79
-rw-r--r--src/lib/mathlib/math/Vector3.cpp109
-rw-r--r--src/lib/mathlib/math/Vector3.hpp78
-rw-r--r--src/lib/mathlib/math/arm/Matrix.cpp40
-rw-r--r--src/lib/mathlib/math/arm/Matrix.hpp292
-rw-r--r--src/lib/mathlib/math/arm/Vector.cpp40
-rw-r--r--src/lib/mathlib/math/arm/Vector.hpp236
-rw-r--r--src/lib/mathlib/math/filter/LowPassFilter2p.cpp77
-rw-r--r--src/lib/mathlib/math/filter/LowPassFilter2p.hpp78
-rw-r--r--src/lib/mathlib/math/filter/module.mk43
-rw-r--r--src/lib/mathlib/math/generic/Matrix.cpp40
-rw-r--r--src/lib/mathlib/math/generic/Matrix.hpp437
-rw-r--r--src/lib/mathlib/math/generic/Vector.cpp40
-rw-r--r--src/lib/mathlib/math/generic/Vector.hpp245
-rw-r--r--src/lib/mathlib/math/nasa_rotation_def.pdfbin0 -> 709235 bytes
-rw-r--r--src/lib/mathlib/math/test/test.cpp94
-rw-r--r--src/lib/mathlib/math/test/test.hpp50
-rw-r--r--src/lib/mathlib/math/test_math.sce63
-rw-r--r--src/lib/mathlib/mathlib.h59
-rw-r--r--src/lib/mathlib/module.mk61
67 files changed, 20362 insertions, 0 deletions
diff --git a/src/lib/conversion/module.mk b/src/lib/conversion/module.mk
new file mode 100644
index 000000000..f5f59a2dc
--- /dev/null
+++ b/src/lib/conversion/module.mk
@@ -0,0 +1,38 @@
+############################################################################
+#
+# Copyright (C) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# 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.
+#
+############################################################################
+
+#
+# Conversion library
+#
+
+SRCS = rotation.cpp
diff --git a/src/lib/conversion/rotation.cpp b/src/lib/conversion/rotation.cpp
new file mode 100644
index 000000000..b078562c2
--- /dev/null
+++ b/src/lib/conversion/rotation.cpp
@@ -0,0 +1,62 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 rotation.cpp
+ *
+ * Vector rotation library
+ */
+
+#include "math.h"
+#include "rotation.h"
+
+__EXPORT void
+get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix)
+{
+ /* first set to zero */
+ rot_matrix->Matrix::zero(3, 3);
+
+ float roll = M_DEG_TO_RAD_F * (float)rot_lookup[rot].roll;
+ float pitch = M_DEG_TO_RAD_F * (float)rot_lookup[rot].pitch;
+ float yaw = M_DEG_TO_RAD_F * (float)rot_lookup[rot].yaw;
+
+ math::EulerAngles euler(roll, pitch, yaw);
+
+ math::Dcm R(euler);
+
+ for (int i = 0; i < 3; i++) {
+ for (int j = 0; j < 3; j++) {
+ (*rot_matrix)(i, j) = R(i, j);
+ }
+ }
+}
diff --git a/src/lib/conversion/rotation.h b/src/lib/conversion/rotation.h
new file mode 100644
index 000000000..85c63c0fc
--- /dev/null
+++ b/src/lib/conversion/rotation.h
@@ -0,0 +1,121 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 rotation.h
+ *
+ * Vector rotation library
+ */
+
+#ifndef ROTATION_H_
+#define ROTATION_H_
+
+#include <unistd.h>
+#include <mathlib/mathlib.h>
+
+/**
+ * Enum for board and external compass rotations.
+ * This enum maps from board attitude to airframe attitude.
+ */
+enum Rotation {
+ ROTATION_NONE = 0,
+ ROTATION_YAW_45 = 1,
+ ROTATION_YAW_90 = 2,
+ ROTATION_YAW_135 = 3,
+ ROTATION_YAW_180 = 4,
+ ROTATION_YAW_225 = 5,
+ ROTATION_YAW_270 = 6,
+ ROTATION_YAW_315 = 7,
+ ROTATION_ROLL_180 = 8,
+ ROTATION_ROLL_180_YAW_45 = 9,
+ ROTATION_ROLL_180_YAW_90 = 10,
+ ROTATION_ROLL_180_YAW_135 = 11,
+ ROTATION_PITCH_180 = 12,
+ ROTATION_ROLL_180_YAW_225 = 13,
+ ROTATION_ROLL_180_YAW_270 = 14,
+ ROTATION_ROLL_180_YAW_315 = 15,
+ ROTATION_ROLL_90 = 16,
+ ROTATION_ROLL_90_YAW_45 = 17,
+ ROTATION_ROLL_90_YAW_90 = 18,
+ ROTATION_ROLL_90_YAW_135 = 19,
+ ROTATION_ROLL_270 = 20,
+ ROTATION_ROLL_270_YAW_45 = 21,
+ ROTATION_ROLL_270_YAW_90 = 22,
+ ROTATION_ROLL_270_YAW_135 = 23,
+ ROTATION_PITCH_90 = 24,
+ ROTATION_PITCH_270 = 25,
+ ROTATION_MAX
+};
+
+typedef struct {
+ uint16_t roll;
+ uint16_t pitch;
+ uint16_t yaw;
+} rot_lookup_t;
+
+const rot_lookup_t rot_lookup[] = {
+ { 0, 0, 0 },
+ { 0, 0, 45 },
+ { 0, 0, 90 },
+ { 0, 0, 135 },
+ { 0, 0, 180 },
+ { 0, 0, 225 },
+ { 0, 0, 270 },
+ { 0, 0, 315 },
+ {180, 0, 0 },
+ {180, 0, 45 },
+ {180, 0, 90 },
+ {180, 0, 135 },
+ { 0, 180, 0 },
+ {180, 0, 225 },
+ {180, 0, 270 },
+ {180, 0, 315 },
+ { 90, 0, 0 },
+ { 90, 0, 45 },
+ { 90, 0, 90 },
+ { 90, 0, 135 },
+ {270, 0, 0 },
+ {270, 0, 45 },
+ {270, 0, 90 },
+ {270, 0, 135 },
+ { 0, 90, 0 },
+ { 0, 270, 0 }
+};
+
+/**
+ * Get the rotation matrix
+ */
+__EXPORT void
+get_rot_matrix(enum Rotation rot, math::Matrix *rot_matrix);
+
+#endif /* ROTATION_H_ */
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
new file mode 100644
index 000000000..2eb58abd6
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -0,0 +1,149 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_pitch_controller.cpp
+ * Implementation of a simple orthogonal pitch PID controller.
+ *
+ * Authors and acknowledgements in header.
+ */
+
+#include "ecl_pitch_controller.h"
+#include <math.h>
+#include <stdint.h>
+#include <float.h>
+#include <geo/geo.h>
+#include <ecl/ecl.h>
+#include <mathlib/mathlib.h>
+
+ECL_PitchController::ECL_PitchController() :
+ _last_run(0),
+ _last_output(0.0f),
+ _integrator(0.0f),
+ _rate_error(0.0f),
+ _rate_setpoint(0.0f),
+ _max_deflection_rad(math::radians(45.0f))
+{
+}
+
+float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitch_rate, float roll, float scaler,
+ bool lock_integrator, float airspeed_min, float airspeed_max, float airspeed)
+{
+ /* get the usual dt estimate */
+ uint64_t dt_micros = ecl_elapsed_time(&_last_run);
+ _last_run = ecl_absolute_time();
+ float dt = (float)dt_micros * 1e-6f;
+
+ /* lock integral for long intervals */
+ if (dt_micros > 500000)
+ lock_integrator = true;
+
+ float k_roll_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_i_rate = _k_i * _tc;
+
+ /* input conditioning */
+ if (!isfinite(airspeed)) {
+ /* airspeed is NaN, +- INF or not available, pick center of band */
+ airspeed = 0.5f * (airspeed_min + airspeed_max);
+ } else if (airspeed < airspeed_min) {
+ airspeed = airspeed_min;
+ }
+
+ /* flying inverted (wings upside down) ? */
+ bool inverted = false;
+
+ /* roll is used as feedforward term and inverted flight needs to be considered */
+ if (fabsf(roll) < math::radians(90.0f)) {
+ /* not inverted, but numerically still potentially close to infinity */
+ roll = math::constrain(roll, math::radians(-80.0f), math::radians(80.0f));
+ } else {
+ /* inverted flight, constrain on the two extremes of -pi..+pi to avoid infinity */
+
+ /* note: the ranges are extended by 10 deg here to avoid numeric resolution effects */
+ if (roll > 0.0f) {
+ /* right hemisphere */
+ roll = math::constrain(roll, math::radians(100.0f), math::radians(180.0f));
+ } else {
+ /* left hemisphere */
+ roll = math::constrain(roll, math::radians(-100.0f), math::radians(-180.0f));
+ }
+ }
+
+ /* calculate the offset in the rate resulting from rolling */
+ float turn_offset = fabsf((CONSTANTS_ONE_G / airspeed) *
+ tanf(roll) * sinf(roll)) * _roll_ff;
+ if (inverted)
+ turn_offset = -turn_offset;
+
+ float pitch_error = pitch_setpoint - pitch;
+ /* rate setpoint from current error and time constant */
+ _rate_setpoint = pitch_error / _tc;
+
+ /* add turn offset */
+ _rate_setpoint += turn_offset;
+
+ _rate_error = _rate_setpoint - pitch_rate;
+
+ float ilimit_scaled = _integrator_max * scaler;
+
+ if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * k_i_rate * dt * scaler;
+
+ /*
+ * anti-windup: do not allow integrator to increase into the
+ * wrong direction if actuator is at limit
+ */
+ if (_last_output < -_max_deflection_rad) {
+ /* only allow motion to center: increase value */
+ id = math::max(id, 0.0f);
+ } else if (_last_output > _max_deflection_rad) {
+ /* only allow motion to center: decrease value */
+ id = math::min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
+ /* store non-limited output */
+ _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_roll_ff)) * scaler;
+
+ return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
+}
+
+void ECL_PitchController::reset_integrator()
+{
+ _integrator = 0.0f;
+}
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
new file mode 100644
index 000000000..1e6cec6a1
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -0,0 +1,115 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_pitch_controller.h
+ * Definition of a simple orthogonal pitch PID controller.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Acknowledgements:
+ *
+ * The control design is based on a design
+ * by Paul Riseborough and Andrew Tridgell, 2013,
+ * which in turn is based on initial work of
+ * Jonathan Challinger, 2012.
+ */
+
+#ifndef ECL_PITCH_CONTROLLER_H
+#define ECL_PITCH_CONTROLLER_H
+
+#include <stdbool.h>
+#include <stdint.h>
+
+class __EXPORT ECL_PitchController
+{
+public:
+ ECL_PitchController();
+
+ float control(float pitch_setpoint, float pitch, float pitch_rate, float roll, float scaler = 1.0f,
+ bool lock_integrator = false, float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f));
+
+ void reset_integrator();
+
+ void set_time_constant(float time_constant) {
+ _tc = time_constant;
+ }
+ void set_k_p(float k_p) {
+ _k_p = k_p;
+ }
+ void set_k_i(float k_i) {
+ _k_i = k_i;
+ }
+ void set_k_d(float k_d) {
+ _k_d = k_d;
+ }
+ void set_integrator_max(float max) {
+ _integrator_max = max;
+ }
+ void set_max_rate_pos(float max_rate_pos) {
+ _max_rate_pos = max_rate_pos;
+ }
+ void set_max_rate_neg(float max_rate_neg) {
+ _max_rate_neg = max_rate_neg;
+ }
+ void set_roll_ff(float roll_ff) {
+ _roll_ff = roll_ff;
+ }
+
+ float get_rate_error() {
+ return _rate_error;
+ }
+
+ float get_desired_rate() {
+ return _rate_setpoint;
+ }
+
+private:
+
+ uint64_t _last_run;
+ float _tc;
+ float _k_p;
+ float _k_i;
+ float _k_d;
+ float _integrator_max;
+ float _max_rate_pos;
+ float _max_rate_neg;
+ float _roll_ff;
+ float _last_output;
+ float _integrator;
+ float _rate_error;
+ float _rate_setpoint;
+ float _max_deflection_rad;
+};
+
+#endif // ECL_PITCH_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
new file mode 100644
index 000000000..0b1ffa7a4
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_roll_controller.cpp
+ * Implementation of a simple orthogonal roll PID controller.
+ *
+ * Authors and acknowledgements in header.
+ */
+
+#include "../ecl.h"
+#include "ecl_roll_controller.h"
+#include <stdint.h>
+#include <float.h>
+#include <geo/geo.h>
+#include <ecl/ecl.h>
+#include <mathlib/mathlib.h>
+
+ECL_RollController::ECL_RollController() :
+ _last_run(0),
+ _tc(0.1f),
+ _last_output(0.0f),
+ _integrator(0.0f),
+ _rate_error(0.0f),
+ _rate_setpoint(0.0f),
+ _max_deflection_rad(math::radians(45.0f))
+{
+
+}
+
+float ECL_RollController::control(float roll_setpoint, float roll, float roll_rate,
+ float scaler, bool lock_integrator, float airspeed_min, float airspeed_max, float airspeed)
+{
+ /* get the usual dt estimate */
+ uint64_t dt_micros = ecl_elapsed_time(&_last_run);
+ _last_run = ecl_absolute_time();
+ float dt = (float)dt_micros * 1e-6f;
+
+ /* lock integral for long intervals */
+ if (dt_micros > 500000)
+ lock_integrator = true;
+
+ float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_i_rate = _k_i * _tc;
+
+ /* input conditioning */
+ if (!isfinite(airspeed)) {
+ /* airspeed is NaN, +- INF or not available, pick center of band */
+ airspeed = 0.5f * (airspeed_min + airspeed_max);
+ } else if (airspeed < airspeed_min) {
+ airspeed = airspeed_min;
+ }
+
+ float roll_error = roll_setpoint - roll;
+ _rate_setpoint = roll_error / _tc;
+
+ /* limit the rate */
+ if (_max_rate > 0.01f) {
+ _rate_setpoint = (_rate_setpoint > _max_rate) ? _max_rate : _rate_setpoint;
+ _rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint;
+ }
+
+ _rate_error = _rate_setpoint - roll_rate;
+
+
+ float ilimit_scaled = _integrator_max * scaler;
+
+ if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * k_i_rate * dt * scaler;
+
+ /*
+ * anti-windup: do not allow integrator to increase into the
+ * wrong direction if actuator is at limit
+ */
+ if (_last_output < -_max_deflection_rad) {
+ /* only allow motion to center: increase value */
+ id = math::max(id, 0.0f);
+ } else if (_last_output > _max_deflection_rad) {
+ /* only allow motion to center: decrease value */
+ id = math::min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
+ /* store non-limited output */
+ _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_ff)) * scaler;
+
+ return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
+}
+
+void ECL_RollController::reset_integrator()
+{
+ _integrator = 0.0f;
+}
+
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
new file mode 100644
index 000000000..0d4ea9333
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -0,0 +1,108 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_roll_controller.h
+ * Definition of a simple orthogonal roll PID controller.
+ *
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ *
+ * Acknowledgements:
+ *
+ * The control design is based on a design
+ * by Paul Riseborough and Andrew Tridgell, 2013,
+ * which in turn is based on initial work of
+ * Jonathan Challinger, 2012.
+ */
+
+#ifndef ECL_ROLL_CONTROLLER_H
+#define ECL_ROLL_CONTROLLER_H
+
+#include <stdbool.h>
+#include <stdint.h>
+
+class __EXPORT ECL_RollController
+{
+public:
+ ECL_RollController();
+
+ float control(float roll_setpoint, float roll, float roll_rate,
+ float scaler = 1.0f, bool lock_integrator = false, float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f));
+
+ void reset_integrator();
+
+ void set_time_constant(float time_constant) {
+ if (time_constant > 0.1f && time_constant < 3.0f) {
+ _tc = time_constant;
+ }
+ }
+ void set_k_p(float k_p) {
+ _k_p = k_p;
+ }
+ void set_k_i(float k_i) {
+ _k_i = k_i;
+ }
+ void set_k_d(float k_d) {
+ _k_d = k_d;
+ }
+ void set_integrator_max(float max) {
+ _integrator_max = max;
+ }
+ void set_max_rate(float max_rate) {
+ _max_rate = max_rate;
+ }
+
+ float get_rate_error() {
+ return _rate_error;
+ }
+
+ float get_desired_rate() {
+ return _rate_setpoint;
+ }
+
+private:
+ uint64_t _last_run;
+ float _tc;
+ float _k_p;
+ float _k_i;
+ float _k_d;
+ float _integrator_max;
+ float _max_rate;
+ float _last_output;
+ float _integrator;
+ float _rate_error;
+ float _rate_setpoint;
+ float _max_deflection_rad;
+};
+
+#endif // ECL_ROLL_CONTROLLER_H
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
new file mode 100644
index 000000000..b786acf24
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -0,0 +1,75 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_yaw_controller.cpp
+ * Implementation of a simple orthogonal coordinated turn yaw PID controller.
+ *
+ * Authors and acknowledgements in header.
+ */
+
+#include "ecl_yaw_controller.h"
+#include <stdint.h>
+#include <float.h>
+#include <geo/geo.h>
+#include <ecl/ecl.h>
+#include <mathlib/mathlib.h>
+
+ECL_YawController::ECL_YawController() :
+ _last_run(0),
+ _last_error(0.0f),
+ _last_output(0.0f),
+ _last_rate_hp_out(0.0f),
+ _last_rate_hp_in(0.0f),
+ _k_d_last(0.0f),
+ _integrator(0.0f)
+{
+
+}
+
+float ECL_YawController::control(float roll, float yaw_rate, float accel_y, float scaler, bool lock_integrator,
+ float airspeed_min, float airspeed_max, float aspeed)
+{
+ /* get the usual dt estimate */
+ uint64_t dt_micros = ecl_elapsed_time(&_last_run);
+ _last_run = ecl_absolute_time();
+
+ float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000;
+
+ return 0.0f;
+}
+
+void ECL_YawController::reset_integrator()
+{
+ _integrator = 0.0f;
+}
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
new file mode 100644
index 000000000..66b227918
--- /dev/null
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -0,0 +1,89 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_yaw_controller.h
+ * Definition of a simple orthogonal coordinated turn yaw PID controller.
+ *
+ */
+#ifndef ECL_YAW_CONTROLLER_H
+#define ECL_YAW_CONTROLLER_H
+
+#include <stdbool.h>
+#include <stdint.h>
+
+class __EXPORT ECL_YawController
+{
+public:
+ ECL_YawController();
+
+ float control(float roll, float yaw_rate, float accel_y, float scaler = 1.0f, bool lock_integrator = false,
+ float airspeed_min = 0, float airspeed_max = 0, float aspeed = (0.0f / 0.0f));
+
+ void reset_integrator();
+
+ void set_k_side(float k_a) {
+ _k_side = k_a;
+ }
+ void set_k_i(float k_i) {
+ _k_i = k_i;
+ }
+ void set_k_d(float k_d) {
+ _k_d = k_d;
+ }
+ void set_k_roll_ff(float k_roll_ff) {
+ _k_roll_ff = k_roll_ff;
+ }
+ void set_integrator_max(float max) {
+ _integrator_max = max;
+ }
+
+private:
+ uint64_t _last_run;
+
+ float _k_side;
+ float _k_i;
+ float _k_d;
+ float _k_roll_ff;
+ float _integrator_max;
+
+ float _last_error;
+ float _last_output;
+ float _last_rate_hp_out;
+ float _last_rate_hp_in;
+ float _k_d_last;
+ float _integrator;
+
+};
+
+#endif // ECL_YAW_CONTROLLER_H
diff --git a/src/lib/ecl/ecl.h b/src/lib/ecl/ecl.h
new file mode 100644
index 000000000..e0f207696
--- /dev/null
+++ b/src/lib/ecl/ecl.h
@@ -0,0 +1,44 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 APL 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 ecl.h
+ * Adapter / shim layer for system calls needed by ECL
+ *
+ */
+
+#include <drivers/drv_hrt.h>
+#include <geo/geo.h>
+
+#define ecl_absolute_time hrt_absolute_time
+#define ecl_elapsed_time hrt_elapsed_time \ No newline at end of file
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
new file mode 100644
index 000000000..27d76f959
--- /dev/null
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -0,0 +1,366 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_l1_pos_controller.h
+ * Implementation of L1 position control.
+ * Authors and acknowledgements in header.
+ *
+ */
+
+#include "ecl_l1_pos_controller.h"
+
+float ECL_L1_Pos_Controller::nav_roll()
+{
+ float ret = atanf(_lateral_accel * 1.0f / CONSTANTS_ONE_G);
+ ret = math::constrain(ret, -_roll_lim_rad, _roll_lim_rad);
+ return ret;
+}
+
+float ECL_L1_Pos_Controller::nav_lateral_acceleration_demand()
+{
+ return _lateral_accel;
+}
+
+float ECL_L1_Pos_Controller::nav_bearing()
+{
+ return _wrap_pi(_nav_bearing);
+}
+
+float ECL_L1_Pos_Controller::bearing_error()
+{
+ return _bearing_error;
+}
+
+float ECL_L1_Pos_Controller::target_bearing()
+{
+ return _target_bearing;
+}
+
+float ECL_L1_Pos_Controller::switch_distance(float wp_radius)
+{
+ /* following [2], switching on L1 distance */
+ return math::max(wp_radius, _L1_distance);
+}
+
+bool ECL_L1_Pos_Controller::reached_loiter_target(void)
+{
+ return _circle_mode;
+}
+
+float ECL_L1_Pos_Controller::crosstrack_error(void)
+{
+ return _crosstrack_error;
+}
+
+void ECL_L1_Pos_Controller::navigate_waypoints(const math::Vector2f &vector_A, const math::Vector2f &vector_B, const math::Vector2f &vector_curr_position,
+ const math::Vector2f &ground_speed_vector)
+{
+
+ /* this follows the logic presented in [1] */
+
+ float eta;
+ float xtrack_vel;
+ float ltrack_vel;
+
+ /* get the direction between the last (visited) and next waypoint */
+ _target_bearing = get_bearing_to_next_waypoint(vector_curr_position.getX(), vector_curr_position.getY(), vector_B.getX(), vector_B.getY());
+
+ /* enforce a minimum ground speed of 0.1 m/s to avoid singularities */
+ float ground_speed = math::max(ground_speed_vector.length(), 0.1f);
+
+ /* calculate the L1 length required for the desired period */
+ _L1_distance = _L1_ratio * ground_speed;
+
+ /* calculate vector from A to B */
+ math::Vector2f vector_AB = get_local_planar_vector(vector_A, vector_B);
+
+ /*
+ * check if waypoints are on top of each other. If yes,
+ * skip A and directly continue to B
+ */
+ if (vector_AB.length() < 1.0e-6f) {
+ vector_AB = get_local_planar_vector(vector_curr_position, vector_B);
+ }
+
+ vector_AB.normalize();
+
+ /* calculate the vector from waypoint A to the aircraft */
+ math::Vector2f vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
+
+ /* calculate crosstrack error (output only) */
+ _crosstrack_error = vector_AB % vector_A_to_airplane;
+
+ /*
+ * If the current position is in a +-135 degree angle behind waypoint A
+ * and further away from A than the L1 distance, then A becomes the L1 point.
+ * If the aircraft is already between A and B normal L1 logic is applied.
+ */
+ float distance_A_to_airplane = vector_A_to_airplane.length();
+ float alongTrackDist = vector_A_to_airplane * vector_AB;
+
+ /* estimate airplane position WRT to B */
+ math::Vector2f vector_B_to_P_unit = get_local_planar_vector(vector_B, vector_curr_position).normalized();
+
+ /* calculate angle of airplane position vector relative to line) */
+
+ // XXX this could probably also be based solely on the dot product
+ float AB_to_BP_bearing = atan2f(vector_B_to_P_unit % vector_AB, vector_B_to_P_unit * vector_AB);
+
+ /* extension from [2], fly directly to A */
+ if (distance_A_to_airplane > _L1_distance && alongTrackDist / math::max(distance_A_to_airplane , 1.0f) < -0.7071f) {
+
+ /* calculate eta to fly to waypoint A */
+
+ /* unit vector from waypoint A to current position */
+ math::Vector2f vector_A_to_airplane_unit = vector_A_to_airplane.normalized();
+ /* velocity across / orthogonal to line */
+ xtrack_vel = ground_speed_vector % (-vector_A_to_airplane_unit);
+ /* velocity along line */
+ ltrack_vel = ground_speed_vector * (-vector_A_to_airplane_unit);
+ eta = atan2f(xtrack_vel, ltrack_vel);
+ /* bearing from current position to L1 point */
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+
+ /*
+ * If the AB vector and the vector from B to airplane point in the same
+ * direction, we have missed the waypoint. At +- 90 degrees we are just passing it.
+ */
+ } else if (fabsf(AB_to_BP_bearing) < math::radians(100.0f)) {
+ /*
+ * Extension, fly back to waypoint.
+ *
+ * This corner case is possible if the system was following
+ * the AB line from waypoint A to waypoint B, then is
+ * switched to manual mode (or otherwise misses the waypoint)
+ * and behind the waypoint continues to follow the AB line.
+ */
+
+ /* calculate eta to fly to waypoint B */
+
+ /* velocity across / orthogonal to line */
+ xtrack_vel = ground_speed_vector % (-vector_B_to_P_unit);
+ /* velocity along line */
+ ltrack_vel = ground_speed_vector * (-vector_B_to_P_unit);
+ eta = atan2f(xtrack_vel, ltrack_vel);
+ /* bearing from current position to L1 point */
+ _nav_bearing = atan2f(-vector_B_to_P_unit.getY() , -vector_B_to_P_unit.getX());
+
+ } else {
+
+ /* calculate eta to fly along the line between A and B */
+
+ /* velocity across / orthogonal to line */
+ xtrack_vel = ground_speed_vector % vector_AB;
+ /* velocity along line */
+ ltrack_vel = ground_speed_vector * vector_AB;
+ /* calculate eta2 (angle of velocity vector relative to line) */
+ float eta2 = atan2f(xtrack_vel, ltrack_vel);
+ /* calculate eta1 (angle to L1 point) */
+ float xtrackErr = vector_A_to_airplane % vector_AB;
+ float sine_eta1 = xtrackErr / math::max(_L1_distance , 0.1f);
+ /* limit output to 45 degrees */
+ sine_eta1 = math::constrain(sine_eta1, -0.7071f, 0.7071f); //sin(pi/4) = 0.7071
+ float eta1 = asinf(sine_eta1);
+ eta = eta1 + eta2;
+ /* bearing from current position to L1 point */
+ _nav_bearing = atan2f(vector_AB.getY(), vector_AB.getX()) + eta1;
+
+ }
+
+ /* limit angle to +-90 degrees */
+ eta = math::constrain(eta, (-M_PI_F) / 2.0f, +M_PI_F / 2.0f);
+ _lateral_accel = _K_L1 * ground_speed * ground_speed / _L1_distance * sinf(eta);
+
+ /* flying to waypoints, not circling them */
+ _circle_mode = false;
+
+ /* the bearing angle, in NED frame */
+ _bearing_error = eta;
+}
+
+void ECL_L1_Pos_Controller::navigate_loiter(const math::Vector2f &vector_A, const math::Vector2f &vector_curr_position, float radius, int8_t loiter_direction,
+ const math::Vector2f &ground_speed_vector)
+{
+ /* the complete guidance logic in this section was proposed by [2] */
+
+ /* calculate the gains for the PD loop (circle tracking) */
+ float omega = (2.0f * M_PI_F / _L1_period);
+ float K_crosstrack = omega * omega;
+ float K_velocity = 2.0f * _L1_damping * omega;
+
+ /* update bearing to next waypoint */
+ _target_bearing = get_bearing_to_next_waypoint(vector_curr_position.getX(), vector_curr_position.getY(), vector_A.getX(), vector_A.getY());
+
+ /* ground speed, enforce minimum of 0.1 m/s to avoid singularities */
+ float ground_speed = math::max(ground_speed_vector.length() , 0.1f);
+
+ /* calculate the L1 length required for the desired period */
+ _L1_distance = _L1_ratio * ground_speed;
+
+ /* calculate the vector from waypoint A to current position */
+ math::Vector2f vector_A_to_airplane = get_local_planar_vector(vector_A, vector_curr_position);
+
+ /* store the normalized vector from waypoint A to current position */
+ math::Vector2f vector_A_to_airplane_unit = (vector_A_to_airplane).normalized();
+
+ /* calculate eta angle towards the loiter center */
+
+ /* velocity across / orthogonal to line from waypoint to current position */
+ float xtrack_vel_center = vector_A_to_airplane_unit % ground_speed_vector;
+ /* velocity along line from waypoint to current position */
+ float ltrack_vel_center = - (ground_speed_vector * vector_A_to_airplane_unit);
+ float eta = atan2f(xtrack_vel_center, ltrack_vel_center);
+ /* limit eta to 90 degrees */
+ eta = math::constrain(eta, -M_PI_F / 2.0f, +M_PI_F / 2.0f);
+
+ /* calculate the lateral acceleration to capture the center point */
+ float lateral_accel_sp_center = _K_L1 * ground_speed * ground_speed / _L1_distance * sinf(eta);
+
+ /* for PD control: Calculate radial position and velocity errors */
+
+ /* radial velocity error */
+ float xtrack_vel_circle = -ltrack_vel_center;
+ /* radial distance from the loiter circle (not center) */
+ float xtrack_err_circle = vector_A_to_airplane.length() - radius;
+
+ /* cross track error for feedback */
+ _crosstrack_error = xtrack_err_circle;
+
+ /* calculate PD update to circle waypoint */
+ float lateral_accel_sp_circle_pd = (xtrack_err_circle * K_crosstrack + xtrack_vel_circle * K_velocity);
+
+ /* calculate velocity on circle / along tangent */
+ float tangent_vel = xtrack_vel_center * loiter_direction;
+
+ /* prevent PD output from turning the wrong way */
+ if (tangent_vel < 0.0f) {
+ lateral_accel_sp_circle_pd = math::max(lateral_accel_sp_circle_pd , 0.0f);
+ }
+
+ /* calculate centripetal acceleration setpoint */
+ float lateral_accel_sp_circle_centripetal = tangent_vel * tangent_vel / math::max((0.5f * radius) , (radius + xtrack_err_circle));
+
+ /* add PD control on circle and centripetal acceleration for total circle command */
+ float lateral_accel_sp_circle = loiter_direction * (lateral_accel_sp_circle_pd + lateral_accel_sp_circle_centripetal);
+
+ /*
+ * Switch between circle (loiter) and capture (towards waypoint center) mode when
+ * the commands switch over. Only fly towards waypoint if outside the circle.
+ */
+
+ // XXX check switch over
+ if ((lateral_accel_sp_center < lateral_accel_sp_circle && loiter_direction > 0 && xtrack_err_circle > 0.0f) |
+ (lateral_accel_sp_center > lateral_accel_sp_circle && loiter_direction < 0 && xtrack_err_circle > 0.0f)) {
+ _lateral_accel = lateral_accel_sp_center;
+ _circle_mode = false;
+ /* angle between requested and current velocity vector */
+ _bearing_error = eta;
+ /* bearing from current position to L1 point */
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+
+ } else {
+ _lateral_accel = lateral_accel_sp_circle;
+ _circle_mode = true;
+ _bearing_error = 0.0f;
+ /* bearing from current position to L1 point */
+ _nav_bearing = atan2f(-vector_A_to_airplane_unit.getY() , -vector_A_to_airplane_unit.getX());
+ }
+}
+
+
+void ECL_L1_Pos_Controller::navigate_heading(float navigation_heading, float current_heading, const math::Vector2f &ground_speed_vector)
+{
+ /* the complete guidance logic in this section was proposed by [2] */
+
+ float eta;
+
+ /*
+ * As the commanded heading is the only reference
+ * (and no crosstrack correction occurs),
+ * target and navigation bearing become the same
+ */
+ _target_bearing = _nav_bearing = _wrap_pi(navigation_heading);
+ eta = _target_bearing - _wrap_pi(current_heading);
+ eta = _wrap_pi(eta);
+
+ /* consequently the bearing error is exactly eta: */
+ _bearing_error = eta;
+
+ /* ground speed is the length of the ground speed vector */
+ float ground_speed = ground_speed_vector.length();
+
+ /* adjust L1 distance to keep constant frequency */
+ _L1_distance = ground_speed / _heading_omega;
+ float omega_vel = ground_speed * _heading_omega;
+
+ /* not circling a waypoint */
+ _circle_mode = false;
+
+ /* navigating heading means by definition no crosstrack error */
+ _crosstrack_error = 0;
+
+ /* limit eta to 90 degrees */
+ eta = math::constrain(eta, (-M_PI_F) / 2.0f, +M_PI_F / 2.0f);
+ _lateral_accel = 2.0f * sinf(eta) * omega_vel;
+}
+
+void ECL_L1_Pos_Controller::navigate_level_flight(float current_heading)
+{
+ /* the logic in this section is trivial, but originally proposed by [2] */
+
+ /* reset all heading / error measures resulting in zero roll */
+ _target_bearing = current_heading;
+ _nav_bearing = current_heading;
+ _bearing_error = 0;
+ _crosstrack_error = 0;
+ _lateral_accel = 0;
+
+ /* not circling a waypoint when flying level */
+ _circle_mode = false;
+
+}
+
+
+math::Vector2f ECL_L1_Pos_Controller::get_local_planar_vector(const math::Vector2f &origin, const math::Vector2f &target) const
+{
+ /* this is an approximation for small angles, proposed by [2] */
+
+ math::Vector2f out;
+
+ out.setX(math::radians((target.getX() - origin.getX())));
+ out.setY(math::radians((target.getY() - origin.getY())*cosf(math::radians(origin.getX()))));
+
+ return out * static_cast<float>(CONSTANTS_RADIUS_OF_EARTH);
+}
+
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.h b/src/lib/ecl/l1/ecl_l1_pos_controller.h
new file mode 100644
index 000000000..7a3c42a92
--- /dev/null
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.h
@@ -0,0 +1,268 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 Estimation and Control Library (ECL). 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 ECL 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 ecl_l1_pos_control.h
+ * Implementation of L1 position control.
+ *
+ *
+ * Acknowledgements and References:
+ *
+ * This implementation has been built for PX4 based on the original
+ * publication from [1] and does include a lot of the ideas (not code)
+ * from [2].
+ *
+ *
+ * [1] S. Park, J. Deyst, and J. P. How, "A New Nonlinear Guidance Logic for Trajectory Tracking,"
+ * Proceedings of the AIAA Guidance, Navigation and Control
+ * Conference, Aug 2004. AIAA-2004-4900.
+ *
+ * [2] Paul Riseborough, Brandon Jones and Andrew Tridgell, L1 control for APM. Aug 2013.
+ * - Explicit control over frequency and damping
+ * - Explicit control over track capture angle
+ * - Ability to use loiter radius smaller than L1 length
+ * - Modified to use PD control for circle tracking to enable loiter radius less than L1 length
+ * - Modified to enable period and damping of guidance loop to be set explicitly
+ * - Modified to provide explicit control over capture angle
+ *
+ */
+
+#ifndef ECL_L1_POS_CONTROLLER_H
+#define ECL_L1_POS_CONTROLLER_H
+
+#include <mathlib/mathlib.h>
+#include <geo/geo.h>
+#include <ecl/ecl.h>
+
+/**
+ * L1 Nonlinear Guidance Logic
+ */
+class __EXPORT ECL_L1_Pos_Controller
+{
+public:
+ ECL_L1_Pos_Controller() {
+ _L1_period = 25;
+ _L1_damping = 0.75f;
+ }
+
+ /**
+ * The current target bearing
+ *
+ * @return bearing angle (-pi..pi, in NED frame)
+ */
+ float nav_bearing();
+
+
+ /**
+ * Get lateral acceleration demand.
+ *
+ * @return Lateral acceleration in m/s^2
+ */
+ float nav_lateral_acceleration_demand();
+
+
+ /**
+ * Heading error.
+ *
+ * The heading error is either compared to the current track
+ * or to the tangent of the current loiter radius.
+ */
+ float bearing_error();
+
+
+ /**
+ * Bearing from aircraft to current target.
+ *
+ * @return bearing angle (-pi..pi, in NED frame)
+ */
+ float target_bearing();
+
+
+ /**
+ * Get roll angle setpoint for fixed wing.
+ *
+ * @return Roll angle (in NED frame)
+ */
+ float nav_roll();
+
+
+ /**
+ * Get the current crosstrack error.
+ *
+ * @return Crosstrack error in meters.
+ */
+ float crosstrack_error();
+
+
+ /**
+ * Returns true if the loiter waypoint has been reached
+ */
+ bool reached_loiter_target();
+
+
+ /**
+ * Returns true if following a circle (loiter)
+ */
+ bool circle_mode() {
+ return _circle_mode;
+ }
+
+
+ /**
+ * Get the switch distance
+ *
+ * This is the distance at which the system will
+ * switch to the next waypoint. This depends on the
+ * period and damping
+ *
+ * @param waypoint_switch_radius The switching radius the waypoint has set.
+ */
+ float switch_distance(float waypoint_switch_radius);
+
+
+ /**
+ * Navigate between two waypoints
+ *
+ * Calling this function with two waypoints results in the
+ * control outputs to fly to the line segment defined by
+ * the points and once captured following the line segment.
+ * This follows the logic in [1].
+ *
+ * @return sets _lateral_accel setpoint
+ */
+ void navigate_waypoints(const math::Vector2f &vector_A, const math::Vector2f &vector_B, const math::Vector2f &vector_curr_position,
+ const math::Vector2f &ground_speed);
+
+
+ /**
+ * Navigate on an orbit around a loiter waypoint.
+ *
+ * This allow orbits smaller than the L1 length,
+ * this modification was introduced in [2].
+ *
+ * @return sets _lateral_accel setpoint
+ */
+ void navigate_loiter(const math::Vector2f &vector_A, const math::Vector2f &vector_curr_position, float radius, int8_t loiter_direction,
+ const math::Vector2f &ground_speed_vector);
+
+
+ /**
+ * Navigate on a fixed bearing.
+ *
+ * This only holds a certain direction and does not perform cross
+ * track correction. Helpful for semi-autonomous modes. Introduced
+ * by [2].
+ *
+ * @return sets _lateral_accel setpoint
+ */
+ void navigate_heading(float navigation_heading, float current_heading, const math::Vector2f &ground_speed);
+
+
+ /**
+ * Keep the wings level.
+ *
+ * This is typically needed for maximum-lift-demand situations,
+ * such as takeoff or near stall. Introduced in [2].
+ */
+ void navigate_level_flight(float current_heading);
+
+
+ /**
+ * Set the L1 period.
+ */
+ void set_l1_period(float period) {
+ _L1_period = period;
+ /* calculate the ratio introduced in [2] */
+ _L1_ratio = 1.0f / M_PI_F * _L1_damping * _L1_period;
+ /* calculate normalized frequency for heading tracking */
+ _heading_omega = sqrtf(2.0f) * M_PI_F / _L1_period;
+ }
+
+
+ /**
+ * Set the L1 damping factor.
+ *
+ * The original publication recommends a default of sqrt(2) / 2 = 0.707
+ */
+ void set_l1_damping(float damping) {
+ _L1_damping = damping;
+ /* calculate the ratio introduced in [2] */
+ _L1_ratio = 1.0f / M_PI_F * _L1_damping * _L1_period;
+ /* calculate the L1 gain (following [2]) */
+ _K_L1 = 4.0f * _L1_damping * _L1_damping;
+ }
+
+
+ /**
+ * Set the maximum roll angle output in radians
+ *
+ */
+ void set_l1_roll_limit(float roll_lim_rad) {
+ _roll_lim_rad = roll_lim_rad;
+ }
+
+private:
+
+ float _lateral_accel; ///< Lateral acceleration setpoint in m/s^2
+ float _L1_distance; ///< L1 lead distance, defined by period and damping
+ bool _circle_mode; ///< flag for loiter mode
+ float _nav_bearing; ///< bearing to L1 reference point
+ float _bearing_error; ///< bearing error
+ float _crosstrack_error; ///< crosstrack error in meters
+ float _target_bearing; ///< the heading setpoint
+
+ float _L1_period; ///< L1 tracking period in seconds
+ float _L1_damping; ///< L1 damping ratio
+ float _L1_ratio; ///< L1 ratio for navigation
+ float _K_L1; ///< L1 control gain for _L1_damping
+ float _heading_omega; ///< Normalized frequency
+
+ float _roll_lim_rad; ///<maximum roll angle
+
+ /**
+ * Convert a 2D vector from WGS84 to planar coordinates.
+ *
+ * This converts from latitude and longitude to planar
+ * coordinates with (0,0) being at the position of ref and
+ * returns a vector in meters towards wp.
+ *
+ * @param ref The reference position in WGS84 coordinates
+ * @param wp The point to convert to into the local coordinates, in WGS84 coordinates
+ * @return The vector in meters pointing from the reference position to the coordinates
+ */
+ math::Vector2f get_local_planar_vector(const math::Vector2f &origin, const math::Vector2f &target) const;
+
+};
+
+
+#endif /* ECL_L1_POS_CONTROLLER_H */
diff --git a/src/lib/ecl/module.mk b/src/lib/ecl/module.mk
new file mode 100644
index 000000000..f2aa3db6a
--- /dev/null
+++ b/src/lib/ecl/module.mk
@@ -0,0 +1,41 @@
+############################################################################
+#
+# Copyright (c) 2013 Estimation and Control Library (ECL). 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.
+#
+############################################################################
+
+#
+# Estimation and Control Library
+#
+
+SRCS = attitude_fw/ecl_pitch_controller.cpp \
+ attitude_fw/ecl_roll_controller.cpp \
+ attitude_fw/ecl_yaw_controller.cpp \
+ l1/ecl_l1_pos_controller.cpp
diff --git a/src/lib/external_lgpl/module.mk b/src/lib/external_lgpl/module.mk
new file mode 100644
index 000000000..53f1629e3
--- /dev/null
+++ b/src/lib/external_lgpl/module.mk
@@ -0,0 +1,48 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# W A R N I N G: The contents of this directory are license-incompatible
+# with the rest of the codebase. Do NOT copy any parts of it
+# into other folders.
+#
+# Acknowledgements:
+#
+# The algorithms in this folder have been developed by Paul Riseborough
+# with support from Andrew Tridgell.
+# Originally licensed as LGPL for APM. As this is built as library and
+# linked, use of this code does not change the usability of PX4 in general
+# or any of the license implications.
+#
+
+SRCS = tecs/tecs.cpp
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
new file mode 100644
index 000000000..864a9d24d
--- /dev/null
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -0,0 +1,534 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
+
+#include "tecs.h"
+#include <ecl/ecl.h>
+
+using namespace math;
+
+#ifndef CONSTANTS_ONE_G
+#define CONSTANTS_ONE_G GRAVITY
+#endif
+
+/**
+ * @file tecs.cpp
+ *
+ * @author Paul Riseborough
+ *
+ * Written by Paul Riseborough 2013 to provide:
+ * - Combined control of speed and height using throttle to control
+ * total energy and pitch angle to control exchange of energy between
+ * potential and kinetic.
+ * Selectable speed or height priority modes when calculating pitch angle
+ * - Fallback mode when no airspeed measurement is available that
+ * sets throttle based on height rate demand and switches pitch angle control to
+ * height priority
+ * - Underspeed protection that demands maximum throttle and switches pitch angle control
+ * to speed priority mode
+ * - Relative ease of tuning through use of intuitive time constant, integrator and damping gains and the use
+ * of easy to measure aircraft performance data
+ *
+ */
+
+void TECS::update_50hz(float baro_altitude, float airspeed, const math::Dcm &rotMat, const math::Vector3 &accel_body, const math::Vector3 &accel_earth)
+{
+ // Implement third order complementary filter for height and height rate
+ // estimted height rate = _integ2_state
+ // estimated height = _integ3_state
+ // Reference Paper :
+ // Optimising the Gains of the Baro-Inertial Vertical Channel
+ // Widnall W.S, Sinha P.K,
+ // AIAA Journal of Guidance and Control, 78-1307R
+
+ // Calculate time in seconds since last update
+ uint64_t now = ecl_absolute_time();
+ float DT = max((now - _update_50hz_last_usec), 0ULL) * 1.0e-6f;
+
+ // printf("dt: %10.6f baro alt: %6.2f eas: %6.2f R(0,0): %6.2f, R(1,1): %6.2f\naccel body: %6.2f %6.2f %6.2f\naccel earth: %6.2f %6.2f %6.2f\n",
+ // DT, baro_altitude, airspeed, rotMat(0, 0), rotMat(1, 1), accel_body(0), accel_body(1), accel_body(2),
+ // accel_earth(0), accel_earth(1), accel_earth(2));
+
+ if (DT > 1.0f) {
+ _integ3_state = baro_altitude;
+ _integ2_state = 0.0f;
+ _integ1_state = 0.0f;
+ DT = 0.02f; // when first starting TECS, use a
+ // small time constant
+ }
+
+ _update_50hz_last_usec = now;
+ _EAS = airspeed;
+
+ // Get height acceleration
+ float hgt_ddot_mea = -(accel_earth(2) + CONSTANTS_ONE_G);
+ // Perform filter calculation using backwards Euler integration
+ // Coefficients selected to place all three filter poles at omega
+ float omega2 = _hgtCompFiltOmega * _hgtCompFiltOmega;
+ float hgt_err = baro_altitude - _integ3_state;
+ float integ1_input = hgt_err * omega2 * _hgtCompFiltOmega;
+ _integ1_state = _integ1_state + integ1_input * DT;
+ float integ2_input = _integ1_state + hgt_ddot_mea + hgt_err * omega2 * 3.0f;
+ _integ2_state = _integ2_state + integ2_input * DT;
+ float integ3_input = _integ2_state + hgt_err * _hgtCompFiltOmega * 3.0f;
+
+ // If more than 1 second has elapsed since last update then reset the integrator state
+ // to the measured height
+ if (DT > 1.0f) {
+ _integ3_state = baro_altitude;
+
+ } else {
+ _integ3_state = _integ3_state + integ3_input * DT;
+ }
+
+ // Update and average speed rate of change
+ // Only required if airspeed is being measured and controlled
+ float temp = 0;
+
+ if (isfinite(airspeed) && airspeed_sensor_enabled()) {
+ // Get DCM
+ // Calculate speed rate of change
+ // XXX check
+ temp = rotMat(2, 0) * CONSTANTS_ONE_G + accel_body(0);
+ // take 5 point moving average
+ //_vel_dot = _vdot_filter.apply(temp);
+ // XXX resolve this properly
+ _vel_dot = 0.9f * _vel_dot + 0.1f * temp;
+
+ } else {
+ _vel_dot = 0.0f;
+ }
+
+}
+
+void TECS::_update_speed(float airspeed_demand, float indicated_airspeed,
+ float indicated_airspeed_min, float indicated_airspeed_max, float EAS2TAS)
+{
+ // Calculate time in seconds since last update
+ uint64_t now = ecl_absolute_time();
+ float DT = max((now - _update_speed_last_usec), 0ULL) * 1.0e-6f;
+ _update_speed_last_usec = now;
+
+ // Convert equivalent airspeeds to true airspeeds
+
+ _EAS_dem = airspeed_demand;
+ _TAS_dem = _EAS_dem * EAS2TAS;
+ _TASmax = indicated_airspeed_max * EAS2TAS;
+ _TASmin = indicated_airspeed_min * EAS2TAS;
+
+ // Reset states of time since last update is too large
+ if (DT > 1.0f) {
+ _integ5_state = (_EAS * EAS2TAS);
+ _integ4_state = 0.0f;
+ DT = 0.1f; // when first starting TECS, use a
+ // small time constant
+ }
+
+ // Get airspeed or default to halfway between min and max if
+ // airspeed is not being used and set speed rate to zero
+ if (!isfinite(indicated_airspeed) || !airspeed_sensor_enabled()) {
+ // If no airspeed available use average of min and max
+ _EAS = 0.5f * (indicated_airspeed_min + indicated_airspeed_max);
+
+ } else {
+ _EAS = indicated_airspeed;
+ }
+
+ // Implement a second order complementary filter to obtain a
+ // smoothed airspeed estimate
+ // airspeed estimate is held in _integ5_state
+ float aspdErr = (_EAS * EAS2TAS) - _integ5_state;
+ float integ4_input = aspdErr * _spdCompFiltOmega * _spdCompFiltOmega;
+
+ // Prevent state from winding up
+ if (_integ5_state < 3.1f) {
+ integ4_input = max(integ4_input , 0.0f);
+ }
+
+ _integ4_state = _integ4_state + integ4_input * DT;
+ float integ5_input = _integ4_state + _vel_dot + aspdErr * _spdCompFiltOmega * 1.4142f;
+ _integ5_state = _integ5_state + integ5_input * DT;
+ // limit the airspeed to a minimum of 3 m/s
+ _integ5_state = max(_integ5_state, 3.0f);
+
+}
+
+void TECS::_update_speed_demand(void)
+{
+ // Set the airspeed demand to the minimum value if an underspeed condition exists
+ // or a bad descent condition exists
+ // This will minimise the rate of descent resulting from an engine failure,
+ // enable the maximum climb rate to be achieved and prevent continued full power descent
+ // into the ground due to an unachievable airspeed value
+ if ((_badDescent) || (_underspeed)) {
+ _TAS_dem = _TASmin;
+ }
+
+ // Constrain speed demand
+ _TAS_dem = constrain(_TAS_dem, _TASmin, _TASmax);
+
+ // calculate velocity rate limits based on physical performance limits
+ // provision to use a different rate limit if bad descent or underspeed condition exists
+ // Use 50% of maximum energy rate to allow margin for total energy contgroller
+ float velRateMax;
+ float velRateMin;
+
+ if ((_badDescent) || (_underspeed)) {
+ velRateMax = 0.5f * _STEdot_max / _integ5_state;
+ velRateMin = 0.5f * _STEdot_min / _integ5_state;
+
+ } else {
+ velRateMax = 0.5f * _STEdot_max / _integ5_state;
+ velRateMin = 0.5f * _STEdot_min / _integ5_state;
+ }
+
+ // Apply rate limit
+ if ((_TAS_dem - _TAS_dem_adj) > (velRateMax * 0.1f)) {
+ _TAS_dem_adj = _TAS_dem_adj + velRateMax * 0.1f;
+ _TAS_rate_dem = velRateMax;
+
+ } else if ((_TAS_dem - _TAS_dem_adj) < (velRateMin * 0.1f)) {
+ _TAS_dem_adj = _TAS_dem_adj + velRateMin * 0.1f;
+ _TAS_rate_dem = velRateMin;
+
+ } else {
+ _TAS_dem_adj = _TAS_dem;
+ _TAS_rate_dem = (_TAS_dem - _TAS_dem_last) / 0.1f;
+ }
+
+ // Constrain speed demand again to protect against bad values on initialisation.
+ _TAS_dem_adj = constrain(_TAS_dem_adj, _TASmin, _TASmax);
+ _TAS_dem_last = _TAS_dem;
+}
+
+void TECS::_update_height_demand(float demand)
+{
+ // Apply 2 point moving average to demanded height
+ // This is required because height demand is only updated at 5Hz
+ _hgt_dem = 0.5f * (demand + _hgt_dem_in_old);
+ _hgt_dem_in_old = _hgt_dem;
+
+ // printf("hgt_dem: %6.2f hgt_dem_last: %6.2f max_climb_rate: %6.2f\n", _hgt_dem, _hgt_dem_prev,
+ // _maxClimbRate);
+
+ // Limit height rate of change
+ if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) {
+ _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
+
+ } else if ((_hgt_dem - _hgt_dem_prev) < (-_maxSinkRate * 0.1f)) {
+ _hgt_dem = _hgt_dem_prev - _maxSinkRate * 0.1f;
+ }
+
+ _hgt_dem_prev = _hgt_dem;
+
+ // Apply first order lag to height demand
+ _hgt_dem_adj = 0.05f * _hgt_dem + 0.95f * _hgt_dem_adj_last;
+ _hgt_rate_dem = (_hgt_dem_adj - _hgt_dem_adj_last) / 0.1f;
+ _hgt_dem_adj_last = _hgt_dem_adj;
+
+ // printf("hgt_dem: %6.2f hgt_dem_adj: %6.2f hgt_dem_last: %6.2f hgt_rate_dem: %6.2f\n", _hgt_dem, _hgt_dem_adj, _hgt_dem_adj_last,
+ // _hgt_rate_dem);
+}
+
+void TECS::_detect_underspeed(void)
+{
+ if (((_integ5_state < _TASmin * 0.9f) && (_throttle_dem >= _THRmaxf * 0.95f)) || ((_integ3_state < _hgt_dem_adj) && _underspeed)) {
+ _underspeed = true;
+
+ } else {
+ _underspeed = false;
+ }
+}
+
+void TECS::_update_energies(void)
+{
+ // Calculate specific energy demands
+ _SPE_dem = _hgt_dem_adj * CONSTANTS_ONE_G;
+ _SKE_dem = 0.5f * _TAS_dem_adj * _TAS_dem_adj;
+
+ // Calculate specific energy rate demands
+ _SPEdot_dem = _hgt_rate_dem * CONSTANTS_ONE_G;
+ _SKEdot_dem = _integ5_state * _TAS_rate_dem;
+
+ // Calculate specific energy
+ _SPE_est = _integ3_state * CONSTANTS_ONE_G;
+ _SKE_est = 0.5f * _integ5_state * _integ5_state;
+
+ // Calculate specific energy rate
+ _SPEdot = _integ2_state * CONSTANTS_ONE_G;
+ _SKEdot = _integ5_state * _vel_dot;
+}
+
+void TECS::_update_throttle(float throttle_cruise, const math::Dcm &rotMat)
+{
+ // Calculate total energy values
+ _STE_error = _SPE_dem - _SPE_est + _SKE_dem - _SKE_est;
+ float STEdot_dem = constrain((_SPEdot_dem + _SKEdot_dem), _STEdot_min, _STEdot_max);
+ float STEdot_error = STEdot_dem - _SPEdot - _SKEdot;
+
+ // Apply 0.5 second first order filter to STEdot_error
+ // This is required to remove accelerometer noise from the measurement
+ STEdot_error = 0.2f * STEdot_error + 0.8f * _STEdotErrLast;
+ _STEdotErrLast = STEdot_error;
+
+ // Calculate throttle demand
+ // If underspeed condition is set, then demand full throttle
+ if (_underspeed) {
+ _throttle_dem_unc = 1.0f;
+
+ } else {
+ // Calculate gain scaler from specific energy error to throttle
+ float K_STE2Thr = 1 / (_timeConst * (_STEdot_max - _STEdot_min));
+
+ // Calculate feed-forward throttle
+ float ff_throttle = 0;
+ float nomThr = throttle_cruise;
+ // Use the demanded rate of change of total energy as the feed-forward demand, but add
+ // additional component which scales with (1/cos(bank angle) - 1) to compensate for induced
+ // drag increase during turns.
+ float cosPhi = sqrtf((rotMat(0, 1) * rotMat(0, 1)) + (rotMat(1, 1) * rotMat(1, 1)));
+ STEdot_dem = STEdot_dem + _rollComp * (1.0f / constrain(cosPhi * cosPhi , 0.1f, 1.0f) - 1.0f);
+
+ if (STEdot_dem >= 0) {
+ ff_throttle = nomThr + STEdot_dem / _STEdot_max * (1.0f - nomThr);
+
+ } else {
+ ff_throttle = nomThr - STEdot_dem / _STEdot_min * nomThr;
+ }
+
+ // Calculate PD + FF throttle
+ _throttle_dem = (_STE_error + STEdot_error * _thrDamp) * K_STE2Thr + ff_throttle;
+
+ // Rate limit PD + FF throttle
+ // Calculate the throttle increment from the specified slew time
+ if (fabsf(_throttle_slewrate) < 0.01f) {
+ float thrRateIncr = _DT * (_THRmaxf - _THRminf) * _throttle_slewrate;
+
+ _throttle_dem = constrain(_throttle_dem,
+ _last_throttle_dem - thrRateIncr,
+ _last_throttle_dem + thrRateIncr);
+ _last_throttle_dem = _throttle_dem;
+ }
+
+
+ // Calculate integrator state upper and lower limits
+ // Set to a value thqat will allow 0.1 (10%) throttle saturation to allow for noise on the demand
+ float integ_max = (_THRmaxf - _throttle_dem + 0.1f);
+ float integ_min = (_THRminf - _throttle_dem - 0.1f);
+
+ // Calculate integrator state, constraining state
+ // Set integrator to a max throttle value dduring climbout
+ _integ6_state = _integ6_state + (_STE_error * _integGain) * _DT * K_STE2Thr;
+
+ if (_climbOutDem) {
+ _integ6_state = integ_max;
+
+ } else {
+ _integ6_state = constrain(_integ6_state, integ_min, integ_max);
+ }
+
+ // Sum the components.
+ // Only use feed-forward component if airspeed is not being used
+ if (airspeed_sensor_enabled()) {
+ _throttle_dem = _throttle_dem + _integ6_state;
+
+ } else {
+ _throttle_dem = ff_throttle;
+ }
+ }
+
+ // Constrain throttle demand
+ _throttle_dem = constrain(_throttle_dem, _THRminf, _THRmaxf);
+}
+
+void TECS::_detect_bad_descent(void)
+{
+ // Detect a demanded airspeed too high for the aircraft to achieve. This will be
+ // evident by the the following conditions:
+ // 1) Underspeed protection not active
+ // 2) Specific total energy error > 200 (greater than ~20m height error)
+ // 3) Specific total energy reducing
+ // 4) throttle demand > 90%
+ // If these four conditions exist simultaneously, then the protection
+ // mode will be activated.
+ // Once active, the following condition are required to stay in the mode
+ // 1) Underspeed protection not active
+ // 2) Specific total energy error > 0
+ // This mode will produce an undulating speed and height response as it cuts in and out but will prevent the aircraft from descending into the ground if an unachievable speed demand is set
+ float STEdot = _SPEdot + _SKEdot;
+
+ if ((!_underspeed && (_STE_error > 200.0f) && (STEdot < 0.0f) && (_throttle_dem >= _THRmaxf * 0.9f)) || (_badDescent && !_underspeed && (_STE_error > 0.0f))) {
+ _badDescent = true;
+
+ } else {
+ _badDescent = false;
+ }
+}
+
+void TECS::_update_pitch(void)
+{
+ // Calculate Speed/Height Control Weighting
+ // This is used to determine how the pitch control prioritises speed and height control
+ // A weighting of 1 provides equal priority (this is the normal mode of operation)
+ // A SKE_weighting of 0 provides 100% priority to height control. This is used when no airspeed measurement is available
+ // A SKE_weighting of 2 provides 100% priority to speed control. This is used when an underspeed condition is detected
+ // or during takeoff/climbout where a minimum pitch angle is set to ensure height is gained. In this instance, if airspeed
+ // rises above the demanded value, the pitch angle will be increased by the TECS controller.
+ float SKE_weighting = constrain(_spdWeight, 0.0f, 2.0f);
+
+ if ((_underspeed || _climbOutDem) && airspeed_sensor_enabled()) {
+ SKE_weighting = 2.0f;
+
+ } else if (!airspeed_sensor_enabled()) {
+ SKE_weighting = 0.0f;
+ }
+
+ float SPE_weighting = 2.0f - SKE_weighting;
+
+ // Calculate Specific Energy Balance demand, and error
+ float SEB_dem = _SPE_dem * SPE_weighting - _SKE_dem * SKE_weighting;
+ float SEBdot_dem = _SPEdot_dem * SPE_weighting - _SKEdot_dem * SKE_weighting;
+ float SEB_error = SEB_dem - (_SPE_est * SPE_weighting - _SKE_est * SKE_weighting);
+ float SEBdot_error = SEBdot_dem - (_SPEdot * SPE_weighting - _SKEdot * SKE_weighting);
+
+ // Calculate integrator state, constraining input if pitch limits are exceeded
+ float integ7_input = SEB_error * _integGain;
+
+ if (_pitch_dem_unc > _PITCHmaxf) {
+ integ7_input = min(integ7_input, _PITCHmaxf - _pitch_dem_unc);
+
+ } else if (_pitch_dem_unc < _PITCHminf) {
+ integ7_input = max(integ7_input, _PITCHminf - _pitch_dem_unc);
+ }
+
+ _integ7_state = _integ7_state + integ7_input * _DT;
+
+ // Apply max and min values for integrator state that will allow for no more than
+ // 5deg of saturation. This allows for some pitch variation due to gusts before the
+ // integrator is clipped. Otherwise the effectiveness of the integrator will be reduced in turbulence
+ float gainInv = (_integ5_state * _timeConst * CONSTANTS_ONE_G);
+ float temp = SEB_error + SEBdot_error * _ptchDamp + SEBdot_dem * _timeConst;
+ _integ7_state = constrain(_integ7_state, (gainInv * (_PITCHminf - 0.0783f)) - temp, (gainInv * (_PITCHmaxf + 0.0783f)) - temp);
+
+ // Calculate pitch demand from specific energy balance signals
+ _pitch_dem_unc = (temp + _integ7_state) / gainInv;
+
+ // Constrain pitch demand
+ _pitch_dem = constrain(_pitch_dem_unc, _PITCHminf, _PITCHmaxf);
+
+ // Rate limit the pitch demand to comply with specified vertical
+ // acceleration limit
+ float ptchRateIncr = _DT * _vertAccLim / _integ5_state;
+
+ if ((_pitch_dem - _last_pitch_dem) > ptchRateIncr) {
+ _pitch_dem = _last_pitch_dem + ptchRateIncr;
+
+ } else if ((_pitch_dem - _last_pitch_dem) < -ptchRateIncr) {
+ _pitch_dem = _last_pitch_dem - ptchRateIncr;
+ }
+
+ _last_pitch_dem = _pitch_dem;
+}
+
+void TECS::_initialise_states(float pitch, float throttle_cruise, float baro_altitude, float ptchMinCO_rad)
+{
+ // Initialise states and variables if DT > 1 second or in climbout
+ if (_DT > 1.0f) {
+ _integ6_state = 0.0f;
+ _integ7_state = 0.0f;
+ _last_throttle_dem = throttle_cruise;
+ _last_pitch_dem = pitch;
+ _hgt_dem_adj_last = baro_altitude;
+ _hgt_dem_adj = _hgt_dem_adj_last;
+ _hgt_dem_prev = _hgt_dem_adj_last;
+ _hgt_dem_in_old = _hgt_dem_adj_last;
+ _TAS_dem_last = _TAS_dem;
+ _TAS_dem_adj = _TAS_dem;
+ _underspeed = false;
+ _badDescent = false;
+ _DT = 0.1f; // when first starting TECS, use a
+ // small time constant
+
+ } else if (_climbOutDem) {
+ _PITCHminf = ptchMinCO_rad;
+ _THRminf = _THRmaxf - 0.01f;
+ _hgt_dem_adj_last = baro_altitude;
+ _hgt_dem_adj = _hgt_dem_adj_last;
+ _hgt_dem_prev = _hgt_dem_adj_last;
+ _TAS_dem_last = _TAS_dem;
+ _TAS_dem_adj = _TAS_dem;
+ _underspeed = false;
+ _badDescent = false;
+ }
+}
+
+void TECS::_update_STE_rate_lim(void)
+{
+ // Calculate Specific Total Energy Rate Limits
+ // This is a tivial calculation at the moment but will get bigger once we start adding altitude effects
+ _STEdot_max = _maxClimbRate * CONSTANTS_ONE_G;
+ _STEdot_min = - _minSinkRate * CONSTANTS_ONE_G;
+}
+
+void TECS::update_pitch_throttle(const math::Dcm &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ float pitch_limit_min, float pitch_limit_max)
+{
+ // Calculate time in seconds since last update
+ uint64_t now = ecl_absolute_time();
+ _DT = max((now - _update_pitch_throttle_last_usec), 0ULL) * 1.0e-6f;
+ _update_pitch_throttle_last_usec = now;
+
+ // printf("tecs in: dt:%10.6f pitch: %6.2f baro_alt: %6.2f alt sp: %6.2f\neas sp: %6.2f eas: %6.2f, eas2tas: %6.2f\n %s pitch min C0: %6.2f thr min: %6.2f, thr max: %6.2f thr cruis: %6.2f pt min: %6.2f, pt max: %6.2f\n",
+ // _DT, pitch, baro_altitude, hgt_dem, EAS_dem, indicated_airspeed, EAS2TAS, (climbOutDem) ? "climb" : "level", ptchMinCO, throttle_min, throttle_max, throttle_cruise, pitch_limit_min, pitch_limit_max);
+
+ // Update the speed estimate using a 2nd order complementary filter
+ _update_speed(EAS_dem, indicated_airspeed, _indicated_airspeed_min, _indicated_airspeed_max, EAS2TAS);
+
+ // Convert inputs
+ _THRmaxf = throttle_max;
+ _THRminf = throttle_min;
+ _PITCHmaxf = pitch_limit_max;
+ _PITCHminf = pitch_limit_min;
+ _climbOutDem = climbOutDem;
+
+ // initialise selected states and variables if DT > 1 second or in climbout
+ _initialise_states(pitch, throttle_cruise, baro_altitude, ptchMinCO);
+
+ // Calculate Specific Total Energy Rate Limits
+ _update_STE_rate_lim();
+
+ // Calculate the speed demand
+ _update_speed_demand();
+
+ // Calculate the height demand
+ _update_height_demand(hgt_dem);
+
+ // Detect underspeed condition
+ _detect_underspeed();
+
+ // Calculate specific energy quantitiues
+ _update_energies();
+
+ // Calculate throttle demand
+ _update_throttle(throttle_cruise, rotMat);
+
+ // Detect bad descent due to demanded airspeed being too high
+ _detect_bad_descent();
+
+ // Calculate pitch demand
+ _update_pitch();
+
+// // Write internal variables to the log_tuning structure. This
+// // structure will be logged in dataflash at 10Hz
+ // log_tuning.hgt_dem = _hgt_dem_adj;
+ // log_tuning.hgt = _integ3_state;
+ // log_tuning.dhgt_dem = _hgt_rate_dem;
+ // log_tuning.dhgt = _integ2_state;
+ // log_tuning.spd_dem = _TAS_dem_adj;
+ // log_tuning.spd = _integ5_state;
+ // log_tuning.dspd = _vel_dot;
+ // log_tuning.ithr = _integ6_state;
+ // log_tuning.iptch = _integ7_state;
+ // log_tuning.thr = _throttle_dem;
+ // log_tuning.ptch = _pitch_dem;
+ // log_tuning.dspd_dem = _TAS_rate_dem;
+}
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
new file mode 100644
index 000000000..f8f832ed7
--- /dev/null
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -0,0 +1,357 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: t -*-
+
+/// @file tecs.h
+/// @brief Combined Total Energy Speed & Height Control.
+
+/*
+ * Written by Paul Riseborough 2013 to provide:
+ * - Combined control of speed and height using throttle to control
+ * total energy and pitch angle to control exchange of energy between
+ * potential and kinetic.
+ * Selectable speed or height priority modes when calculating pitch angle
+ * - Fallback mode when no airspeed measurement is available that
+ * sets throttle based on height rate demand and switches pitch angle control to
+ * height priority
+ * - Underspeed protection that demands maximum throttle switches pitch angle control
+ * to speed priority mode
+ * - Relative ease of tuning through use of intuitive time constant, trim rate and damping parameters and the use
+ * of easy to measure aircraft performance data
+ */
+
+#ifndef TECS_H
+#define TECS_H
+
+#include <mathlib/mathlib.h>
+#include <stdint.h>
+
+class __EXPORT TECS
+{
+public:
+ TECS() :
+
+ _airspeed_enabled(false),
+ _throttle_slewrate(0.0f),
+ _climbOutDem(false),
+ _hgt_dem_prev(0.0f),
+ _hgt_dem_adj_last(0.0f),
+ _hgt_dem_in_old(0.0f),
+ _TAS_dem_last(0.0f),
+ _TAS_dem_adj(0.0f),
+ _TAS_dem(0.0f),
+ _integ1_state(0.0f),
+ _integ2_state(0.0f),
+ _integ3_state(0.0f),
+ _integ4_state(0.0f),
+ _integ5_state(0.0f),
+ _integ6_state(0.0f),
+ _integ7_state(0.0f),
+ _pitch_dem(0.0f),
+ _last_pitch_dem(0.0f),
+ _SPE_dem(0.0f),
+ _SKE_dem(0.0f),
+ _SPEdot_dem(0.0f),
+ _SKEdot_dem(0.0f),
+ _SPE_est(0.0f),
+ _SKE_est(0.0f),
+ _SPEdot(0.0f),
+ _SKEdot(0.0f),
+ _vel_dot(0.0f),
+ _STEdotErrLast(0.0f) {
+
+ }
+
+ bool airspeed_sensor_enabled() {
+ return _airspeed_enabled;
+ }
+
+ void enable_airspeed(bool enabled) {
+ _airspeed_enabled = enabled;
+ }
+
+ // Update of the estimated height and height rate internal state
+ // Update of the inertial speed rate internal state
+ // Should be called at 50Hz or greater
+ void update_50hz(float baro_altitude, float airspeed, const math::Dcm &rotMat, const math::Vector3 &accel_body, const math::Vector3 &accel_earth);
+
+ // Update the control loop calculations
+ void update_pitch_throttle(const math::Dcm &rotMat, float pitch, float baro_altitude, float hgt_dem, float EAS_dem, float indicated_airspeed, float EAS2TAS, bool climbOutDem, float ptchMinCO,
+ float throttle_min, float throttle_max, float throttle_cruise,
+ float pitch_limit_min, float pitch_limit_max);
+ // demanded throttle in percentage
+ // should return 0 to 100
+ float get_throttle_demand(void) {
+ return _throttle_dem;
+ }
+ int32_t get_throttle_demand_percent(void) {
+ return get_throttle_demand();
+ }
+
+
+ float get_pitch_demand() { return _pitch_dem; }
+
+ // demanded pitch angle in centi-degrees
+ // should return between -9000 to +9000
+ int32_t get_pitch_demand_cd() { return int32_t(get_pitch_demand() * 5729.5781f);}
+
+ // Rate of change of velocity along X body axis in m/s^2
+ float get_VXdot(void) { return _vel_dot; }
+
+
+ float get_speed_weight() {
+ return _spdWeight;
+ }
+
+ // log data on internal state of the controller. Called at 10Hz
+ // void log_data(DataFlash_Class &dataflash, uint8_t msgid);
+
+ // struct PACKED log_TECS_Tuning {
+ // LOG_PACKET_HEADER;
+ // float hgt;
+ // float dhgt;
+ // float hgt_dem;
+ // float dhgt_dem;
+ // float spd_dem;
+ // float spd;
+ // float dspd;
+ // float ithr;
+ // float iptch;
+ // float thr;
+ // float ptch;
+ // float dspd_dem;
+ // } log_tuning;
+
+ void set_time_const(float time_const) {
+ _timeConst = time_const;
+ }
+
+ void set_min_sink_rate(float rate) {
+ _minSinkRate = rate;
+ }
+
+ void set_max_sink_rate(float sink_rate) {
+ _maxSinkRate = sink_rate;
+ }
+
+ void set_max_climb_rate(float climb_rate) {
+ _maxClimbRate = climb_rate;
+ }
+
+ void set_throttle_damp(float throttle_damp) {
+ _thrDamp = throttle_damp;
+ }
+
+ void set_integrator_gain(float gain) {
+ _integGain = gain;
+ }
+
+ void set_vertical_accel_limit(float limit) {
+ _vertAccLim = limit;
+ }
+
+ void set_height_comp_filter_omega(float omega) {
+ _hgtCompFiltOmega = omega;
+ }
+
+ void set_speed_comp_filter_omega(float omega) {
+ _spdCompFiltOmega = omega;
+ }
+
+ void set_roll_throttle_compensation(float compensation) {
+ _rollComp = compensation;
+ }
+
+ void set_speed_weight(float weight) {
+ _spdWeight = weight;
+ }
+
+ void set_pitch_damping(float damping) {
+ _ptchDamp = damping;
+ }
+
+ void set_throttle_slewrate(float slewrate) {
+ _throttle_slewrate = slewrate;
+ }
+
+ void set_indicated_airspeed_min(float airspeed) {
+ _indicated_airspeed_min = airspeed;
+ }
+
+ void set_indicated_airspeed_max(float airspeed) {
+ _indicated_airspeed_max = airspeed;
+ }
+
+private:
+ // Last time update_50Hz was called
+ uint64_t _update_50hz_last_usec;
+
+ // Last time update_speed was called
+ uint64_t _update_speed_last_usec;
+
+ // Last time update_pitch_throttle was called
+ uint64_t _update_pitch_throttle_last_usec;
+
+ // TECS tuning parameters
+ float _hgtCompFiltOmega;
+ float _spdCompFiltOmega;
+ float _maxClimbRate;
+ float _minSinkRate;
+ float _maxSinkRate;
+ float _timeConst;
+ float _ptchDamp;
+ float _thrDamp;
+ float _integGain;
+ float _vertAccLim;
+ float _rollComp;
+ float _spdWeight;
+
+ // throttle demand in the range from 0.0 to 1.0
+ float _throttle_dem;
+
+ // pitch angle demand in radians
+ float _pitch_dem;
+
+ // Integrator state 1 - height filter second derivative
+ float _integ1_state;
+
+ // Integrator state 2 - height rate
+ float _integ2_state;
+
+ // Integrator state 3 - height
+ float _integ3_state;
+
+ // Integrator state 4 - airspeed filter first derivative
+ float _integ4_state;
+
+ // Integrator state 5 - true airspeed
+ float _integ5_state;
+
+ // Integrator state 6 - throttle integrator
+ float _integ6_state;
+
+ // Integrator state 6 - pitch integrator
+ float _integ7_state;
+
+ // throttle demand rate limiter state
+ float _last_throttle_dem;
+
+ // pitch demand rate limiter state
+ float _last_pitch_dem;
+
+ // Rate of change of speed along X axis
+ float _vel_dot;
+
+ // Equivalent airspeed
+ float _EAS;
+
+ // True airspeed limits
+ float _TASmax;
+ float _TASmin;
+
+ // Current and last true airspeed demand
+ float _TAS_dem;
+ float _TAS_dem_last;
+
+ // Equivalent airspeed demand
+ float _EAS_dem;
+
+ // height demands
+ float _hgt_dem;
+ float _hgt_dem_in_old;
+ float _hgt_dem_adj;
+ float _hgt_dem_adj_last;
+ float _hgt_rate_dem;
+ float _hgt_dem_prev;
+
+ // Speed demand after application of rate limiting
+ // This is the demand tracked by the TECS control loops
+ float _TAS_dem_adj;
+
+ // Speed rate demand after application of rate limiting
+ // This is the demand tracked by the TECS control loops
+ float _TAS_rate_dem;
+
+ // Total energy rate filter state
+ float _STEdotErrLast;
+
+ // Underspeed condition
+ bool _underspeed;
+
+ // Bad descent condition caused by unachievable airspeed demand
+ bool _badDescent;
+
+ // climbout mode
+ bool _climbOutDem;
+
+ // throttle demand before limiting
+ float _throttle_dem_unc;
+
+ // pitch demand before limiting
+ float _pitch_dem_unc;
+
+ // Maximum and minimum specific total energy rate limits
+ float _STEdot_max;
+ float _STEdot_min;
+
+ // Maximum and minimum floating point throttle limits
+ float _THRmaxf;
+ float _THRminf;
+
+ // Maximum and minimum floating point pitch limits
+ float _PITCHmaxf;
+ float _PITCHminf;
+
+ // Specific energy quantities
+ float _SPE_dem;
+ float _SKE_dem;
+ float _SPEdot_dem;
+ float _SKEdot_dem;
+ float _SPE_est;
+ float _SKE_est;
+ float _SPEdot;
+ float _SKEdot;
+
+ // Specific energy error quantities
+ float _STE_error;
+
+ // Time since last update of main TECS loop (seconds)
+ float _DT;
+
+ bool _airspeed_enabled;
+ float _throttle_slewrate;
+ float _indicated_airspeed_min;
+ float _indicated_airspeed_max;
+
+ // Update the airspeed internal state using a second order complementary filter
+ void _update_speed(float airspeed_demand, float indicated_airspeed,
+ float indicated_airspeed_min, float indicated_airspeed_max, float EAS2TAS);
+
+ // Update the demanded airspeed
+ void _update_speed_demand(void);
+
+ // Update the demanded height
+ void _update_height_demand(float demand);
+
+ // Detect an underspeed condition
+ void _detect_underspeed(void);
+
+ // Update Specific Energy Quantities
+ void _update_energies(void);
+
+ // Update Demanded Throttle
+ void _update_throttle(float throttle_cruise, const math::Dcm &rotMat);
+
+ // Detect Bad Descent
+ void _detect_bad_descent(void);
+
+ // Update Demanded Pitch Angle
+ void _update_pitch(void);
+
+ // Initialise states and variables
+ void _initialise_states(float pitch, float throttle_cruise, float baro_altitude, float ptchMinCO_rad);
+
+ // Calculate specific total energy rate limits
+ void _update_STE_rate_lim(void);
+
+};
+
+#endif //TECS_H
diff --git a/src/lib/geo/geo.c b/src/lib/geo/geo.c
new file mode 100644
index 000000000..43105fdba
--- /dev/null
+++ b/src/lib/geo/geo.c
@@ -0,0 +1,468 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * 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 geo.c
+ *
+ * Geo / math functions to perform geodesic calculations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ */
+
+#include <geo/geo.h>
+#include <nuttx/config.h>
+#include <unistd.h>
+#include <pthread.h>
+#include <stdio.h>
+#include <math.h>
+#include <stdbool.h>
+
+
+/* values for map projection */
+static double phi_1;
+static double sin_phi_1;
+static double cos_phi_1;
+static double lambda_0;
+static double scale;
+
+__EXPORT void map_projection_init(double lat_0, double lon_0) //lat_0, lon_0 are expected to be in correct format: -> 47.1234567 and not 471234567
+{
+ /* notation and formulas according to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
+ phi_1 = lat_0 / 180.0 * M_PI;
+ lambda_0 = lon_0 / 180.0 * M_PI;
+
+ sin_phi_1 = sin(phi_1);
+ cos_phi_1 = cos(phi_1);
+
+ /* calculate local scale by using the relation of true distance and the distance on plane */ //TODO: this is a quick solution, there are probably easier ways to determine the scale
+
+ /* 1) calculate true distance d on sphere to a point: http://www.movable-type.co.uk/scripts/latlong.html */
+ const double r_earth = 6371000;
+
+ double lat1 = phi_1;
+ double lon1 = lambda_0;
+
+ double lat2 = phi_1 + 0.5 / 180 * M_PI;
+ double lon2 = lambda_0 + 0.5 / 180 * M_PI;
+ double sin_lat_2 = sin(lat2);
+ double cos_lat_2 = cos(lat2);
+ double d = acos(sin(lat1) * sin_lat_2 + cos(lat1) * cos_lat_2 * cos(lon2 - lon1)) * r_earth;
+
+ /* 2) calculate distance rho on plane */
+ double k_bar = 0;
+ double c = acos(sin_phi_1 * sin_lat_2 + cos_phi_1 * cos_lat_2 * cos(lon2 - lambda_0));
+
+ if (0 != c)
+ k_bar = c / sin(c);
+
+ double x2 = k_bar * (cos_lat_2 * sin(lon2 - lambda_0)); //Projection of point 2 on plane
+ double y2 = k_bar * ((cos_phi_1 * sin_lat_2 - sin_phi_1 * cos_lat_2 * cos(lon2 - lambda_0)));
+ double rho = sqrt(pow(x2, 2) + pow(y2, 2));
+
+ scale = d / rho;
+
+}
+
+__EXPORT void map_projection_project(double lat, double lon, float *x, float *y)
+{
+ /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
+ double phi = lat / 180.0 * M_PI;
+ double lambda = lon / 180.0 * M_PI;
+
+ double sin_phi = sin(phi);
+ double cos_phi = cos(phi);
+
+ double k_bar = 0;
+ /* using small angle approximation (formula in comment is without aproximation) */
+ double c = acos(sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2)); //double c = acos( sin_phi_1 * sin_phi + cos_phi_1 * cos_phi * cos(lambda - lambda_0) );
+
+ if (0 != c)
+ k_bar = c / sin(c);
+
+ /* using small angle approximation (formula in comment is without aproximation) */
+ *y = k_bar * (cos_phi * (lambda - lambda_0)) * scale;//*y = k_bar * (cos_phi * sin(lambda - lambda_0)) * scale;
+ *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * (1 - pow((lambda - lambda_0), 2) / 2))) * scale; // *x = k_bar * ((cos_phi_1 * sin_phi - sin_phi_1 * cos_phi * cos(lambda - lambda_0))) * scale;
+
+// printf("%phi_1=%.10f, lambda_0 =%.10f\n", phi_1, lambda_0);
+}
+
+__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon)
+{
+ /* notation and formulas accoring to: http://mathworld.wolfram.com/AzimuthalEquidistantProjection.html */
+
+ double x_descaled = x / scale;
+ double y_descaled = y / scale;
+
+ double c = sqrt(pow(x_descaled, 2) + pow(y_descaled, 2));
+ double sin_c = sin(c);
+ double cos_c = cos(c);
+
+ double lat_sphere = 0;
+
+ if (c != 0)
+ lat_sphere = asin(cos_c * sin_phi_1 + (x_descaled * sin_c * cos_phi_1) / c);
+ else
+ lat_sphere = asin(cos_c * sin_phi_1);
+
+// printf("lat_sphere = %.10f\n",lat_sphere);
+
+ double lon_sphere = 0;
+
+ if (phi_1 == M_PI / 2) {
+ //using small angle approximation (formula in comment is without aproximation)
+ lon_sphere = (lambda_0 - y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(-y_descaled, x_descaled));
+
+ } else if (phi_1 == -M_PI / 2) {
+ //using small angle approximation (formula in comment is without aproximation)
+ lon_sphere = (lambda_0 + y_descaled / x_descaled); //lon_sphere = (lambda_0 + atan2(y_descaled, x_descaled));
+
+ } else {
+
+ lon_sphere = (lambda_0 + atan2(y_descaled * sin_c , c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c));
+ //using small angle approximation
+// double denominator = (c * cos_phi_1 * cos_c - x_descaled * sin_phi_1 * sin_c);
+// if(denominator != 0)
+// {
+// lon_sphere = (lambda_0 + (y_descaled * sin_c) / denominator);
+// }
+// else
+// {
+// ...
+// }
+ }
+
+// printf("lon_sphere = %.10f\n",lon_sphere);
+
+ *lat = lat_sphere * 180.0 / M_PI;
+ *lon = lon_sphere * 180.0 / M_PI;
+
+}
+
+
+__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
+{
+ double lat_now_rad = lat_now / 180.0d * M_PI;
+ double lon_now_rad = lon_now / 180.0d * M_PI;
+ double lat_next_rad = lat_next / 180.0d * M_PI;
+ double lon_next_rad = lon_next / 180.0d * M_PI;
+
+
+ double d_lat = lat_next_rad - lat_now_rad;
+ double d_lon = lon_next_rad - lon_now_rad;
+
+ double a = sin(d_lat / 2.0d) * sin(d_lat / 2.0d) + sin(d_lon / 2.0d) * sin(d_lon / 2.0d) * cos(lat_now_rad) * cos(lat_next_rad);
+ double c = 2.0d * atan2(sqrt(a), sqrt(1.0d - a));
+
+ const double radius_earth = 6371000.0d;
+ return radius_earth * c;
+}
+
+__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next)
+{
+ double lat_now_rad = lat_now * M_DEG_TO_RAD;
+ double lon_now_rad = lon_now * M_DEG_TO_RAD;
+ double lat_next_rad = lat_next * M_DEG_TO_RAD;
+ double lon_next_rad = lon_next * M_DEG_TO_RAD;
+
+ double d_lat = lat_next_rad - lat_now_rad;
+ double d_lon = lon_next_rad - lon_now_rad;
+
+ /* conscious mix of double and float trig function to maximize speed and efficiency */
+ float theta = atan2f(sin(d_lon) * cos(lat_next_rad) , cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon));
+
+ theta = _wrap_pi(theta);
+
+ return theta;
+}
+
+__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float* vx, float* vy)
+{
+ double lat_now_rad = lat_now * M_DEG_TO_RAD;
+ double lon_now_rad = lon_now * M_DEG_TO_RAD;
+ double lat_next_rad = lat_next * M_DEG_TO_RAD;
+ double lon_next_rad = lon_next * M_DEG_TO_RAD;
+
+ double d_lat = lat_next_rad - lat_now_rad;
+ double d_lon = lon_next_rad - lon_now_rad;
+
+ /* conscious mix of double and float trig function to maximize speed and efficiency */
+ *vy = CONSTANTS_RADIUS_OF_EARTH * sin(d_lon) * cos(lat_next_rad);
+ *vx = CONSTANTS_RADIUS_OF_EARTH * cos(lat_now_rad) * sin(lat_next_rad) - sin(lat_now_rad) * cos(lat_next_rad) * cos(d_lon);
+}
+
+__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float* vx, float* vy)
+{
+ double lat_now_rad = lat_now * M_DEG_TO_RAD;
+ double lon_now_rad = lon_now * M_DEG_TO_RAD;
+ double lat_next_rad = lat_next * M_DEG_TO_RAD;
+ double lon_next_rad = lon_next * M_DEG_TO_RAD;
+
+ double d_lat = lat_next_rad - lat_now_rad;
+ double d_lon = lon_next_rad - lon_now_rad;
+
+ /* conscious mix of double and float trig function to maximize speed and efficiency */
+ *vy = CONSTANTS_RADIUS_OF_EARTH * d_lon;
+ *vx = CONSTANTS_RADIUS_OF_EARTH * cos(lat_now_rad);
+}
+
+// Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
+
+__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end)
+{
+// This function returns the distance to the nearest point on the track line. Distance is positive if current
+// position is right of the track and negative if left of the track as seen from a point on the track line
+// headed towards the end point.
+
+ float dist_to_end;
+ float bearing_end;
+ float bearing_track;
+ float bearing_diff;
+
+ int return_value = ERROR; // Set error flag, cleared when valid result calculated.
+ crosstrack_error->past_end = false;
+ crosstrack_error->distance = 0.0f;
+ crosstrack_error->bearing = 0.0f;
+
+ // Return error if arguments are bad
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_start == 0.0d || lon_start == 0.0d || lat_end == 0.0d || lon_end == 0.0d) return return_value;
+
+ bearing_end = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+ bearing_track = get_bearing_to_next_waypoint(lat_start, lon_start, lat_end, lon_end);
+ bearing_diff = bearing_track - bearing_end;
+ bearing_diff = _wrap_pi(bearing_diff);
+
+ // Return past_end = true if past end point of line
+ if (bearing_diff > M_PI_2_F || bearing_diff < -M_PI_2_F) {
+ crosstrack_error->past_end = true;
+ return_value = OK;
+ return return_value;
+ }
+
+ dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+ crosstrack_error->distance = (dist_to_end) * sin(bearing_diff);
+
+ if (sin(bearing_diff) >= 0) {
+ crosstrack_error->bearing = _wrap_pi(bearing_track - M_PI_2_F);
+
+ } else {
+ crosstrack_error->bearing = _wrap_pi(bearing_track + M_PI_2_F);
+ }
+
+ return_value = OK;
+
+ return return_value;
+
+}
+
+
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
+ float radius, float arc_start_bearing, float arc_sweep)
+{
+ // This function returns the distance to the nearest point on the track arc. Distance is positive if current
+ // position is right of the arc and negative if left of the arc as seen from the closest point on the arc and
+ // headed towards the end point.
+
+ // Determine if the current position is inside or outside the sector between the line from the center
+ // to the arc start and the line from the center to the arc end
+ float bearing_sector_start;
+ float bearing_sector_end;
+ float bearing_now = get_bearing_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
+ bool in_sector;
+
+ int return_value = ERROR; // Set error flag, cleared when valid result calculated.
+ crosstrack_error->past_end = false;
+ crosstrack_error->distance = 0.0f;
+ crosstrack_error->bearing = 0.0f;
+
+ // Return error if arguments are bad
+ if (lat_now == 0.0d || lon_now == 0.0d || lat_center == 0.0d || lon_center == 0.0d || radius == 0.0d) return return_value;
+
+
+ if (arc_sweep >= 0) {
+ bearing_sector_start = arc_start_bearing;
+ bearing_sector_end = arc_start_bearing + arc_sweep;
+
+ if (bearing_sector_end > 2.0f * M_PI_F) bearing_sector_end -= M_TWOPI_F;
+
+ } else {
+ bearing_sector_end = arc_start_bearing;
+ bearing_sector_start = arc_start_bearing - arc_sweep;
+
+ if (bearing_sector_start < 0.0f) bearing_sector_start += M_TWOPI_F;
+ }
+
+ in_sector = false;
+
+ // Case where sector does not span zero
+ if (bearing_sector_end >= bearing_sector_start && bearing_now >= bearing_sector_start && bearing_now <= bearing_sector_end) in_sector = true;
+
+ // Case where sector does span zero
+ if (bearing_sector_end < bearing_sector_start && (bearing_now > bearing_sector_start || bearing_now < bearing_sector_end)) in_sector = true;
+
+ // If in the sector then calculate distance and bearing to closest point
+ if (in_sector) {
+ crosstrack_error->past_end = false;
+ float dist_to_center = get_distance_to_next_waypoint(lat_now, lon_now, lat_center, lon_center);
+
+ if (dist_to_center <= radius) {
+ crosstrack_error->distance = radius - dist_to_center;
+ crosstrack_error->bearing = bearing_now + M_PI_F;
+
+ } else {
+ crosstrack_error->distance = dist_to_center - radius;
+ crosstrack_error->bearing = bearing_now;
+ }
+
+ // If out of the sector then calculate dist and bearing to start or end point
+
+ } else {
+
+ // Use the approximation that 111,111 meters in the y direction is 1 degree (of latitude)
+ // and 111,111 * cos(latitude) meters in the x direction is 1 degree (of longitude) to
+ // calculate the position of the start and end points. We should not be doing this often
+ // as this function generally will not be called repeatedly when we are out of the sector.
+
+ // TO DO - this is messed up and won't compile
+ float start_disp_x = radius * sin(arc_start_bearing);
+ float start_disp_y = radius * cos(arc_start_bearing);
+ float end_disp_x = radius * sin(_wrapPI(arc_start_bearing + arc_sweep));
+ float end_disp_y = radius * cos(_wrapPI(arc_start_bearing + arc_sweep));
+ float lon_start = lon_now + start_disp_x / 111111.0d;
+ float lat_start = lat_now + start_disp_y * cos(lat_now) / 111111.0d;
+ float lon_end = lon_now + end_disp_x / 111111.0d;
+ float lat_end = lat_now + end_disp_y * cos(lat_now) / 111111.0d;
+ float dist_to_start = get_distance_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
+ float dist_to_end = get_distance_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+
+
+ if (dist_to_start < dist_to_end) {
+ crosstrack_error->distance = dist_to_start;
+ crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_start, lon_start);
+
+ } else {
+ crosstrack_error->past_end = true;
+ crosstrack_error->distance = dist_to_end;
+ crosstrack_error->bearing = get_bearing_to_next_waypoint(lat_now, lon_now, lat_end, lon_end);
+ }
+
+ }
+
+ crosstrack_error->bearing = _wrapPI(crosstrack_error->bearing);
+ return_value = OK;
+ return return_value;
+}
+
+__EXPORT float _wrap_pi(float bearing)
+{
+ /* value is inf or NaN */
+ if (!isfinite(bearing) || bearing == 0) {
+ return bearing;
+ }
+
+ int c = 0;
+
+ while (bearing > M_PI_F && c < 30) {
+ bearing -= M_TWOPI_F;
+ c++;
+ }
+
+ c = 0;
+
+ while (bearing <= -M_PI_F && c < 30) {
+ bearing += M_TWOPI_F;
+ c++;
+ }
+
+ return bearing;
+}
+
+__EXPORT float _wrap_2pi(float bearing)
+{
+ /* value is inf or NaN */
+ if (!isfinite(bearing)) {
+ return bearing;
+ }
+
+ while (bearing >= M_TWOPI_F) {
+ bearing = bearing - M_TWOPI_F;
+ }
+
+ while (bearing < 0.0f) {
+ bearing = bearing + M_TWOPI_F;
+ }
+
+ return bearing;
+}
+
+__EXPORT float _wrap_180(float bearing)
+{
+ /* value is inf or NaN */
+ if (!isfinite(bearing)) {
+ return bearing;
+ }
+
+ while (bearing > 180.0f) {
+ bearing = bearing - 360.0f;
+ }
+
+ while (bearing <= -180.0f) {
+ bearing = bearing + 360.0f;
+ }
+
+ return bearing;
+}
+
+__EXPORT float _wrap_360(float bearing)
+{
+ /* value is inf or NaN */
+ if (!isfinite(bearing)) {
+ return bearing;
+ }
+
+ while (bearing >= 360.0f) {
+ bearing = bearing - 360.0f;
+ }
+
+ while (bearing < 0.0f) {
+ bearing = bearing + 360.0f;
+ }
+
+ return bearing;
+}
+
+
diff --git a/src/lib/geo/geo.h b/src/lib/geo/geo.h
new file mode 100644
index 000000000..123ff80f1
--- /dev/null
+++ b/src/lib/geo/geo.h
@@ -0,0 +1,129 @@
+/****************************************************************************
+ *
+ * Copyright (C) 2012 PX4 Development Team. All rights reserved.
+ * Author: Thomas Gubler <thomasgubler@student.ethz.ch>
+ * Julian Oes <joes@student.ethz.ch>
+ * 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 geo.h
+ *
+ * Definition of geo / math functions to perform geodesic calculations
+ *
+ * @author Thomas Gubler <thomasgubler@student.ethz.ch>
+ * @author Julian Oes <joes@student.ethz.ch>
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * Additional functions - @author Doug Weibel <douglas.weibel@colorado.edu>
+ */
+
+#pragma once
+
+__BEGIN_DECLS
+
+#include <stdbool.h>
+
+#define CONSTANTS_ONE_G 9.80665f /* m/s^2 */
+#define CONSTANTS_AIR_DENSITY_SEA_LEVEL_15C 1.225f /* kg/m^3 */
+#define CONSTANTS_AIR_GAS_CONST 287.1f /* J/(kg * K) */
+#define CONSTANTS_ABSOLUTE_NULL_CELSIUS -273.15f /* °C */
+#define CONSTANTS_RADIUS_OF_EARTH 6371000 /* meters (m) */
+
+// XXX remove
+struct crosstrack_error_s {
+ bool past_end; // Flag indicating we are past the end of the line/arc segment
+ float distance; // Distance in meters to closest point on line/arc
+ float bearing; // Bearing in radians to closest point on line/arc
+} ;
+
+/**
+ * Initializes the map transformation.
+ *
+ * Initializes the transformation between the geographic coordinate system and the azimuthal equidistant plane
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT void map_projection_init(double lat_0, double lon_0);
+
+/**
+ * Transforms a point in the geographic coordinate system to the local azimuthal equidistant plane
+ * @param x north
+ * @param y east
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT void map_projection_project(double lat, double lon, float *x, float *y);
+
+/**
+ * Transforms a point in the local azimuthal equidistant plane to the geographic coordinate system
+ *
+ * @param x north
+ * @param y east
+ * @param lat in degrees (47.1234567°, not 471234567°)
+ * @param lon in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT void map_projection_reproject(float x, float y, double *lat, double *lon);
+
+/**
+ * Returns the distance to the next waypoint in meters.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT float get_distance_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+
+/**
+ * Returns the bearing to the next waypoint in radians.
+ *
+ * @param lat_now current position in degrees (47.1234567°, not 471234567°)
+ * @param lon_now current position in degrees (8.1234567°, not 81234567°)
+ * @param lat_next next waypoint position in degrees (47.1234567°, not 471234567°)
+ * @param lon_next next waypoint position in degrees (8.1234567°, not 81234567°)
+ */
+__EXPORT float get_bearing_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next);
+
+__EXPORT void get_vector_to_next_waypoint(double lat_now, double lon_now, double lat_next, double lon_next, float* vx, float* vy);
+
+__EXPORT void get_vector_to_next_waypoint_fast(double lat_now, double lon_now, double lat_next, double lon_next, float* vx, float* vy);
+
+__EXPORT int get_distance_to_line(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_start, double lon_start, double lat_end, double lon_end);
+
+__EXPORT int get_distance_to_arc(struct crosstrack_error_s * crosstrack_error, double lat_now, double lon_now, double lat_center, double lon_center,
+ float radius, float arc_start_bearing, float arc_sweep);
+
+__EXPORT float _wrap_180(float bearing);
+__EXPORT float _wrap_360(float bearing);
+__EXPORT float _wrap_pi(float bearing);
+__EXPORT float _wrap_2pi(float bearing);
+
+__END_DECLS
diff --git a/src/lib/geo/module.mk b/src/lib/geo/module.mk
new file mode 100644
index 000000000..30a2dc99f
--- /dev/null
+++ b/src/lib/geo/module.mk
@@ -0,0 +1,38 @@
+############################################################################
+#
+# 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.
+#
+############################################################################
+
+#
+# Geo library
+#
+
+SRCS = geo.c
diff --git a/src/lib/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h b/src/lib/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h
new file mode 100644
index 000000000..8f39acd9d
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Device/ARM/ARMCM3/Include/ARMCM3.h
@@ -0,0 +1,264 @@
+/**************************************************************************//**
+ * @file ARMCM3.h
+ * @brief CMSIS Core Peripheral Access Layer Header File for
+ * ARMCM3 Device Series
+ * @version V1.07
+ * @date 30. January 2012
+ *
+ * @note
+ * Copyright (C) 2012 ARM Limited. All rights reserved.
+ *
+ * @par
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M
+ * processor based microcontrollers. This file can be freely distributed
+ * within development tools that are supporting such ARM based processors.
+ *
+ * @par
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
+ *
+ ******************************************************************************/
+
+#ifndef ARMCM3_H
+#define ARMCM3_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/* ------------------------- Interrupt Number Definition ------------------------ */
+
+typedef enum IRQn
+{
+/* ------------------- Cortex-M3 Processor Exceptions Numbers ------------------- */
+ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
+ HardFault_IRQn = -13, /*!< 3 HardFault Interrupt */
+ MemoryManagement_IRQn = -12, /*!< 4 Memory Management Interrupt */
+ BusFault_IRQn = -11, /*!< 5 Bus Fault Interrupt */
+ UsageFault_IRQn = -10, /*!< 6 Usage Fault Interrupt */
+ SVCall_IRQn = -5, /*!< 11 SV Call Interrupt */
+ DebugMonitor_IRQn = -4, /*!< 12 Debug Monitor Interrupt */
+ PendSV_IRQn = -2, /*!< 14 Pend SV Interrupt */
+ SysTick_IRQn = -1, /*!< 15 System Tick Interrupt */
+
+/* ---------------------- ARMCM3 Specific Interrupt Numbers --------------------- */
+ WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
+ RTC_IRQn = 1, /*!< Real Time Clock Interrupt */
+ TIM0_IRQn = 2, /*!< Timer0 / Timer1 Interrupt */
+ TIM2_IRQn = 3, /*!< Timer2 / Timer3 Interrupt */
+ MCIA_IRQn = 4, /*!< MCIa Interrupt */
+ MCIB_IRQn = 5, /*!< MCIb Interrupt */
+ UART0_IRQn = 6, /*!< UART0 Interrupt */
+ UART1_IRQn = 7, /*!< UART1 Interrupt */
+ UART2_IRQn = 8, /*!< UART2 Interrupt */
+ UART4_IRQn = 9, /*!< UART4 Interrupt */
+ AACI_IRQn = 10, /*!< AACI / AC97 Interrupt */
+ CLCD_IRQn = 11, /*!< CLCD Combined Interrupt */
+ ENET_IRQn = 12, /*!< Ethernet Interrupt */
+ USBDC_IRQn = 13, /*!< USB Device Interrupt */
+ USBHC_IRQn = 14, /*!< USB Host Controller Interrupt */
+ CHLCD_IRQn = 15, /*!< Character LCD Interrupt */
+ FLEXRAY_IRQn = 16, /*!< Flexray Interrupt */
+ CAN_IRQn = 17, /*!< CAN Interrupt */
+ LIN_IRQn = 18, /*!< LIN Interrupt */
+ I2C_IRQn = 19, /*!< I2C ADC/DAC Interrupt */
+ CPU_CLCD_IRQn = 28, /*!< CPU CLCD Combined Interrupt */
+ UART3_IRQn = 30, /*!< UART3 Interrupt */
+ SPI_IRQn = 31, /*!< SPI Touchscreen Interrupt */
+} IRQn_Type;
+
+
+/* ================================================================================ */
+/* ================ Processor and Core Peripheral Section ================ */
+/* ================================================================================ */
+
+/* -------- Configuration of the Cortex-M4 Processor and Core Peripherals ------- */
+#define __CM3_REV 0x0201 /*!< Core revision r2p1 */
+#define __MPU_PRESENT 1 /*!< MPU present or not */
+#define __NVIC_PRIO_BITS 3 /*!< Number of Bits used for Priority Levels */
+#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
+
+#include <core_cm3.h> /* Processor and core peripherals */
+/* NuttX */
+//#include "system_ARMCM3.h" /* System Header */
+
+
+/* ================================================================================ */
+/* ================ Device Specific Peripheral Section ================ */
+/* ================================================================================ */
+
+/* ------------------- Start of section using anonymous unions ------------------ */
+#if defined(__CC_ARM)
+ #pragma push
+ #pragma anon_unions
+#elif defined(__ICCARM__)
+ #pragma language=extended
+#elif defined(__GNUC__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TMS470__)
+/* anonymous unions are enabled by default */
+#elif defined(__TASKING__)
+ #pragma warning 586
+#else
+ #warning Not supported compiler type
+#endif
+
+
+
+/* ================================================================================ */
+/* ================ CPU FPGA System (CPU_SYS) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
+ __IO uint32_t MEMCFG; /* Offset: 0x004 (R/W) Remap and Alias Memory Control */
+ __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
+ __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
+ __I uint32_t TS; /* Offset: 0x010 (R/ ) Touchscreen Register */
+ __IO uint32_t CTRL1; /* Offset: 0x014 (R/W) Misc Control Functions */
+ uint32_t RESERVED0[2];
+ __IO uint32_t CLKCFG; /* Offset: 0x020 (R/W) System Clock Configuration */
+ __IO uint32_t WSCFG; /* Offset: 0x024 (R/W) Flash Waitstate Configuration */
+ __IO uint32_t CPUCFG; /* Offset: 0x028 (R/W) Processor Configuration */
+ uint32_t RESERVED1[3];
+ __IO uint32_t BASE; /* Offset: 0x038 (R/W) ROM Table base Address */
+ __IO uint32_t ID2; /* Offset: 0x03C (R/W) Secondary Identification Register */
+} ARM_CPU_SYS_TypeDef;
+
+
+/* ================================================================================ */
+/* ================ DUT FPGA System (DUT_SYS) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
+ __IO uint32_t PERCFG; /* Offset: 0x004 (R/W) Peripheral Control Signals */
+ __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
+ __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
+ __IO uint32_t SEG7; /* Offset: 0x010 (R/W) 7-segment LED Output States */
+ __I uint32_t CNT25MHz; /* Offset: 0x014 (R/ ) Freerunning counter incrementing at 25MHz */
+ __I uint32_t CNT100Hz; /* Offset: 0x018 (R/ ) Freerunning counter incrementing at 100Hz */
+} ARM_DUT_SYS_TypeDef;
+
+
+/* ================================================================================ */
+/* ================ Timer (TIM) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __IO uint32_t Timer1Load; /* Offset: 0x000 (R/W) Timer 1 Load */
+ __I uint32_t Timer1Value; /* Offset: 0x004 (R/ ) Timer 1 Counter Current Value */
+ __IO uint32_t Timer1Control; /* Offset: 0x008 (R/W) Timer 1 Control */
+ __O uint32_t Timer1IntClr; /* Offset: 0x00C ( /W) Timer 1 Interrupt Clear */
+ __I uint32_t Timer1RIS; /* Offset: 0x010 (R/ ) Timer 1 Raw Interrupt Status */
+ __I uint32_t Timer1MIS; /* Offset: 0x014 (R/ ) Timer 1 Masked Interrupt Status */
+ __IO uint32_t Timer1BGLoad; /* Offset: 0x018 (R/W) Background Load Register */
+ uint32_t RESERVED0[1];
+ __IO uint32_t Timer2Load; /* Offset: 0x020 (R/W) Timer 2 Load */
+ __I uint32_t Timer2Value; /* Offset: 0x024 (R/ ) Timer 2 Counter Current Value */
+ __IO uint32_t Timer2Control; /* Offset: 0x028 (R/W) Timer 2 Control */
+ __O uint32_t Timer2IntClr; /* Offset: 0x02C ( /W) Timer 2 Interrupt Clear */
+ __I uint32_t Timer2RIS; /* Offset: 0x030 (R/ ) Timer 2 Raw Interrupt Status */
+ __I uint32_t Timer2MIS; /* Offset: 0x034 (R/ ) Timer 2 Masked Interrupt Status */
+ __IO uint32_t Timer2BGLoad; /* Offset: 0x038 (R/W) Background Load Register */
+} ARM_TIM_TypeDef;
+
+
+/* ================================================================================ */
+/* ============== Universal Asyncronous Receiver / Transmitter (UART) ============= */
+/* ================================================================================ */
+typedef struct
+{
+ __IO uint32_t DR; /* Offset: 0x000 (R/W) Data */
+ union {
+ __I uint32_t RSR; /* Offset: 0x000 (R/ ) Receive Status */
+ __O uint32_t ECR; /* Offset: 0x000 ( /W) Error Clear */
+ };
+ uint32_t RESERVED0[4];
+ __IO uint32_t FR; /* Offset: 0x018 (R/W) Flags */
+ uint32_t RESERVED1[1];
+ __IO uint32_t ILPR; /* Offset: 0x020 (R/W) IrDA Low-power Counter */
+ __IO uint32_t IBRD; /* Offset: 0x024 (R/W) Interger Baud Rate */
+ __IO uint32_t FBRD; /* Offset: 0x028 (R/W) Fractional Baud Rate */
+ __IO uint32_t LCR_H; /* Offset: 0x02C (R/W) Line Control */
+ __IO uint32_t CR; /* Offset: 0x030 (R/W) Control */
+ __IO uint32_t IFLS; /* Offset: 0x034 (R/W) Interrupt FIFO Level Select */
+ __IO uint32_t IMSC; /* Offset: 0x038 (R/W) Interrupt Mask Set / Clear */
+ __IO uint32_t RIS; /* Offset: 0x03C (R/W) Raw Interrupt Status */
+ __IO uint32_t MIS; /* Offset: 0x040 (R/W) Masked Interrupt Status */
+ __O uint32_t ICR; /* Offset: 0x044 ( /W) Interrupt Clear */
+ __IO uint32_t DMACR; /* Offset: 0x048 (R/W) DMA Control */
+} ARM_UART_TypeDef;
+
+
+/* -------------------- End of section using anonymous unions ------------------- */
+#if defined(__CC_ARM)
+ #pragma pop
+#elif defined(__ICCARM__)
+ /* leave anonymous unions enabled */
+#elif defined(__GNUC__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TMS470__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TASKING__)
+ #pragma warning restore
+#else
+ #warning Not supported compiler type
+#endif
+
+
+
+
+/* ================================================================================ */
+/* ================ Peripheral memory map ================ */
+/* ================================================================================ */
+/* -------------------------- CPU FPGA memory map ------------------------------- */
+#define ARM_FLASH_BASE (0x00000000UL)
+#define ARM_RAM_BASE (0x20000000UL)
+#define ARM_RAM_FPGA_BASE (0x1EFF0000UL)
+#define ARM_CPU_CFG_BASE (0xDFFF0000UL)
+
+#define ARM_CPU_SYS_BASE (ARM_CPU_CFG_BASE + 0x00000)
+#define ARM_UART3_BASE (ARM_CPU_CFG_BASE + 0x05000)
+
+/* -------------------------- DUT FPGA memory map ------------------------------- */
+#define ARM_APB_BASE (0x40000000UL)
+#define ARM_AHB_BASE (0x4FF00000UL)
+#define ARM_DMC_BASE (0x60000000UL)
+#define ARM_SMC_BASE (0xA0000000UL)
+
+#define ARM_TIM0_BASE (ARM_APB_BASE + 0x02000)
+#define ARM_TIM2_BASE (ARM_APB_BASE + 0x03000)
+#define ARM_DUT_SYS_BASE (ARM_APB_BASE + 0x04000)
+#define ARM_UART0_BASE (ARM_APB_BASE + 0x06000)
+#define ARM_UART1_BASE (ARM_APB_BASE + 0x07000)
+#define ARM_UART2_BASE (ARM_APB_BASE + 0x08000)
+#define ARM_UART4_BASE (ARM_APB_BASE + 0x09000)
+
+
+/* ================================================================================ */
+/* ================ Peripheral declaration ================ */
+/* ================================================================================ */
+/* -------------------------- CPU FPGA Peripherals ------------------------------ */
+#define ARM_CPU_SYS ((ARM_CPU_SYS_TypeDef *) ARM_CPU_SYS_BASE)
+#define ARM_UART3 (( ARM_UART_TypeDef *) ARM_UART3_BASE)
+
+/* -------------------------- DUT FPGA Peripherals ------------------------------ */
+#define ARM_DUT_SYS ((ARM_DUT_SYS_TypeDef *) ARM_DUT_SYS_BASE)
+#define ARM_TIM0 (( ARM_TIM_TypeDef *) ARM_TIM0_BASE)
+#define ARM_TIM2 (( ARM_TIM_TypeDef *) ARM_TIM2_BASE)
+#define ARM_UART0 (( ARM_UART_TypeDef *) ARM_UART0_BASE)
+#define ARM_UART1 (( ARM_UART_TypeDef *) ARM_UART1_BASE)
+#define ARM_UART2 (( ARM_UART_TypeDef *) ARM_UART2_BASE)
+#define ARM_UART4 (( ARM_UART_TypeDef *) ARM_UART4_BASE)
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ARMCM3_H */
diff --git a/src/lib/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h b/src/lib/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h
new file mode 100644
index 000000000..181b7e433
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Device/ARM/ARMCM4/Include/ARMCM4.h
@@ -0,0 +1,265 @@
+/**************************************************************************//**
+ * @file ARMCM4.h
+ * @brief CMSIS Core Peripheral Access Layer Header File for
+ * ARMCM4 Device Series
+ * @version V1.07
+ * @date 30. January 2012
+ *
+ * @note
+ * Copyright (C) 2012 ARM Limited. All rights reserved.
+ *
+ * @par
+ * ARM Limited (ARM) is supplying this software for use with Cortex-M
+ * processor based microcontrollers. This file can be freely distributed
+ * within development tools that are supporting such ARM based processors.
+ *
+ * @par
+ * THIS SOFTWARE IS PROVIDED "AS IS". NO WARRANTIES, WHETHER EXPRESS, IMPLIED
+ * OR STATUTORY, INCLUDING, BUT NOT LIMITED TO, IMPLIED WARRANTIES OF
+ * MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE APPLY TO THIS SOFTWARE.
+ * ARM SHALL NOT, IN ANY CIRCUMSTANCES, BE LIABLE FOR SPECIAL, INCIDENTAL, OR
+ * CONSEQUENTIAL DAMAGES, FOR ANY REASON WHATSOEVER.
+ *
+ ******************************************************************************/
+
+#ifndef ARMCM4_H
+#define ARMCM4_H
+
+#ifdef __cplusplus
+extern "C" {
+#endif
+
+
+/* ------------------------- Interrupt Number Definition ------------------------ */
+
+typedef enum IRQn
+{
+/* ------------------- Cortex-M4 Processor Exceptions Numbers ------------------- */
+ NonMaskableInt_IRQn = -14, /*!< 2 Non Maskable Interrupt */
+ HardFault_IRQn = -13, /*!< 3 HardFault Interrupt */
+ MemoryManagement_IRQn = -12, /*!< 4 Memory Management Interrupt */
+ BusFault_IRQn = -11, /*!< 5 Bus Fault Interrupt */
+ UsageFault_IRQn = -10, /*!< 6 Usage Fault Interrupt */
+ SVCall_IRQn = -5, /*!< 11 SV Call Interrupt */
+ DebugMonitor_IRQn = -4, /*!< 12 Debug Monitor Interrupt */
+ PendSV_IRQn = -2, /*!< 14 Pend SV Interrupt */
+ SysTick_IRQn = -1, /*!< 15 System Tick Interrupt */
+
+/* ---------------------- ARMCM4 Specific Interrupt Numbers --------------------- */
+ WDT_IRQn = 0, /*!< Watchdog Timer Interrupt */
+ RTC_IRQn = 1, /*!< Real Time Clock Interrupt */
+ TIM0_IRQn = 2, /*!< Timer0 / Timer1 Interrupt */
+ TIM2_IRQn = 3, /*!< Timer2 / Timer3 Interrupt */
+ MCIA_IRQn = 4, /*!< MCIa Interrupt */
+ MCIB_IRQn = 5, /*!< MCIb Interrupt */
+ UART0_IRQn = 6, /*!< UART0 Interrupt */
+ UART1_IRQn = 7, /*!< UART1 Interrupt */
+ UART2_IRQn = 8, /*!< UART2 Interrupt */
+ UART4_IRQn = 9, /*!< UART4 Interrupt */
+ AACI_IRQn = 10, /*!< AACI / AC97 Interrupt */
+ CLCD_IRQn = 11, /*!< CLCD Combined Interrupt */
+ ENET_IRQn = 12, /*!< Ethernet Interrupt */
+ USBDC_IRQn = 13, /*!< USB Device Interrupt */
+ USBHC_IRQn = 14, /*!< USB Host Controller Interrupt */
+ CHLCD_IRQn = 15, /*!< Character LCD Interrupt */
+ FLEXRAY_IRQn = 16, /*!< Flexray Interrupt */
+ CAN_IRQn = 17, /*!< CAN Interrupt */
+ LIN_IRQn = 18, /*!< LIN Interrupt */
+ I2C_IRQn = 19, /*!< I2C ADC/DAC Interrupt */
+ CPU_CLCD_IRQn = 28, /*!< CPU CLCD Combined Interrupt */
+ UART3_IRQn = 30, /*!< UART3 Interrupt */
+ SPI_IRQn = 31, /*!< SPI Touchscreen Interrupt */
+} IRQn_Type;
+
+
+/* ================================================================================ */
+/* ================ Processor and Core Peripheral Section ================ */
+/* ================================================================================ */
+
+/* -------- Configuration of the Cortex-M4 Processor and Core Peripherals ------- */
+#define __CM4_REV 0x0001 /*!< Core revision r0p1 */
+#define __MPU_PRESENT 1 /*!< MPU present or not */
+#define __NVIC_PRIO_BITS 3 /*!< Number of Bits used for Priority Levels */
+#define __Vendor_SysTickConfig 0 /*!< Set to 1 if different SysTick Config is used */
+#define __FPU_PRESENT 1 /*!< FPU present or not */
+
+#include <core_cm4.h> /* Processor and core peripherals */
+/* NuttX */
+//#include "system_ARMCM4.h" /* System Header */
+
+
+/* ================================================================================ */
+/* ================ Device Specific Peripheral Section ================ */
+/* ================================================================================ */
+
+/* ------------------- Start of section using anonymous unions ------------------ */
+#if defined(__CC_ARM)
+ #pragma push
+ #pragma anon_unions
+#elif defined(__ICCARM__)
+ #pragma language=extended
+#elif defined(__GNUC__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TMS470__)
+/* anonymous unions are enabled by default */
+#elif defined(__TASKING__)
+ #pragma warning 586
+#else
+ #warning Not supported compiler type
+#endif
+
+
+
+/* ================================================================================ */
+/* ================ CPU FPGA System (CPU_SYS) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
+ __IO uint32_t MEMCFG; /* Offset: 0x004 (R/W) Remap and Alias Memory Control */
+ __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
+ __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
+ __I uint32_t TS; /* Offset: 0x010 (R/ ) Touchscreen Register */
+ __IO uint32_t CTRL1; /* Offset: 0x014 (R/W) Misc Control Functions */
+ uint32_t RESERVED0[2];
+ __IO uint32_t CLKCFG; /* Offset: 0x020 (R/W) System Clock Configuration */
+ __IO uint32_t WSCFG; /* Offset: 0x024 (R/W) Flash Waitstate Configuration */
+ __IO uint32_t CPUCFG; /* Offset: 0x028 (R/W) Processor Configuration */
+ uint32_t RESERVED1[3];
+ __IO uint32_t BASE; /* Offset: 0x038 (R/W) ROM Table base Address */
+ __IO uint32_t ID2; /* Offset: 0x03C (R/W) Secondary Identification Register */
+} ARM_CPU_SYS_TypeDef;
+
+
+/* ================================================================================ */
+/* ================ DUT FPGA System (DUT_SYS) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __I uint32_t ID; /* Offset: 0x000 (R/ ) Board and FPGA Identifier */
+ __IO uint32_t PERCFG; /* Offset: 0x004 (R/W) Peripheral Control Signals */
+ __I uint32_t SW; /* Offset: 0x008 (R/ ) Switch States */
+ __IO uint32_t LED; /* Offset: 0x00C (R/W) LED Output States */
+ __IO uint32_t SEG7; /* Offset: 0x010 (R/W) 7-segment LED Output States */
+ __I uint32_t CNT25MHz; /* Offset: 0x014 (R/ ) Freerunning counter incrementing at 25MHz */
+ __I uint32_t CNT100Hz; /* Offset: 0x018 (R/ ) Freerunning counter incrementing at 100Hz */
+} ARM_DUT_SYS_TypeDef;
+
+
+/* ================================================================================ */
+/* ================ Timer (TIM) ================ */
+/* ================================================================================ */
+typedef struct
+{
+ __IO uint32_t Timer1Load; /* Offset: 0x000 (R/W) Timer 1 Load */
+ __I uint32_t Timer1Value; /* Offset: 0x004 (R/ ) Timer 1 Counter Current Value */
+ __IO uint32_t Timer1Control; /* Offset: 0x008 (R/W) Timer 1 Control */
+ __O uint32_t Timer1IntClr; /* Offset: 0x00C ( /W) Timer 1 Interrupt Clear */
+ __I uint32_t Timer1RIS; /* Offset: 0x010 (R/ ) Timer 1 Raw Interrupt Status */
+ __I uint32_t Timer1MIS; /* Offset: 0x014 (R/ ) Timer 1 Masked Interrupt Status */
+ __IO uint32_t Timer1BGLoad; /* Offset: 0x018 (R/W) Background Load Register */
+ uint32_t RESERVED0[1];
+ __IO uint32_t Timer2Load; /* Offset: 0x020 (R/W) Timer 2 Load */
+ __I uint32_t Timer2Value; /* Offset: 0x024 (R/ ) Timer 2 Counter Current Value */
+ __IO uint32_t Timer2Control; /* Offset: 0x028 (R/W) Timer 2 Control */
+ __O uint32_t Timer2IntClr; /* Offset: 0x02C ( /W) Timer 2 Interrupt Clear */
+ __I uint32_t Timer2RIS; /* Offset: 0x030 (R/ ) Timer 2 Raw Interrupt Status */
+ __I uint32_t Timer2MIS; /* Offset: 0x034 (R/ ) Timer 2 Masked Interrupt Status */
+ __IO uint32_t Timer2BGLoad; /* Offset: 0x038 (R/W) Background Load Register */
+} ARM_TIM_TypeDef;
+
+
+/* ================================================================================ */
+/* ============== Universal Asyncronous Receiver / Transmitter (UART) ============= */
+/* ================================================================================ */
+typedef struct
+{
+ __IO uint32_t DR; /* Offset: 0x000 (R/W) Data */
+ union {
+ __I uint32_t RSR; /* Offset: 0x000 (R/ ) Receive Status */
+ __O uint32_t ECR; /* Offset: 0x000 ( /W) Error Clear */
+ };
+ uint32_t RESERVED0[4];
+ __IO uint32_t FR; /* Offset: 0x018 (R/W) Flags */
+ uint32_t RESERVED1[1];
+ __IO uint32_t ILPR; /* Offset: 0x020 (R/W) IrDA Low-power Counter */
+ __IO uint32_t IBRD; /* Offset: 0x024 (R/W) Interger Baud Rate */
+ __IO uint32_t FBRD; /* Offset: 0x028 (R/W) Fractional Baud Rate */
+ __IO uint32_t LCR_H; /* Offset: 0x02C (R/W) Line Control */
+ __IO uint32_t CR; /* Offset: 0x030 (R/W) Control */
+ __IO uint32_t IFLS; /* Offset: 0x034 (R/W) Interrupt FIFO Level Select */
+ __IO uint32_t IMSC; /* Offset: 0x038 (R/W) Interrupt Mask Set / Clear */
+ __IO uint32_t RIS; /* Offset: 0x03C (R/W) Raw Interrupt Status */
+ __IO uint32_t MIS; /* Offset: 0x040 (R/W) Masked Interrupt Status */
+ __O uint32_t ICR; /* Offset: 0x044 ( /W) Interrupt Clear */
+ __IO uint32_t DMACR; /* Offset: 0x048 (R/W) DMA Control */
+} ARM_UART_TypeDef;
+
+
+/* -------------------- End of section using anonymous unions ------------------- */
+#if defined(__CC_ARM)
+ #pragma pop
+#elif defined(__ICCARM__)
+ /* leave anonymous unions enabled */
+#elif defined(__GNUC__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TMS470__)
+ /* anonymous unions are enabled by default */
+#elif defined(__TASKING__)
+ #pragma warning restore
+#else
+ #warning Not supported compiler type
+#endif
+
+
+
+
+/* ================================================================================ */
+/* ================ Peripheral memory map ================ */
+/* ================================================================================ */
+/* -------------------------- CPU FPGA memory map ------------------------------- */
+#define ARM_FLASH_BASE (0x00000000UL)
+#define ARM_RAM_BASE (0x20000000UL)
+#define ARM_RAM_FPGA_BASE (0x1EFF0000UL)
+#define ARM_CPU_CFG_BASE (0xDFFF0000UL)
+
+#define ARM_CPU_SYS_BASE (ARM_CPU_CFG_BASE + 0x00000)
+#define ARM_UART3_BASE (ARM_CPU_CFG_BASE + 0x05000)
+
+/* -------------------------- DUT FPGA memory map ------------------------------- */
+#define ARM_APB_BASE (0x40000000UL)
+#define ARM_AHB_BASE (0x4FF00000UL)
+#define ARM_DMC_BASE (0x60000000UL)
+#define ARM_SMC_BASE (0xA0000000UL)
+
+#define ARM_TIM0_BASE (ARM_APB_BASE + 0x02000)
+#define ARM_TIM2_BASE (ARM_APB_BASE + 0x03000)
+#define ARM_DUT_SYS_BASE (ARM_APB_BASE + 0x04000)
+#define ARM_UART0_BASE (ARM_APB_BASE + 0x06000)
+#define ARM_UART1_BASE (ARM_APB_BASE + 0x07000)
+#define ARM_UART2_BASE (ARM_APB_BASE + 0x08000)
+#define ARM_UART4_BASE (ARM_APB_BASE + 0x09000)
+
+
+/* ================================================================================ */
+/* ================ Peripheral declaration ================ */
+/* ================================================================================ */
+/* -------------------------- CPU FPGA Peripherals ------------------------------ */
+#define ARM_CPU_SYS ((ARM_CPU_SYS_TypeDef *) ARM_CPU_SYS_BASE)
+#define ARM_UART3 (( ARM_UART_TypeDef *) ARM_UART3_BASE)
+
+/* -------------------------- DUT FPGA Peripherals ------------------------------ */
+#define ARM_DUT_SYS ((ARM_DUT_SYS_TypeDef *) ARM_DUT_SYS_BASE)
+#define ARM_TIM0 (( ARM_TIM_TypeDef *) ARM_TIM0_BASE)
+#define ARM_TIM2 (( ARM_TIM_TypeDef *) ARM_TIM2_BASE)
+#define ARM_UART0 (( ARM_UART_TypeDef *) ARM_UART0_BASE)
+#define ARM_UART1 (( ARM_UART_TypeDef *) ARM_UART1_BASE)
+#define ARM_UART2 (( ARM_UART_TypeDef *) ARM_UART2_BASE)
+#define ARM_UART4 (( ARM_UART_TypeDef *) ARM_UART4_BASE)
+
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /* ARMCM4_H */
diff --git a/src/lib/mathlib/CMSIS/Include/arm_common_tables.h b/src/lib/mathlib/CMSIS/Include/arm_common_tables.h
new file mode 100644
index 000000000..9c37ab4e5
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/arm_common_tables.h
@@ -0,0 +1,93 @@
+/* ----------------------------------------------------------------------
+* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
+*
+* $Date: 17. January 2013
+* $Revision: V1.4.1
+*
+* Project: CMSIS DSP Library
+* Title: arm_common_tables.h
+*
+* Description: This file has extern declaration for common tables like Bitreverse, reciprocal etc which are used across different functions
+*
+* Target Processor: Cortex-M4/Cortex-M3
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+* - Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* - 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.
+* - Neither the name of ARM LIMITED 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.
+* -------------------------------------------------------------------- */
+
+#ifndef _ARM_COMMON_TABLES_H
+#define _ARM_COMMON_TABLES_H
+
+#include "arm_math.h"
+
+extern const uint16_t armBitRevTable[1024];
+extern const q15_t armRecipTableQ15[64];
+extern const q31_t armRecipTableQ31[64];
+extern const q31_t realCoefAQ31[1024];
+extern const q31_t realCoefBQ31[1024];
+extern const float32_t twiddleCoef_16[32];
+extern const float32_t twiddleCoef_32[64];
+extern const float32_t twiddleCoef_64[128];
+extern const float32_t twiddleCoef_128[256];
+extern const float32_t twiddleCoef_256[512];
+extern const float32_t twiddleCoef_512[1024];
+extern const float32_t twiddleCoef_1024[2048];
+extern const float32_t twiddleCoef_2048[4096];
+extern const float32_t twiddleCoef_4096[8192];
+#define twiddleCoef twiddleCoef_4096
+extern const q31_t twiddleCoefQ31[6144];
+extern const q15_t twiddleCoefQ15[6144];
+extern const float32_t twiddleCoef_rfft_32[32];
+extern const float32_t twiddleCoef_rfft_64[64];
+extern const float32_t twiddleCoef_rfft_128[128];
+extern const float32_t twiddleCoef_rfft_256[256];
+extern const float32_t twiddleCoef_rfft_512[512];
+extern const float32_t twiddleCoef_rfft_1024[1024];
+extern const float32_t twiddleCoef_rfft_2048[2048];
+extern const float32_t twiddleCoef_rfft_4096[4096];
+
+
+#define ARMBITREVINDEXTABLE__16_TABLE_LENGTH ((uint16_t)20 )
+#define ARMBITREVINDEXTABLE__32_TABLE_LENGTH ((uint16_t)48 )
+#define ARMBITREVINDEXTABLE__64_TABLE_LENGTH ((uint16_t)56 )
+#define ARMBITREVINDEXTABLE_128_TABLE_LENGTH ((uint16_t)208 )
+#define ARMBITREVINDEXTABLE_256_TABLE_LENGTH ((uint16_t)440 )
+#define ARMBITREVINDEXTABLE_512_TABLE_LENGTH ((uint16_t)448 )
+#define ARMBITREVINDEXTABLE1024_TABLE_LENGTH ((uint16_t)1800)
+#define ARMBITREVINDEXTABLE2048_TABLE_LENGTH ((uint16_t)3808)
+#define ARMBITREVINDEXTABLE4096_TABLE_LENGTH ((uint16_t)4032)
+
+extern const uint16_t armBitRevIndexTable16[ARMBITREVINDEXTABLE__16_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable32[ARMBITREVINDEXTABLE__32_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable64[ARMBITREVINDEXTABLE__64_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable128[ARMBITREVINDEXTABLE_128_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable256[ARMBITREVINDEXTABLE_256_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable512[ARMBITREVINDEXTABLE_512_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable1024[ARMBITREVINDEXTABLE1024_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable2048[ARMBITREVINDEXTABLE2048_TABLE_LENGTH];
+extern const uint16_t armBitRevIndexTable4096[ARMBITREVINDEXTABLE4096_TABLE_LENGTH];
+
+#endif /* ARM_COMMON_TABLES_H */
diff --git a/src/lib/mathlib/CMSIS/Include/arm_const_structs.h b/src/lib/mathlib/CMSIS/Include/arm_const_structs.h
new file mode 100644
index 000000000..406f737dc
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/arm_const_structs.h
@@ -0,0 +1,85 @@
+/* ----------------------------------------------------------------------
+* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
+*
+* $Date: 17. January 2013
+* $Revision: V1.4.1
+*
+* Project: CMSIS DSP Library
+* Title: arm_const_structs.h
+*
+* Description: This file has constant structs that are initialized for
+* user convenience. For example, some can be given as
+* arguments to the arm_cfft_f32() function.
+*
+* Target Processor: Cortex-M4/Cortex-M3
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+* - Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* - 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.
+* - Neither the name of ARM LIMITED 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.
+* -------------------------------------------------------------------- */
+
+#ifndef _ARM_CONST_STRUCTS_H
+#define _ARM_CONST_STRUCTS_H
+
+#include "arm_math.h"
+#include "arm_common_tables.h"
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len16 = {
+ 16, twiddleCoef_16, armBitRevIndexTable16, ARMBITREVINDEXTABLE__16_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len32 = {
+ 32, twiddleCoef_32, armBitRevIndexTable32, ARMBITREVINDEXTABLE__32_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len64 = {
+ 64, twiddleCoef_64, armBitRevIndexTable64, ARMBITREVINDEXTABLE__64_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len128 = {
+ 128, twiddleCoef_128, armBitRevIndexTable128, ARMBITREVINDEXTABLE_128_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len256 = {
+ 256, twiddleCoef_256, armBitRevIndexTable256, ARMBITREVINDEXTABLE_256_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len512 = {
+ 512, twiddleCoef_512, armBitRevIndexTable512, ARMBITREVINDEXTABLE_512_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len1024 = {
+ 1024, twiddleCoef_1024, armBitRevIndexTable1024, ARMBITREVINDEXTABLE1024_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len2048 = {
+ 2048, twiddleCoef_2048, armBitRevIndexTable2048, ARMBITREVINDEXTABLE2048_TABLE_LENGTH
+ };
+
+ const arm_cfft_instance_f32 arm_cfft_sR_f32_len4096 = {
+ 4096, twiddleCoef_4096, armBitRevIndexTable4096, ARMBITREVINDEXTABLE4096_TABLE_LENGTH
+ };
+
+#endif
diff --git a/src/lib/mathlib/CMSIS/Include/arm_math.h b/src/lib/mathlib/CMSIS/Include/arm_math.h
new file mode 100644
index 000000000..6f66f9ee3
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/arm_math.h
@@ -0,0 +1,7318 @@
+/* ----------------------------------------------------------------------
+* Copyright (C) 2010-2013 ARM Limited. All rights reserved.
+*
+* $Date: 17. January 2013
+* $Revision: V1.4.1
+*
+* Project: CMSIS DSP Library
+* Title: arm_math.h
+*
+* Description: Public header file for CMSIS DSP Library
+*
+* Target Processor: Cortex-M4/Cortex-M3/Cortex-M0
+*
+* Redistribution and use in source and binary forms, with or without
+* modification, are permitted provided that the following conditions
+* are met:
+* - Redistributions of source code must retain the above copyright
+* notice, this list of conditions and the following disclaimer.
+* - 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.
+* - Neither the name of ARM LIMITED 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.
+ * -------------------------------------------------------------------- */
+
+/**
+ \mainpage CMSIS DSP Software Library
+ *
+ * <b>Introduction</b>
+ *
+ * This user manual describes the CMSIS DSP software library,
+ * a suite of common signal processing functions for use on Cortex-M processor based devices.
+ *
+ * The library is divided into a number of functions each covering a specific category:
+ * - Basic math functions
+ * - Fast math functions
+ * - Complex math functions
+ * - Filters
+ * - Matrix functions
+ * - Transforms
+ * - Motor control functions
+ * - Statistical functions
+ * - Support functions
+ * - Interpolation functions
+ *
+ * The library has separate functions for operating on 8-bit integers, 16-bit integers,
+ * 32-bit integer and 32-bit floating-point values.
+ *
+ * <b>Using the Library</b>
+ *
+ * The library installer contains prebuilt versions of the libraries in the <code>Lib</code> folder.
+ * - arm_cortexM4lf_math.lib (Little endian and Floating Point Unit on Cortex-M4)
+ * - arm_cortexM4bf_math.lib (Big endian and Floating Point Unit on Cortex-M4)
+ * - arm_cortexM4l_math.lib (Little endian on Cortex-M4)
+ * - arm_cortexM4b_math.lib (Big endian on Cortex-M4)
+ * - arm_cortexM3l_math.lib (Little endian on Cortex-M3)
+ * - arm_cortexM3b_math.lib (Big endian on Cortex-M3)
+ * - arm_cortexM0l_math.lib (Little endian on Cortex-M0)
+ * - arm_cortexM0b_math.lib (Big endian on Cortex-M3)
+ *
+ * The library functions are declared in the public file <code>arm_math.h</code> which is placed in the <code>Include</code> folder.
+ * Simply include this file and link the appropriate library in the application and begin calling the library functions. The Library supports single
+ * public header file <code> arm_math.h</code> for Cortex-M4/M3/M0 with little endian and big endian. Same header file will be used for floating point unit(FPU) variants.
+ * Define the appropriate pre processor MACRO ARM_MATH_CM4 or ARM_MATH_CM3 or
+ * ARM_MATH_CM0 or ARM_MATH_CM0PLUS depending on the target processor in the application.
+ *
+ * <b>Examples</b>
+ *
+ * The library ships with a number of examples which demonstrate how to use the library functions.
+ *
+ * <b>Toolchain Support</b>
+ *
+ * The library has been developed and tested with MDK-ARM version 4.60.
+ * The library is being tested in GCC and IAR toolchains and updates on this activity will be made available shortly.
+ *
+ * <b>Building the Library</b>
+ *
+ * The library installer contains project files to re build libraries on MDK Tool chain in the <code>CMSIS\\DSP_Lib\\Source\\ARM</code> folder.
+ * - arm_cortexM0b_math.uvproj
+ * - arm_cortexM0l_math.uvproj
+ * - arm_cortexM3b_math.uvproj
+ * - arm_cortexM3l_math.uvproj
+ * - arm_cortexM4b_math.uvproj
+ * - arm_cortexM4l_math.uvproj
+ * - arm_cortexM4bf_math.uvproj
+ * - arm_cortexM4lf_math.uvproj
+ *
+ *
+ * The project can be built by opening the appropriate project in MDK-ARM 4.60 chain and defining the optional pre processor MACROs detailed above.
+ *
+ * <b>Pre-processor Macros</b>
+ *
+ * Each library project have differant pre-processor macros.
+ *
+ * - UNALIGNED_SUPPORT_DISABLE:
+ *
+ * Define macro UNALIGNED_SUPPORT_DISABLE, If the silicon does not support unaligned memory access
+ *
+ * - ARM_MATH_BIG_ENDIAN:
+ *
+ * Define macro ARM_MATH_BIG_ENDIAN to build the library for big endian targets. By default library builds for little endian targets.
+ *
+ * - ARM_MATH_MATRIX_CHECK:
+ *
+ * Define macro ARM_MATH_MATRIX_CHECK for checking on the input and output sizes of matrices
+ *
+ * - ARM_MATH_ROUNDING:
+ *
+ * Define macro ARM_MATH_ROUNDING for rounding on support functions
+ *
+ * - ARM_MATH_CMx:
+ *
+ * Define macro ARM_MATH_CM4 for building the library on Cortex-M4 target, ARM_MATH_CM3 for building library on Cortex-M3 target
+ * and ARM_MATH_CM0 for building library on cortex-M0 target, ARM_MATH_CM0PLUS for building library on cortex-M0+ target.
+ *
+ * - __FPU_PRESENT:
+ *
+ * Initialize macro __FPU_PRESENT = 1 when building on FPU supported Targets. Enable this macro for M4bf and M4lf libraries
+ *
+ * <b>Copyright Notice</b>
+ *
+ * Copyright (C) 2010-2013 ARM Limited. All rights reserved.
+ */
+
+
+/**
+ * @defgroup groupMath Basic Math Functions
+ */
+
+/**
+ * @defgroup groupFastMath Fast Math Functions
+ * This set of functions provides a fast approximation to sine, cosine, and square root.
+ * As compared to most of the other functions in the CMSIS math library, the fast math functions
+ * operate on individual values and not arrays.
+ * There are separate functions for Q15, Q31, and floating-point data.
+ *
+ */
+
+/**
+ * @defgroup groupCmplxMath Complex Math Functions
+ * This set of functions operates on complex data vectors.
+ * The data in the complex arrays is stored in an interleaved fashion
+ * (real, imag, real, imag, ...).
+ * In the API functions, the number of samples in a complex array refers
+ * to the number of complex values; the array contains twice this number of
+ * real values.
+ */
+
+/**
+ * @defgroup groupFilters Filtering Functions
+ */
+
+/**
+ * @defgroup groupMatrix Matrix Functions
+ *
+ * This set of functions provides basic matrix math operations.
+ * The functions operate on matrix data structures. For example,
+ * the type
+ * definition for the floating-point matrix structure is shown
+ * below:
+ * <pre>
+ * typedef struct
+ * {
+ * uint16_t numRows; // number of rows of the matrix.
+ * uint16_t numCols; // number of columns of the matrix.
+ * float32_t *pData; // points to the data of the matrix.
+ * } arm_matrix_instance_f32;
+ * </pre>
+ * There are similar definitions for Q15 and Q31 data types.
+ *
+ * The structure specifies the size of the matrix and then points to
+ * an array of data. The array is of size <code>numRows X numCols</code>
+ * and the values are arranged in row order. That is, the
+ * matrix element (i, j) is stored at:
+ * <pre>
+ * pData[i*numCols + j]
+ * </pre>
+ *
+ * \par Init Functions
+ * There is an associated initialization function for each type of matrix
+ * data structure.
+ * The initialization function sets the values of the internal structure fields.
+ * Refer to the function <code>arm_mat_init_f32()</code>, <code>arm_mat_init_q31()</code>
+ * and <code>arm_mat_init_q15()</code> for floating-point, Q31 and Q15 types, respectively.
+ *
+ * \par
+ * Use of the initialization function is optional. However, if initialization function is used
+ * then the instance structure cannot be placed into a const data section.
+ * To place the instance structure in a const data
+ * section, manually initialize the data structure. For example:
+ * <pre>
+ * <code>arm_matrix_instance_f32 S = {nRows, nColumns, pData};</code>
+ * <code>arm_matrix_instance_q31 S = {nRows, nColumns, pData};</code>
+ * <code>arm_matrix_instance_q15 S = {nRows, nColumns, pData};</code>
+ * </pre>
+ * where <code>nRows</code> specifies the number of rows, <code>nColumns</code>
+ * specifies the number of columns, and <code>pData</code> points to the
+ * data array.
+ *
+ * \par Size Checking
+ * By default all of the matrix functions perform size checking on the input and
+ * output matrices. For example, the matrix addition function verifies that the
+ * two input matrices and the output matrix all have the same number of rows and
+ * columns. If the size check fails the functions return:
+ * <pre>
+ * ARM_MATH_SIZE_MISMATCH
+ * </pre>
+ * Otherwise the functions return
+ * <pre>
+ * ARM_MATH_SUCCESS
+ * </pre>
+ * There is some overhead associated with this matrix size checking.
+ * The matrix size checking is enabled via the \#define
+ * <pre>
+ * ARM_MATH_MATRIX_CHECK
+ * </pre>
+ * within the library project settings. By default this macro is defined
+ * and size checking is enabled. By changing the project settings and
+ * undefining this macro size checking is eliminated and the functions
+ * run a bit faster. With size checking disabled the functions always
+ * return <code>ARM_MATH_SUCCESS</code>.
+ */
+
+/**
+ * @defgroup groupTransforms Transform Functions
+ */
+
+/**
+ * @defgroup groupController Controller Functions
+ */
+
+/**
+ * @defgroup groupStats Statistics Functions
+ */
+/**
+ * @defgroup groupSupport Support Functions
+ */
+
+/**
+ * @defgroup groupInterpolation Interpolation Functions
+ * These functions perform 1- and 2-dimensional interpolation of data.
+ * Linear interpolation is used for 1-dimensional data and
+ * bilinear interpolation is used for 2-dimensional data.
+ */
+
+/**
+ * @defgroup groupExamples Examples
+ */
+#ifndef _ARM_MATH_H
+#define _ARM_MATH_H
+
+#define __CMSIS_GENERIC /* disable NVIC and Systick functions */
+
+/* PX4 */
+#include <nuttx/config.h>
+#ifdef CONFIG_ARCH_CORTEXM4
+# define ARM_MATH_CM4 1
+#endif
+#ifdef CONFIG_ARCH_CORTEXM3
+# define ARM_MATH_CM3 1
+#endif
+#ifdef CONFIG_ARCH_FPU
+# define __FPU_PRESENT 1
+#endif
+
+#if defined (ARM_MATH_CM4)
+#include "core_cm4.h"
+#elif defined (ARM_MATH_CM3)
+#include "core_cm3.h"
+#elif defined (ARM_MATH_CM0)
+#include "core_cm0.h"
+#define ARM_MATH_CM0_FAMILY
+#elif defined (ARM_MATH_CM0PLUS)
+#include "core_cm0plus.h"
+#define ARM_MATH_CM0_FAMILY
+#else
+#include "ARMCM4.h"
+#warning "Define either ARM_MATH_CM4 OR ARM_MATH_CM3...By Default building on ARM_MATH_CM4....."
+#endif
+
+#undef __CMSIS_GENERIC /* enable NVIC and Systick functions */
+#include "string.h"
+#include "math.h"
+#ifdef __cplusplus
+extern "C"
+{
+#endif
+
+
+ /**
+ * @brief Macros required for reciprocal calculation in Normalized LMS
+ */
+
+#define DELTA_Q31 (0x100)
+#define DELTA_Q15 0x5
+#define INDEX_MASK 0x0000003F
+#ifndef PI
+#define PI 3.14159265358979f
+#endif
+
+ /**
+ * @brief Macros required for SINE and COSINE Fast math approximations
+ */
+
+#define TABLE_SIZE 256
+#define TABLE_SPACING_Q31 0x800000
+#define TABLE_SPACING_Q15 0x80
+
+ /**
+ * @brief Macros required for SINE and COSINE Controller functions
+ */
+ /* 1.31(q31) Fixed value of 2/360 */
+ /* -1 to +1 is divided into 360 values so total spacing is (2/360) */
+#define INPUT_SPACING 0xB60B61
+
+ /**
+ * @brief Macro for Unaligned Support
+ */
+#ifndef UNALIGNED_SUPPORT_DISABLE
+ #define ALIGN4
+#else
+ #if defined (__GNUC__)
+ #define ALIGN4 __attribute__((aligned(4)))
+ #else
+ #define ALIGN4 __align(4)
+ #endif
+#endif /* #ifndef UNALIGNED_SUPPORT_DISABLE */
+
+ /**
+ * @brief Error status returned by some functions in the library.
+ */
+
+ typedef enum
+ {
+ ARM_MATH_SUCCESS = 0, /**< No error */
+ ARM_MATH_ARGUMENT_ERROR = -1, /**< One or more arguments are incorrect */
+ ARM_MATH_LENGTH_ERROR = -2, /**< Length of data buffer is incorrect */
+ ARM_MATH_SIZE_MISMATCH = -3, /**< Size of matrices is not compatible with the operation. */
+ ARM_MATH_NANINF = -4, /**< Not-a-number (NaN) or infinity is generated */
+ ARM_MATH_SINGULAR = -5, /**< Generated by matrix inversion if the input matrix is singular and cannot be inverted. */
+ ARM_MATH_TEST_FAILURE = -6 /**< Test Failed */
+ } arm_status;
+
+ /**
+ * @brief 8-bit fractional data type in 1.7 format.
+ */
+ typedef int8_t q7_t;
+
+ /**
+ * @brief 16-bit fractional data type in 1.15 format.
+ */
+ typedef int16_t q15_t;
+
+ /**
+ * @brief 32-bit fractional data type in 1.31 format.
+ */
+ typedef int32_t q31_t;
+
+ /**
+ * @brief 64-bit fractional data type in 1.63 format.
+ */
+ typedef int64_t q63_t;
+
+ /**
+ * @brief 32-bit floating-point type definition.
+ */
+ typedef float float32_t;
+
+ /**
+ * @brief 64-bit floating-point type definition.
+ */
+ typedef double float64_t;
+
+ /**
+ * @brief definition to read/write two 16 bit values.
+ */
+#if defined __CC_ARM
+#define __SIMD32_TYPE int32_t __packed
+#define CMSIS_UNUSED __attribute__((unused))
+#elif defined __ICCARM__
+#define CMSIS_UNUSED
+#define __SIMD32_TYPE int32_t __packed
+#elif defined __GNUC__
+#define __SIMD32_TYPE int32_t
+#define CMSIS_UNUSED __attribute__((unused))
+#else
+#error Unknown compiler
+#endif
+
+#define __SIMD32(addr) (*(__SIMD32_TYPE **) & (addr))
+#define __SIMD32_CONST(addr) ((__SIMD32_TYPE *)(addr))
+
+#define _SIMD32_OFFSET(addr) (*(__SIMD32_TYPE *) (addr))
+
+#define __SIMD64(addr) (*(int64_t **) & (addr))
+
+#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY)
+ /**
+ * @brief definition to pack two 16 bit values.
+ */
+#define __PKHBT(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0x0000FFFF) | \
+ (((int32_t)(ARG2) << ARG3) & (int32_t)0xFFFF0000) )
+#define __PKHTB(ARG1, ARG2, ARG3) ( (((int32_t)(ARG1) << 0) & (int32_t)0xFFFF0000) | \
+ (((int32_t)(ARG2) >> ARG3) & (int32_t)0x0000FFFF) )
+
+#endif
+
+
+ /**
+ * @brief definition to pack four 8 bit values.
+ */
+#ifndef ARM_MATH_BIG_ENDIAN
+
+#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v0) << 0) & (int32_t)0x000000FF) | \
+ (((int32_t)(v1) << 8) & (int32_t)0x0000FF00) | \
+ (((int32_t)(v2) << 16) & (int32_t)0x00FF0000) | \
+ (((int32_t)(v3) << 24) & (int32_t)0xFF000000) )
+#else
+
+#define __PACKq7(v0,v1,v2,v3) ( (((int32_t)(v3) << 0) & (int32_t)0x000000FF) | \
+ (((int32_t)(v2) << 8) & (int32_t)0x0000FF00) | \
+ (((int32_t)(v1) << 16) & (int32_t)0x00FF0000) | \
+ (((int32_t)(v0) << 24) & (int32_t)0xFF000000) )
+
+#endif
+
+
+ /**
+ * @brief Clips Q63 to Q31 values.
+ */
+ static __INLINE q31_t clip_q63_to_q31(
+ q63_t x)
+ {
+ return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
+ ((0x7FFFFFFF ^ ((q31_t) (x >> 63)))) : (q31_t) x;
+ }
+
+ /**
+ * @brief Clips Q63 to Q15 values.
+ */
+ static __INLINE q15_t clip_q63_to_q15(
+ q63_t x)
+ {
+ return ((q31_t) (x >> 32) != ((q31_t) x >> 31)) ?
+ ((0x7FFF ^ ((q15_t) (x >> 63)))) : (q15_t) (x >> 15);
+ }
+
+ /**
+ * @brief Clips Q31 to Q7 values.
+ */
+ static __INLINE q7_t clip_q31_to_q7(
+ q31_t x)
+ {
+ return ((q31_t) (x >> 24) != ((q31_t) x >> 23)) ?
+ ((0x7F ^ ((q7_t) (x >> 31)))) : (q7_t) x;
+ }
+
+ /**
+ * @brief Clips Q31 to Q15 values.
+ */
+ static __INLINE q15_t clip_q31_to_q15(
+ q31_t x)
+ {
+ return ((q31_t) (x >> 16) != ((q31_t) x >> 15)) ?
+ ((0x7FFF ^ ((q15_t) (x >> 31)))) : (q15_t) x;
+ }
+
+ /**
+ * @brief Multiplies 32 X 64 and returns 32 bit result in 2.30 format.
+ */
+
+ static __INLINE q63_t mult32x64(
+ q63_t x,
+ q31_t y)
+ {
+ return ((((q63_t) (x & 0x00000000FFFFFFFF) * y) >> 32) +
+ (((q63_t) (x >> 32) * y)));
+ }
+
+
+#if defined (ARM_MATH_CM0_FAMILY) && defined ( __CC_ARM )
+#define __CLZ __clz
+#endif
+
+#if defined (ARM_MATH_CM0_FAMILY) && ((defined (__ICCARM__)) ||(defined (__GNUC__)) || defined (__TASKING__) )
+
+ static __INLINE uint32_t __CLZ(
+ q31_t data);
+
+
+ static __INLINE uint32_t __CLZ(
+ q31_t data)
+ {
+ uint32_t count = 0;
+ uint32_t mask = 0x80000000;
+
+ while((data & mask) == 0)
+ {
+ count += 1u;
+ mask = mask >> 1u;
+ }
+
+ return (count);
+
+ }
+
+#endif
+
+ /**
+ * @brief Function to Calculates 1/in (reciprocal) value of Q31 Data type.
+ */
+
+ static __INLINE uint32_t arm_recip_q31(
+ q31_t in,
+ q31_t * dst,
+ q31_t * pRecipTable)
+ {
+
+ uint32_t out, tempVal;
+ uint32_t index, i;
+ uint32_t signBits;
+
+ if(in > 0)
+ {
+ signBits = __CLZ(in) - 1;
+ }
+ else
+ {
+ signBits = __CLZ(-in) - 1;
+ }
+
+ /* Convert input sample to 1.31 format */
+ in = in << signBits;
+
+ /* calculation of index for initial approximated Val */
+ index = (uint32_t) (in >> 24u);
+ index = (index & INDEX_MASK);
+
+ /* 1.31 with exp 1 */
+ out = pRecipTable[index];
+
+ /* calculation of reciprocal value */
+ /* running approximation for two iterations */
+ for (i = 0u; i < 2u; i++)
+ {
+ tempVal = (q31_t) (((q63_t) in * out) >> 31u);
+ tempVal = 0x7FFFFFFF - tempVal;
+ /* 1.31 with exp 1 */
+ //out = (q31_t) (((q63_t) out * tempVal) >> 30u);
+ out = (q31_t) clip_q63_to_q31(((q63_t) out * tempVal) >> 30u);
+ }
+
+ /* write output */
+ *dst = out;
+
+ /* return num of signbits of out = 1/in value */
+ return (signBits + 1u);
+
+ }
+
+ /**
+ * @brief Function to Calculates 1/in (reciprocal) value of Q15 Data type.
+ */
+ static __INLINE uint32_t arm_recip_q15(
+ q15_t in,
+ q15_t * dst,
+ q15_t * pRecipTable)
+ {
+
+ uint32_t out = 0, tempVal = 0;
+ uint32_t index = 0, i = 0;
+ uint32_t signBits = 0;
+
+ if(in > 0)
+ {
+ signBits = __CLZ(in) - 17;
+ }
+ else
+ {
+ signBits = __CLZ(-in) - 17;
+ }
+
+ /* Convert input sample to 1.15 format */
+ in = in << signBits;
+
+ /* calculation of index for initial approximated Val */
+ index = in >> 8;
+ index = (index & INDEX_MASK);
+
+ /* 1.15 with exp 1 */
+ out = pRecipTable[index];
+
+ /* calculation of reciprocal value */
+ /* running approximation for two iterations */
+ for (i = 0; i < 2; i++)
+ {
+ tempVal = (q15_t) (((q31_t) in * out) >> 15);
+ tempVal = 0x7FFF - tempVal;
+ /* 1.15 with exp 1 */
+ out = (q15_t) (((q31_t) out * tempVal) >> 14);
+ }
+
+ /* write output */
+ *dst = out;
+
+ /* return num of signbits of out = 1/in value */
+ return (signBits + 1);
+
+ }
+
+
+ /*
+ * @brief C custom defined intrinisic function for only M0 processors
+ */
+#if defined(ARM_MATH_CM0_FAMILY)
+
+ static __INLINE q31_t __SSAT(
+ q31_t x,
+ uint32_t y)
+ {
+ int32_t posMax, negMin;
+ uint32_t i;
+
+ posMax = 1;
+ for (i = 0; i < (y - 1); i++)
+ {
+ posMax = posMax * 2;
+ }
+
+ if(x > 0)
+ {
+ posMax = (posMax - 1);
+
+ if(x > posMax)
+ {
+ x = posMax;
+ }
+ }
+ else
+ {
+ negMin = -posMax;
+
+ if(x < negMin)
+ {
+ x = negMin;
+ }
+ }
+ return (x);
+
+
+ }
+
+#endif /* end of ARM_MATH_CM0_FAMILY */
+
+
+
+ /*
+ * @brief C custom defined intrinsic function for M3 and M0 processors
+ */
+#if defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY)
+
+ /*
+ * @brief C custom defined QADD8 for M3 and M0 processors
+ */
+ static __INLINE q31_t __QADD8(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q7_t r, s, t, u;
+
+ r = (q7_t) x;
+ s = (q7_t) y;
+
+ r = __SSAT((q31_t) (r + s), 8);
+ s = __SSAT(((q31_t) (((x << 16) >> 24) + ((y << 16) >> 24))), 8);
+ t = __SSAT(((q31_t) (((x << 8) >> 24) + ((y << 8) >> 24))), 8);
+ u = __SSAT(((q31_t) ((x >> 24) + (y >> 24))), 8);
+
+ sum =
+ (((q31_t) u << 24) & 0xFF000000) | (((q31_t) t << 16) & 0x00FF0000) |
+ (((q31_t) s << 8) & 0x0000FF00) | (r & 0x000000FF);
+
+ return sum;
+
+ }
+
+ /*
+ * @brief C custom defined QSUB8 for M3 and M0 processors
+ */
+ static __INLINE q31_t __QSUB8(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s, t, u;
+
+ r = (q7_t) x;
+ s = (q7_t) y;
+
+ r = __SSAT((r - s), 8);
+ s = __SSAT(((q31_t) (((x << 16) >> 24) - ((y << 16) >> 24))), 8) << 8;
+ t = __SSAT(((q31_t) (((x << 8) >> 24) - ((y << 8) >> 24))), 8) << 16;
+ u = __SSAT(((q31_t) ((x >> 24) - (y >> 24))), 8) << 24;
+
+ sum =
+ (u & 0xFF000000) | (t & 0x00FF0000) | (s & 0x0000FF00) | (r &
+ 0x000000FF);
+
+ return sum;
+ }
+
+ /*
+ * @brief C custom defined QADD16 for M3 and M0 processors
+ */
+
+ /*
+ * @brief C custom defined QADD16 for M3 and M0 processors
+ */
+ static __INLINE q31_t __QADD16(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = __SSAT(r + s, 16);
+ s = __SSAT(((q31_t) ((x >> 16) + (y >> 16))), 16) << 16;
+
+ sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return sum;
+
+ }
+
+ /*
+ * @brief C custom defined SHADD16 for M3 and M0 processors
+ */
+ static __INLINE q31_t __SHADD16(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = ((r >> 1) + (s >> 1));
+ s = ((q31_t) ((x >> 17) + (y >> 17))) << 16;
+
+ sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return sum;
+
+ }
+
+ /*
+ * @brief C custom defined QSUB16 for M3 and M0 processors
+ */
+ static __INLINE q31_t __QSUB16(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = __SSAT(r - s, 16);
+ s = __SSAT(((q31_t) ((x >> 16) - (y >> 16))), 16) << 16;
+
+ sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return sum;
+ }
+
+ /*
+ * @brief C custom defined SHSUB16 for M3 and M0 processors
+ */
+ static __INLINE q31_t __SHSUB16(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t diff;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = ((r >> 1) - (s >> 1));
+ s = (((x >> 17) - (y >> 17)) << 16);
+
+ diff = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return diff;
+ }
+
+ /*
+ * @brief C custom defined QASX for M3 and M0 processors
+ */
+ static __INLINE q31_t __QASX(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum = 0;
+
+ sum =
+ ((sum +
+ clip_q31_to_q15((q31_t) ((short) (x >> 16) + (short) y))) << 16) +
+ clip_q31_to_q15((q31_t) ((short) x - (short) (y >> 16)));
+
+ return sum;
+ }
+
+ /*
+ * @brief C custom defined SHASX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SHASX(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = ((r >> 1) - (y >> 17));
+ s = (((x >> 17) + (s >> 1)) << 16);
+
+ sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return sum;
+ }
+
+
+ /*
+ * @brief C custom defined QSAX for M3 and M0 processors
+ */
+ static __INLINE q31_t __QSAX(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum = 0;
+
+ sum =
+ ((sum +
+ clip_q31_to_q15((q31_t) ((short) (x >> 16) - (short) y))) << 16) +
+ clip_q31_to_q15((q31_t) ((short) x + (short) (y >> 16)));
+
+ return sum;
+ }
+
+ /*
+ * @brief C custom defined SHSAX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SHSAX(
+ q31_t x,
+ q31_t y)
+ {
+
+ q31_t sum;
+ q31_t r, s;
+
+ r = (short) x;
+ s = (short) y;
+
+ r = ((r >> 1) + (y >> 17));
+ s = (((x >> 17) - (s >> 1)) << 16);
+
+ sum = (s & 0xFFFF0000) | (r & 0x0000FFFF);
+
+ return sum;
+ }
+
+ /*
+ * @brief C custom defined SMUSDX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMUSDX(
+ q31_t x,
+ q31_t y)
+ {
+
+ return ((q31_t) (((short) x * (short) (y >> 16)) -
+ ((short) (x >> 16) * (short) y)));
+ }
+
+ /*
+ * @brief C custom defined SMUADX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMUADX(
+ q31_t x,
+ q31_t y)
+ {
+
+ return ((q31_t) (((short) x * (short) (y >> 16)) +
+ ((short) (x >> 16) * (short) y)));
+ }
+
+ /*
+ * @brief C custom defined QADD for M3 and M0 processors
+ */
+ static __INLINE q31_t __QADD(
+ q31_t x,
+ q31_t y)
+ {
+ return clip_q63_to_q31((q63_t) x + y);
+ }
+
+ /*
+ * @brief C custom defined QSUB for M3 and M0 processors
+ */
+ static __INLINE q31_t __QSUB(
+ q31_t x,
+ q31_t y)
+ {
+ return clip_q63_to_q31((q63_t) x - y);
+ }
+
+ /*
+ * @brief C custom defined SMLAD for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMLAD(
+ q31_t x,
+ q31_t y,
+ q31_t sum)
+ {
+
+ return (sum + ((short) (x >> 16) * (short) (y >> 16)) +
+ ((short) x * (short) y));
+ }
+
+ /*
+ * @brief C custom defined SMLADX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMLADX(
+ q31_t x,
+ q31_t y,
+ q31_t sum)
+ {
+
+ return (sum + ((short) (x >> 16) * (short) (y)) +
+ ((short) x * (short) (y >> 16)));
+ }
+
+ /*
+ * @brief C custom defined SMLSDX for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMLSDX(
+ q31_t x,
+ q31_t y,
+ q31_t sum)
+ {
+
+ return (sum - ((short) (x >> 16) * (short) (y)) +
+ ((short) x * (short) (y >> 16)));
+ }
+
+ /*
+ * @brief C custom defined SMLALD for M3 and M0 processors
+ */
+ static __INLINE q63_t __SMLALD(
+ q31_t x,
+ q31_t y,
+ q63_t sum)
+ {
+
+ return (sum + ((short) (x >> 16) * (short) (y >> 16)) +
+ ((short) x * (short) y));
+ }
+
+ /*
+ * @brief C custom defined SMLALDX for M3 and M0 processors
+ */
+ static __INLINE q63_t __SMLALDX(
+ q31_t x,
+ q31_t y,
+ q63_t sum)
+ {
+
+ return (sum + ((short) (x >> 16) * (short) y)) +
+ ((short) x * (short) (y >> 16));
+ }
+
+ /*
+ * @brief C custom defined SMUAD for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMUAD(
+ q31_t x,
+ q31_t y)
+ {
+
+ return (((x >> 16) * (y >> 16)) +
+ (((x << 16) >> 16) * ((y << 16) >> 16)));
+ }
+
+ /*
+ * @brief C custom defined SMUSD for M3 and M0 processors
+ */
+ static __INLINE q31_t __SMUSD(
+ q31_t x,
+ q31_t y)
+ {
+
+ return (-((x >> 16) * (y >> 16)) +
+ (((x << 16) >> 16) * ((y << 16) >> 16)));
+ }
+
+
+ /*
+ * @brief C custom defined SXTB16 for M3 and M0 processors
+ */
+ static __INLINE q31_t __SXTB16(
+ q31_t x)
+ {
+
+ return ((((x << 24) >> 24) & 0x0000FFFF) |
+ (((x << 8) >> 8) & 0xFFFF0000));
+ }
+
+
+#endif /* defined (ARM_MATH_CM3) || defined (ARM_MATH_CM0_FAMILY) */
+
+
+ /**
+ * @brief Instance structure for the Q7 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q7_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ } arm_fir_instance_q7;
+
+ /**
+ * @brief Instance structure for the Q15 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ } arm_fir_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ } arm_fir_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of filter coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ } arm_fir_instance_f32;
+
+
+ /**
+ * @brief Processing function for the Q7 FIR filter.
+ * @param[in] *S points to an instance of the Q7 FIR filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_q7(
+ const arm_fir_instance_q7 * S,
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q7 FIR filter.
+ * @param[in,out] *S points to an instance of the Q7 FIR structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed.
+ * @return none
+ */
+ void arm_fir_init_q7(
+ arm_fir_instance_q7 * S,
+ uint16_t numTaps,
+ q7_t * pCoeffs,
+ q7_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR filter.
+ * @param[in] *S points to an instance of the Q15 FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_q15(
+ const arm_fir_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the fast Q15 FIR filter for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q15 FIR filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_fast_q15(
+ const arm_fir_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q15 FIR filter.
+ * @param[in,out] *S points to an instance of the Q15 FIR filter structure.
+ * @param[in] numTaps Number of filter coefficients in the filter. Must be even and greater than or equal to 4.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ * @return The function returns ARM_MATH_SUCCESS if initialization was successful or ARM_MATH_ARGUMENT_ERROR if
+ * <code>numTaps</code> is not a supported value.
+ */
+
+ arm_status arm_fir_init_q15(
+ arm_fir_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 FIR filter.
+ * @param[in] *S points to an instance of the Q31 FIR filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_q31(
+ const arm_fir_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the fast Q31 FIR filter for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q31 FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_fast_q31(
+ const arm_fir_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q31 FIR filter.
+ * @param[in,out] *S points to an instance of the Q31 FIR structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ * @return none.
+ */
+ void arm_fir_init_q31(
+ arm_fir_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the floating-point FIR filter.
+ * @param[in] *S points to an instance of the floating-point FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_f32(
+ const arm_fir_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the floating-point FIR filter.
+ * @param[in,out] *S points to an instance of the floating-point FIR filter structure.
+ * @param[in] numTaps Number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of samples that are processed at a time.
+ * @return none.
+ */
+ void arm_fir_init_f32(
+ arm_fir_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q15 Biquad cascade filter.
+ */
+ typedef struct
+ {
+ int8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q15_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ q15_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+ int8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
+
+ } arm_biquad_casd_df1_inst_q15;
+
+
+ /**
+ * @brief Instance structure for the Q31 Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q31_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ q31_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+ uint8_t postShift; /**< Additional shift, in bits, applied to each output sample. */
+
+ } arm_biquad_casd_df1_inst_q31;
+
+ /**
+ * @brief Instance structure for the floating-point Biquad cascade filter.
+ */
+ typedef struct
+ {
+ uint32_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float32_t *pState; /**< Points to the array of state coefficients. The array is of length 4*numStages. */
+ float32_t *pCoeffs; /**< Points to the array of coefficients. The array is of length 5*numStages. */
+
+
+ } arm_biquad_casd_df1_inst_f32;
+
+
+
+ /**
+ * @brief Processing function for the Q15 Biquad cascade filter.
+ * @param[in] *S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df1_q15(
+ const arm_biquad_casd_df1_inst_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q15 Biquad cascade filter.
+ * @param[in,out] *S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
+ * @return none
+ */
+
+ void arm_biquad_cascade_df1_init_q15(
+ arm_biquad_casd_df1_inst_q15 * S,
+ uint8_t numStages,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ int8_t postShift);
+
+
+ /**
+ * @brief Fast but less precise processing function for the Q15 Biquad cascade filter for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q15 Biquad cascade structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df1_fast_q15(
+ const arm_biquad_casd_df1_inst_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 Biquad cascade filter
+ * @param[in] *S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df1_q31(
+ const arm_biquad_casd_df1_inst_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Fast but less precise processing function for the Q31 Biquad cascade filter for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df1_fast_q31(
+ const arm_biquad_casd_df1_inst_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q31 Biquad cascade filter.
+ * @param[in,out] *S points to an instance of the Q31 Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] postShift Shift to be applied to the output. Varies according to the coefficients format
+ * @return none
+ */
+
+ void arm_biquad_cascade_df1_init_q31(
+ arm_biquad_casd_df1_inst_q31 * S,
+ uint8_t numStages,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ int8_t postShift);
+
+ /**
+ * @brief Processing function for the floating-point Biquad cascade filter.
+ * @param[in] *S points to an instance of the floating-point Biquad cascade structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df1_f32(
+ const arm_biquad_casd_df1_inst_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the floating-point Biquad cascade filter.
+ * @param[in,out] *S points to an instance of the floating-point Biquad cascade structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @return none
+ */
+
+ void arm_biquad_cascade_df1_init_f32(
+ arm_biquad_casd_df1_inst_f32 * S,
+ uint8_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+ /**
+ * @brief Instance structure for the floating-point matrix structure.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ float32_t *pData; /**< points to the data of the matrix. */
+ } arm_matrix_instance_f32;
+
+ /**
+ * @brief Instance structure for the Q15 matrix structure.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ q15_t *pData; /**< points to the data of the matrix. */
+
+ } arm_matrix_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 matrix structure.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows of the matrix. */
+ uint16_t numCols; /**< number of columns of the matrix. */
+ q31_t *pData; /**< points to the data of the matrix. */
+
+ } arm_matrix_instance_q31;
+
+
+
+ /**
+ * @brief Floating-point matrix addition.
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_add_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+ /**
+ * @brief Q15 matrix addition.
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_add_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst);
+
+ /**
+ * @brief Q31 matrix addition.
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_add_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix transpose.
+ * @param[in] *pSrc points to the input matrix
+ * @param[out] *pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_trans_f32(
+ const arm_matrix_instance_f32 * pSrc,
+ arm_matrix_instance_f32 * pDst);
+
+
+ /**
+ * @brief Q15 matrix transpose.
+ * @param[in] *pSrc points to the input matrix
+ * @param[out] *pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_trans_q15(
+ const arm_matrix_instance_q15 * pSrc,
+ arm_matrix_instance_q15 * pDst);
+
+ /**
+ * @brief Q31 matrix transpose.
+ * @param[in] *pSrc points to the input matrix
+ * @param[out] *pDst points to the output matrix
+ * @return The function returns either <code>ARM_MATH_SIZE_MISMATCH</code>
+ * or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_trans_q31(
+ const arm_matrix_instance_q31 * pSrc,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix multiplication
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_mult_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+ /**
+ * @brief Q15 matrix multiplication
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @param[in] *pState points to the array for storing intermediate results
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_mult_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst,
+ q15_t * pState);
+
+ /**
+ * @brief Q15 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @param[in] *pState points to the array for storing intermediate results
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_mult_fast_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst,
+ q15_t * pState);
+
+ /**
+ * @brief Q31 matrix multiplication
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_mult_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+ /**
+ * @brief Q31 matrix multiplication (fast variant) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_mult_fast_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Floating-point matrix subtraction
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_sub_f32(
+ const arm_matrix_instance_f32 * pSrcA,
+ const arm_matrix_instance_f32 * pSrcB,
+ arm_matrix_instance_f32 * pDst);
+
+ /**
+ * @brief Q15 matrix subtraction
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_sub_q15(
+ const arm_matrix_instance_q15 * pSrcA,
+ const arm_matrix_instance_q15 * pSrcB,
+ arm_matrix_instance_q15 * pDst);
+
+ /**
+ * @brief Q31 matrix subtraction
+ * @param[in] *pSrcA points to the first input matrix structure
+ * @param[in] *pSrcB points to the second input matrix structure
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_sub_q31(
+ const arm_matrix_instance_q31 * pSrcA,
+ const arm_matrix_instance_q31 * pSrcB,
+ arm_matrix_instance_q31 * pDst);
+
+ /**
+ * @brief Floating-point matrix scaling.
+ * @param[in] *pSrc points to the input matrix
+ * @param[in] scale scale factor
+ * @param[out] *pDst points to the output matrix
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_scale_f32(
+ const arm_matrix_instance_f32 * pSrc,
+ float32_t scale,
+ arm_matrix_instance_f32 * pDst);
+
+ /**
+ * @brief Q15 matrix scaling.
+ * @param[in] *pSrc points to input matrix
+ * @param[in] scaleFract fractional portion of the scale factor
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] *pDst points to output matrix
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_scale_q15(
+ const arm_matrix_instance_q15 * pSrc,
+ q15_t scaleFract,
+ int32_t shift,
+ arm_matrix_instance_q15 * pDst);
+
+ /**
+ * @brief Q31 matrix scaling.
+ * @param[in] *pSrc points to input matrix
+ * @param[in] scaleFract fractional portion of the scale factor
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] *pDst points to output matrix structure
+ * @return The function returns either
+ * <code>ARM_MATH_SIZE_MISMATCH</code> or <code>ARM_MATH_SUCCESS</code> based on the outcome of size checking.
+ */
+
+ arm_status arm_mat_scale_q31(
+ const arm_matrix_instance_q31 * pSrc,
+ q31_t scaleFract,
+ int32_t shift,
+ arm_matrix_instance_q31 * pDst);
+
+
+ /**
+ * @brief Q31 matrix initialization.
+ * @param[in,out] *S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] *pData points to the matrix data array.
+ * @return none
+ */
+
+ void arm_mat_init_q31(
+ arm_matrix_instance_q31 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ q31_t * pData);
+
+ /**
+ * @brief Q15 matrix initialization.
+ * @param[in,out] *S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] *pData points to the matrix data array.
+ * @return none
+ */
+
+ void arm_mat_init_q15(
+ arm_matrix_instance_q15 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ q15_t * pData);
+
+ /**
+ * @brief Floating-point matrix initialization.
+ * @param[in,out] *S points to an instance of the floating-point matrix structure.
+ * @param[in] nRows number of rows in the matrix.
+ * @param[in] nColumns number of columns in the matrix.
+ * @param[in] *pData points to the matrix data array.
+ * @return none
+ */
+
+ void arm_mat_init_f32(
+ arm_matrix_instance_f32 * S,
+ uint16_t nRows,
+ uint16_t nColumns,
+ float32_t * pData);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 PID Control.
+ */
+ typedef struct
+ {
+ q15_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+#ifdef ARM_MATH_CM0_FAMILY
+ q15_t A1;
+ q15_t A2;
+#else
+ q31_t A1; /**< The derived gain A1 = -Kp - 2Kd | Kd.*/
+#endif
+ q15_t state[3]; /**< The state array of length 3. */
+ q15_t Kp; /**< The proportional gain. */
+ q15_t Ki; /**< The integral gain. */
+ q15_t Kd; /**< The derivative gain. */
+ } arm_pid_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 PID Control.
+ */
+ typedef struct
+ {
+ q31_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+ q31_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
+ q31_t A2; /**< The derived gain, A2 = Kd . */
+ q31_t state[3]; /**< The state array of length 3. */
+ q31_t Kp; /**< The proportional gain. */
+ q31_t Ki; /**< The integral gain. */
+ q31_t Kd; /**< The derivative gain. */
+
+ } arm_pid_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point PID Control.
+ */
+ typedef struct
+ {
+ float32_t A0; /**< The derived gain, A0 = Kp + Ki + Kd . */
+ float32_t A1; /**< The derived gain, A1 = -Kp - 2Kd. */
+ float32_t A2; /**< The derived gain, A2 = Kd . */
+ float32_t state[3]; /**< The state array of length 3. */
+ float32_t Kp; /**< The proportional gain. */
+ float32_t Ki; /**< The integral gain. */
+ float32_t Kd; /**< The derivative gain. */
+ } arm_pid_instance_f32;
+
+
+
+ /**
+ * @brief Initialization function for the floating-point PID Control.
+ * @param[in,out] *S points to an instance of the PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ * @return none.
+ */
+ void arm_pid_init_f32(
+ arm_pid_instance_f32 * S,
+ int32_t resetStateFlag);
+
+ /**
+ * @brief Reset function for the floating-point PID Control.
+ * @param[in,out] *S is an instance of the floating-point PID Control structure
+ * @return none
+ */
+ void arm_pid_reset_f32(
+ arm_pid_instance_f32 * S);
+
+
+ /**
+ * @brief Initialization function for the Q31 PID Control.
+ * @param[in,out] *S points to an instance of the Q15 PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ * @return none.
+ */
+ void arm_pid_init_q31(
+ arm_pid_instance_q31 * S,
+ int32_t resetStateFlag);
+
+
+ /**
+ * @brief Reset function for the Q31 PID Control.
+ * @param[in,out] *S points to an instance of the Q31 PID Control structure
+ * @return none
+ */
+
+ void arm_pid_reset_q31(
+ arm_pid_instance_q31 * S);
+
+ /**
+ * @brief Initialization function for the Q15 PID Control.
+ * @param[in,out] *S points to an instance of the Q15 PID structure.
+ * @param[in] resetStateFlag flag to reset the state. 0 = no change in state 1 = reset the state.
+ * @return none.
+ */
+ void arm_pid_init_q15(
+ arm_pid_instance_q15 * S,
+ int32_t resetStateFlag);
+
+ /**
+ * @brief Reset function for the Q15 PID Control.
+ * @param[in,out] *S points to an instance of the q15 PID Control structure
+ * @return none
+ */
+ void arm_pid_reset_q15(
+ arm_pid_instance_q15 * S);
+
+
+ /**
+ * @brief Instance structure for the floating-point Linear Interpolate function.
+ */
+ typedef struct
+ {
+ uint32_t nValues; /**< nValues */
+ float32_t x1; /**< x1 */
+ float32_t xSpacing; /**< xSpacing */
+ float32_t *pYData; /**< pointer to the table of Y values */
+ } arm_linear_interp_instance_f32;
+
+ /**
+ * @brief Instance structure for the floating-point bilinear interpolation function.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ float32_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_f32;
+
+ /**
+ * @brief Instance structure for the Q31 bilinear interpolation function.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q31_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q31;
+
+ /**
+ * @brief Instance structure for the Q15 bilinear interpolation function.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q15_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q15 bilinear interpolation function.
+ */
+
+ typedef struct
+ {
+ uint16_t numRows; /**< number of rows in the data table. */
+ uint16_t numCols; /**< number of columns in the data table. */
+ q7_t *pData; /**< points to the data table. */
+ } arm_bilinear_interp_instance_q7;
+
+
+ /**
+ * @brief Q7 vector multiplication.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_mult_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q15 vector multiplication.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_mult_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q31 vector multiplication.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_mult_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Floating-point vector multiplication.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_mult_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+
+
+
+
+ /**
+ * @brief Instance structure for the Q15 CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q15_t *pTwiddle; /**< points to the Sin twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix2_instance_q15;
+
+ arm_status arm_cfft_radix2_init_q15(
+ arm_cfft_radix2_instance_q15 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ void arm_cfft_radix2_q15(
+ const arm_cfft_radix2_instance_q15 * S,
+ q15_t * pSrc);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q15_t *pTwiddle; /**< points to the twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix4_instance_q15;
+
+ arm_status arm_cfft_radix4_init_q15(
+ arm_cfft_radix4_instance_q15 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ void arm_cfft_radix4_q15(
+ const arm_cfft_radix4_instance_q15 * S,
+ q15_t * pSrc);
+
+ /**
+ * @brief Instance structure for the Radix-2 Q31 CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q31_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix2_instance_q31;
+
+ arm_status arm_cfft_radix2_init_q31(
+ arm_cfft_radix2_instance_q31 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ void arm_cfft_radix2_q31(
+ const arm_cfft_radix2_instance_q31 * S,
+ q31_t * pSrc);
+
+ /**
+ * @brief Instance structure for the Q31 CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ q31_t *pTwiddle; /**< points to the twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ } arm_cfft_radix4_instance_q31;
+
+
+ void arm_cfft_radix4_q31(
+ const arm_cfft_radix4_instance_q31 * S,
+ q31_t * pSrc);
+
+ arm_status arm_cfft_radix4_init_q31(
+ arm_cfft_radix4_instance_q31 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ float32_t onebyfftLen; /**< value of 1/fftLen. */
+ } arm_cfft_radix2_instance_f32;
+
+/* Deprecated */
+ arm_status arm_cfft_radix2_init_f32(
+ arm_cfft_radix2_instance_f32 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix2_f32(
+ const arm_cfft_radix2_instance_f32 * S,
+ float32_t * pSrc);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ uint8_t ifftFlag; /**< flag that selects forward (ifftFlag=0) or inverse (ifftFlag=1) transform. */
+ uint8_t bitReverseFlag; /**< flag that enables (bitReverseFlag=1) or disables (bitReverseFlag=0) bit reversal of output. */
+ float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t twidCoefModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ uint16_t bitRevFactor; /**< bit reversal modifier that supports different size FFTs with the same bit reversal table. */
+ float32_t onebyfftLen; /**< value of 1/fftLen. */
+ } arm_cfft_radix4_instance_f32;
+
+/* Deprecated */
+ arm_status arm_cfft_radix4_init_f32(
+ arm_cfft_radix4_instance_f32 * S,
+ uint16_t fftLen,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+/* Deprecated */
+ void arm_cfft_radix4_f32(
+ const arm_cfft_radix4_instance_f32 * S,
+ float32_t * pSrc);
+
+ /**
+ * @brief Instance structure for the floating-point CFFT/CIFFT function.
+ */
+
+ typedef struct
+ {
+ uint16_t fftLen; /**< length of the FFT. */
+ const float32_t *pTwiddle; /**< points to the Twiddle factor table. */
+ const uint16_t *pBitRevTable; /**< points to the bit reversal table. */
+ uint16_t bitRevLength; /**< bit reversal table length. */
+ } arm_cfft_instance_f32;
+
+ void arm_cfft_f32(
+ const arm_cfft_instance_f32 * S,
+ float32_t * p1,
+ uint8_t ifftFlag,
+ uint8_t bitReverseFlag);
+
+ /**
+ * @brief Instance structure for the Q15 RFFT/RIFFT function.
+ */
+
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint32_t fftLenBy2; /**< length of the complex FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ q15_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ q15_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_q15;
+
+ arm_status arm_rfft_init_q15(
+ arm_rfft_instance_q15 * S,
+ arm_cfft_radix4_instance_q15 * S_CFFT,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_q15(
+ const arm_rfft_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst);
+
+ /**
+ * @brief Instance structure for the Q31 RFFT/RIFFT function.
+ */
+
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint32_t fftLenBy2; /**< length of the complex FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ q31_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ q31_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_q31;
+
+ arm_status arm_rfft_init_q31(
+ arm_rfft_instance_q31 * S,
+ arm_cfft_radix4_instance_q31 * S_CFFT,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_q31(
+ const arm_rfft_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst);
+
+ /**
+ * @brief Instance structure for the floating-point RFFT/RIFFT function.
+ */
+
+ typedef struct
+ {
+ uint32_t fftLenReal; /**< length of the real FFT. */
+ uint16_t fftLenBy2; /**< length of the complex FFT. */
+ uint8_t ifftFlagR; /**< flag that selects forward (ifftFlagR=0) or inverse (ifftFlagR=1) transform. */
+ uint8_t bitReverseFlagR; /**< flag that enables (bitReverseFlagR=1) or disables (bitReverseFlagR=0) bit reversal of output. */
+ uint32_t twidCoefRModifier; /**< twiddle coefficient modifier that supports different size FFTs with the same twiddle factor table. */
+ float32_t *pTwiddleAReal; /**< points to the real twiddle factor table. */
+ float32_t *pTwiddleBReal; /**< points to the imag twiddle factor table. */
+ arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
+ } arm_rfft_instance_f32;
+
+ arm_status arm_rfft_init_f32(
+ arm_rfft_instance_f32 * S,
+ arm_cfft_radix4_instance_f32 * S_CFFT,
+ uint32_t fftLenReal,
+ uint32_t ifftFlagR,
+ uint32_t bitReverseFlag);
+
+ void arm_rfft_f32(
+ const arm_rfft_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst);
+
+ /**
+ * @brief Instance structure for the floating-point RFFT/RIFFT function.
+ */
+
+typedef struct
+ {
+ arm_cfft_instance_f32 Sint; /**< Internal CFFT structure. */
+ uint16_t fftLenRFFT; /**< length of the real sequence */
+ float32_t * pTwiddleRFFT; /**< Twiddle factors real stage */
+ } arm_rfft_fast_instance_f32 ;
+
+arm_status arm_rfft_fast_init_f32 (
+ arm_rfft_fast_instance_f32 * S,
+ uint16_t fftLen);
+
+void arm_rfft_fast_f32(
+ arm_rfft_fast_instance_f32 * S,
+ float32_t * p, float32_t * pOut,
+ uint8_t ifftFlag);
+
+ /**
+ * @brief Instance structure for the floating-point DCT4/IDCT4 function.
+ */
+
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ float32_t normalize; /**< normalizing factor. */
+ float32_t *pTwiddle; /**< points to the twiddle factor table. */
+ float32_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_f32 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_f32 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_f32;
+
+ /**
+ * @brief Initialization function for the floating-point DCT4/IDCT4.
+ * @param[in,out] *S points to an instance of floating-point DCT4/IDCT4 structure.
+ * @param[in] *S_RFFT points to an instance of floating-point RFFT/RIFFT structure.
+ * @param[in] *S_CFFT points to an instance of floating-point CFFT/CIFFT structure.
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>fftLenReal</code> is not a supported transform length.
+ */
+
+ arm_status arm_dct4_init_f32(
+ arm_dct4_instance_f32 * S,
+ arm_rfft_instance_f32 * S_RFFT,
+ arm_cfft_radix4_instance_f32 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ float32_t normalize);
+
+ /**
+ * @brief Processing function for the floating-point DCT4/IDCT4.
+ * @param[in] *S points to an instance of the floating-point DCT4/IDCT4 structure.
+ * @param[in] *pState points to state buffer.
+ * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
+ * @return none.
+ */
+
+ void arm_dct4_f32(
+ const arm_dct4_instance_f32 * S,
+ float32_t * pState,
+ float32_t * pInlineBuffer);
+
+ /**
+ * @brief Instance structure for the Q31 DCT4/IDCT4 function.
+ */
+
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ q31_t normalize; /**< normalizing factor. */
+ q31_t *pTwiddle; /**< points to the twiddle factor table. */
+ q31_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_q31 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_q31 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_q31;
+
+ /**
+ * @brief Initialization function for the Q31 DCT4/IDCT4.
+ * @param[in,out] *S points to an instance of Q31 DCT4/IDCT4 structure.
+ * @param[in] *S_RFFT points to an instance of Q31 RFFT/RIFFT structure
+ * @param[in] *S_CFFT points to an instance of Q31 CFFT/CIFFT structure
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
+ */
+
+ arm_status arm_dct4_init_q31(
+ arm_dct4_instance_q31 * S,
+ arm_rfft_instance_q31 * S_RFFT,
+ arm_cfft_radix4_instance_q31 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ q31_t normalize);
+
+ /**
+ * @brief Processing function for the Q31 DCT4/IDCT4.
+ * @param[in] *S points to an instance of the Q31 DCT4 structure.
+ * @param[in] *pState points to state buffer.
+ * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
+ * @return none.
+ */
+
+ void arm_dct4_q31(
+ const arm_dct4_instance_q31 * S,
+ q31_t * pState,
+ q31_t * pInlineBuffer);
+
+ /**
+ * @brief Instance structure for the Q15 DCT4/IDCT4 function.
+ */
+
+ typedef struct
+ {
+ uint16_t N; /**< length of the DCT4. */
+ uint16_t Nby2; /**< half of the length of the DCT4. */
+ q15_t normalize; /**< normalizing factor. */
+ q15_t *pTwiddle; /**< points to the twiddle factor table. */
+ q15_t *pCosFactor; /**< points to the cosFactor table. */
+ arm_rfft_instance_q15 *pRfft; /**< points to the real FFT instance. */
+ arm_cfft_radix4_instance_q15 *pCfft; /**< points to the complex FFT instance. */
+ } arm_dct4_instance_q15;
+
+ /**
+ * @brief Initialization function for the Q15 DCT4/IDCT4.
+ * @param[in,out] *S points to an instance of Q15 DCT4/IDCT4 structure.
+ * @param[in] *S_RFFT points to an instance of Q15 RFFT/RIFFT structure.
+ * @param[in] *S_CFFT points to an instance of Q15 CFFT/CIFFT structure.
+ * @param[in] N length of the DCT4.
+ * @param[in] Nby2 half of the length of the DCT4.
+ * @param[in] normalize normalizing factor.
+ * @return arm_status function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_ARGUMENT_ERROR if <code>N</code> is not a supported transform length.
+ */
+
+ arm_status arm_dct4_init_q15(
+ arm_dct4_instance_q15 * S,
+ arm_rfft_instance_q15 * S_RFFT,
+ arm_cfft_radix4_instance_q15 * S_CFFT,
+ uint16_t N,
+ uint16_t Nby2,
+ q15_t normalize);
+
+ /**
+ * @brief Processing function for the Q15 DCT4/IDCT4.
+ * @param[in] *S points to an instance of the Q15 DCT4 structure.
+ * @param[in] *pState points to state buffer.
+ * @param[in,out] *pInlineBuffer points to the in-place input and output buffer.
+ * @return none.
+ */
+
+ void arm_dct4_q15(
+ const arm_dct4_instance_q15 * S,
+ q15_t * pState,
+ q15_t * pInlineBuffer);
+
+ /**
+ * @brief Floating-point vector addition.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_add_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q7 vector addition.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_add_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q15 vector addition.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_add_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q31 vector addition.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_add_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Floating-point vector subtraction.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_sub_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q7 vector subtraction.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_sub_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q15 vector subtraction.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_sub_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q31 vector subtraction.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_sub_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Multiplies a floating-point vector by a scalar.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] scale scale factor to be applied
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_scale_f32(
+ float32_t * pSrc,
+ float32_t scale,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Multiplies a Q7 vector by a scalar.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_scale_q7(
+ q7_t * pSrc,
+ q7_t scaleFract,
+ int8_t shift,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Multiplies a Q15 vector by a scalar.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_scale_q15(
+ q15_t * pSrc,
+ q15_t scaleFract,
+ int8_t shift,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Multiplies a Q31 vector by a scalar.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] scaleFract fractional portion of the scale value
+ * @param[in] shift number of bits to shift the result by
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_scale_q31(
+ q31_t * pSrc,
+ q31_t scaleFract,
+ int8_t shift,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q7 vector absolute value.
+ * @param[in] *pSrc points to the input buffer
+ * @param[out] *pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_abs_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Floating-point vector absolute value.
+ * @param[in] *pSrc points to the input buffer
+ * @param[out] *pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_abs_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q15 vector absolute value.
+ * @param[in] *pSrc points to the input buffer
+ * @param[out] *pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_abs_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Q31 vector absolute value.
+ * @param[in] *pSrc points to the input buffer
+ * @param[out] *pDst points to the output buffer
+ * @param[in] blockSize number of samples in each vector
+ * @return none.
+ */
+
+ void arm_abs_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Dot product of floating-point vectors.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] *result output result returned here
+ * @return none.
+ */
+
+ void arm_dot_prod_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ uint32_t blockSize,
+ float32_t * result);
+
+ /**
+ * @brief Dot product of Q7 vectors.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] *result output result returned here
+ * @return none.
+ */
+
+ void arm_dot_prod_q7(
+ q7_t * pSrcA,
+ q7_t * pSrcB,
+ uint32_t blockSize,
+ q31_t * result);
+
+ /**
+ * @brief Dot product of Q15 vectors.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] *result output result returned here
+ * @return none.
+ */
+
+ void arm_dot_prod_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ uint32_t blockSize,
+ q63_t * result);
+
+ /**
+ * @brief Dot product of Q31 vectors.
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] blockSize number of samples in each vector
+ * @param[out] *result output result returned here
+ * @return none.
+ */
+
+ void arm_dot_prod_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ uint32_t blockSize,
+ q63_t * result);
+
+ /**
+ * @brief Shifts the elements of a Q7 vector a specified number of bits.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_shift_q7(
+ q7_t * pSrc,
+ int8_t shiftBits,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Shifts the elements of a Q15 vector a specified number of bits.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_shift_q15(
+ q15_t * pSrc,
+ int8_t shiftBits,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Shifts the elements of a Q31 vector a specified number of bits.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] shiftBits number of bits to shift. A positive value shifts left; a negative value shifts right.
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_shift_q31(
+ q31_t * pSrc,
+ int8_t shiftBits,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Adds a constant offset to a floating-point vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_offset_f32(
+ float32_t * pSrc,
+ float32_t offset,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Adds a constant offset to a Q7 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_offset_q7(
+ q7_t * pSrc,
+ q7_t offset,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Adds a constant offset to a Q15 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_offset_q15(
+ q15_t * pSrc,
+ q15_t offset,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Adds a constant offset to a Q31 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[in] offset is the offset to be added
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_offset_q31(
+ q31_t * pSrc,
+ q31_t offset,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Negates the elements of a floating-point vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_negate_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Negates the elements of a Q7 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_negate_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Negates the elements of a Q15 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_negate_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Negates the elements of a Q31 vector.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] blockSize number of samples in the vector
+ * @return none.
+ */
+
+ void arm_negate_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+ /**
+ * @brief Copies the elements of a floating-point vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_copy_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Copies the elements of a Q7 vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_copy_q7(
+ q7_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Copies the elements of a Q15 vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_copy_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Copies the elements of a Q31 vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_copy_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+ /**
+ * @brief Fills a constant value into a floating-point vector.
+ * @param[in] value input value to be filled
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_fill_f32(
+ float32_t value,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Fills a constant value into a Q7 vector.
+ * @param[in] value input value to be filled
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_fill_q7(
+ q7_t value,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Fills a constant value into a Q15 vector.
+ * @param[in] value input value to be filled
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_fill_q15(
+ q15_t value,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Fills a constant value into a Q31 vector.
+ * @param[in] value input value to be filled
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_fill_q31(
+ q31_t value,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+/**
+ * @brief Convolution of floating-point sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q15 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return none.
+ */
+
+
+ void arm_conv_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+/**
+ * @brief Convolution of Q15 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the location where the output result is written. Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+ /**
+ * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+ /**
+ * @brief Convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] *pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] *pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return none.
+ */
+
+ void arm_conv_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+
+ /**
+ * @brief Convolution of Q31 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+ /**
+ * @brief Convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+ /**
+ * @brief Convolution of Q7 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ * @return none.
+ */
+
+ void arm_conv_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+
+ /**
+ * @brief Convolution of Q7 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length srcALen+srcBLen-1.
+ * @return none.
+ */
+
+ void arm_conv_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst);
+
+
+ /**
+ * @brief Partial convolution of floating-point sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+ /**
+ * @brief Partial convolution of Q15 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+/**
+ * @brief Partial convolution of Q15 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+ /**
+ * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] * pScratch1 points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] * pScratch2 points to scratch buffer of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Partial convolution of Q31 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+ /**
+ * @brief Partial convolution of Q7 sequences
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+/**
+ * @brief Partial convolution of Q7 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] firstIndex is the first output sample to start with.
+ * @param[in] numPoints is the number of output points to be computed.
+ * @return Returns either ARM_MATH_SUCCESS if the function completed correctly or ARM_MATH_ARGUMENT_ERROR if the requested subset is not in the range [0 srcALen+srcBLen-2].
+ */
+
+ arm_status arm_conv_partial_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ uint32_t firstIndex,
+ uint32_t numPoints);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR decimator.
+ */
+
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ } arm_fir_decimate_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR decimator.
+ */
+
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+
+ } arm_fir_decimate_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR decimator.
+ */
+
+ typedef struct
+ {
+ uint8_t M; /**< decimation factor. */
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+
+ } arm_fir_decimate_instance_f32;
+
+
+
+ /**
+ * @brief Processing function for the floating-point FIR decimator.
+ * @param[in] *S points to an instance of the floating-point FIR decimator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none
+ */
+
+ void arm_fir_decimate_f32(
+ const arm_fir_decimate_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point FIR decimator.
+ * @param[in,out] *S points to an instance of the floating-point FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+
+ arm_status arm_fir_decimate_init_f32(
+ arm_fir_decimate_instance_f32 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q15 FIR decimator.
+ * @param[in] *S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none
+ */
+
+ void arm_fir_decimate_q15(
+ const arm_fir_decimate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q15 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none
+ */
+
+ void arm_fir_decimate_fast_q15(
+ const arm_fir_decimate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR decimator.
+ * @param[in,out] *S points to an instance of the Q15 FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+
+ arm_status arm_fir_decimate_init_q15(
+ arm_fir_decimate_instance_q15 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 FIR decimator.
+ * @param[in] *S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none
+ */
+
+ void arm_fir_decimate_q31(
+ const arm_fir_decimate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 FIR decimator (fast variant) for Cortex-M3 and Cortex-M4.
+ * @param[in] *S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none
+ */
+
+ void arm_fir_decimate_fast_q31(
+ arm_fir_decimate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 FIR decimator.
+ * @param[in,out] *S points to an instance of the Q31 FIR decimator structure.
+ * @param[in] numTaps number of coefficients in the filter.
+ * @param[in] M decimation factor.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * <code>blockSize</code> is not a multiple of <code>M</code>.
+ */
+
+ arm_status arm_fir_decimate_init_q31(
+ arm_fir_decimate_instance_q31 * S,
+ uint16_t numTaps,
+ uint8_t M,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR interpolator.
+ */
+
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ q15_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
+ } arm_fir_interpolate_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR interpolator.
+ */
+
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ q31_t *pState; /**< points to the state variable array. The array is of length blockSize+phaseLength-1. */
+ } arm_fir_interpolate_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR interpolator.
+ */
+
+ typedef struct
+ {
+ uint8_t L; /**< upsample factor. */
+ uint16_t phaseLength; /**< length of each polyphase filter component. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length L*phaseLength. */
+ float32_t *pState; /**< points to the state variable array. The array is of length phaseLength+numTaps-1. */
+ } arm_fir_interpolate_instance_f32;
+
+
+ /**
+ * @brief Processing function for the Q15 FIR interpolator.
+ * @param[in] *S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_interpolate_q15(
+ const arm_fir_interpolate_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 FIR interpolator.
+ * @param[in,out] *S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficient buffer.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+
+ arm_status arm_fir_interpolate_init_q15(
+ arm_fir_interpolate_instance_q15 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 FIR interpolator.
+ * @param[in] *S points to an instance of the Q15 FIR interpolator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_interpolate_q31(
+ const arm_fir_interpolate_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q31 FIR interpolator.
+ * @param[in,out] *S points to an instance of the Q31 FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficient buffer.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+
+ arm_status arm_fir_interpolate_init_q31(
+ arm_fir_interpolate_instance_q31 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the floating-point FIR interpolator.
+ * @param[in] *S points to an instance of the floating-point FIR interpolator structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_interpolate_f32(
+ const arm_fir_interpolate_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the floating-point FIR interpolator.
+ * @param[in,out] *S points to an instance of the floating-point FIR interpolator structure.
+ * @param[in] L upsample factor.
+ * @param[in] numTaps number of filter coefficients in the filter.
+ * @param[in] *pCoeffs points to the filter coefficient buffer.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return The function returns ARM_MATH_SUCCESS if initialization is successful or ARM_MATH_LENGTH_ERROR if
+ * the filter length <code>numTaps</code> is not a multiple of the interpolation factor <code>L</code>.
+ */
+
+ arm_status arm_fir_interpolate_init_f32(
+ arm_fir_interpolate_instance_f32 * S,
+ uint8_t L,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Instance structure for the high precision Q31 Biquad cascade filter.
+ */
+
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ q63_t *pState; /**< points to the array of state coefficients. The array is of length 4*numStages. */
+ q31_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ uint8_t postShift; /**< additional shift, in bits, applied to each output sample. */
+
+ } arm_biquad_cas_df1_32x64_ins_q31;
+
+
+ /**
+ * @param[in] *S points to an instance of the high precision Q31 Biquad cascade filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cas_df1_32x64_q31(
+ const arm_biquad_cas_df1_32x64_ins_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @param[in,out] *S points to an instance of the high precision Q31 Biquad cascade filter structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] postShift shift to be applied to the output. Varies according to the coefficients format
+ * @return none
+ */
+
+ void arm_biquad_cas_df1_32x64_init_q31(
+ arm_biquad_cas_df1_32x64_ins_q31 * S,
+ uint8_t numStages,
+ q31_t * pCoeffs,
+ q63_t * pState,
+ uint8_t postShift);
+
+
+
+ /**
+ * @brief Instance structure for the floating-point transposed direct form II Biquad cascade filter.
+ */
+
+ typedef struct
+ {
+ uint8_t numStages; /**< number of 2nd order stages in the filter. Overall order is 2*numStages. */
+ float32_t *pState; /**< points to the array of state coefficients. The array is of length 2*numStages. */
+ float32_t *pCoeffs; /**< points to the array of coefficients. The array is of length 5*numStages. */
+ } arm_biquad_cascade_df2T_instance_f32;
+
+
+ /**
+ * @brief Processing function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in] *S points to an instance of the filter data structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_biquad_cascade_df2T_f32(
+ const arm_biquad_cascade_df2T_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the floating-point transposed direct form II Biquad cascade filter.
+ * @param[in,out] *S points to an instance of the filter data structure.
+ * @param[in] numStages number of 2nd order stages in the filter.
+ * @param[in] *pCoeffs points to the filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @return none
+ */
+
+ void arm_biquad_cascade_df2T_init_f32(
+ arm_biquad_cascade_df2T_instance_f32 * S,
+ uint8_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+
+
+ /**
+ * @brief Instance structure for the Q15 FIR lattice filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 FIR lattice filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point FIR lattice filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numStages; /**< number of filter stages. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numStages. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numStages. */
+ } arm_fir_lattice_instance_f32;
+
+ /**
+ * @brief Initialization function for the Q15 FIR lattice filter.
+ * @param[in] *S points to an instance of the Q15 FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] *pState points to the state buffer. The array is of length numStages.
+ * @return none.
+ */
+
+ void arm_fir_lattice_init_q15(
+ arm_fir_lattice_instance_q15 * S,
+ uint16_t numStages,
+ q15_t * pCoeffs,
+ q15_t * pState);
+
+
+ /**
+ * @brief Processing function for the Q15 FIR lattice filter.
+ * @param[in] *S points to an instance of the Q15 FIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+ void arm_fir_lattice_q15(
+ const arm_fir_lattice_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q31 FIR lattice filter.
+ * @param[in] *S points to an instance of the Q31 FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] *pState points to the state buffer. The array is of length numStages.
+ * @return none.
+ */
+
+ void arm_fir_lattice_init_q31(
+ arm_fir_lattice_instance_q31 * S,
+ uint16_t numStages,
+ q31_t * pCoeffs,
+ q31_t * pState);
+
+
+ /**
+ * @brief Processing function for the Q31 FIR lattice filter.
+ * @param[in] *S points to an instance of the Q31 FIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_fir_lattice_q31(
+ const arm_fir_lattice_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+/**
+ * @brief Initialization function for the floating-point FIR lattice filter.
+ * @param[in] *S points to an instance of the floating-point FIR lattice structure.
+ * @param[in] numStages number of filter stages.
+ * @param[in] *pCoeffs points to the coefficient buffer. The array is of length numStages.
+ * @param[in] *pState points to the state buffer. The array is of length numStages.
+ * @return none.
+ */
+
+ void arm_fir_lattice_init_f32(
+ arm_fir_lattice_instance_f32 * S,
+ uint16_t numStages,
+ float32_t * pCoeffs,
+ float32_t * pState);
+
+ /**
+ * @brief Processing function for the floating-point FIR lattice filter.
+ * @param[in] *S points to an instance of the floating-point FIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_fir_lattice_f32(
+ const arm_fir_lattice_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Instance structure for the Q15 IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ q15_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ q15_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q31 IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ q31_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ q31_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_q31;
+
+ /**
+ * @brief Instance structure for the floating-point IIR lattice filter.
+ */
+ typedef struct
+ {
+ uint16_t numStages; /**< number of stages in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numStages+blockSize. */
+ float32_t *pkCoeffs; /**< points to the reflection coefficient array. The array is of length numStages. */
+ float32_t *pvCoeffs; /**< points to the ladder coefficient array. The array is of length numStages+1. */
+ } arm_iir_lattice_instance_f32;
+
+ /**
+ * @brief Processing function for the floating-point IIR lattice filter.
+ * @param[in] *S points to an instance of the floating-point IIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_iir_lattice_f32(
+ const arm_iir_lattice_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the floating-point IIR lattice filter.
+ * @param[in] *S points to an instance of the floating-point IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
+ * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize-1.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_iir_lattice_init_f32(
+ arm_iir_lattice_instance_f32 * S,
+ uint16_t numStages,
+ float32_t * pkCoeffs,
+ float32_t * pvCoeffs,
+ float32_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q31 IIR lattice filter.
+ * @param[in] *S points to an instance of the Q31 IIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_iir_lattice_q31(
+ const arm_iir_lattice_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q31 IIR lattice filter.
+ * @param[in] *S points to an instance of the Q31 IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] *pkCoeffs points to the reflection coefficient buffer. The array is of length numStages.
+ * @param[in] *pvCoeffs points to the ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] *pState points to the state buffer. The array is of length numStages+blockSize.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_iir_lattice_init_q31(
+ arm_iir_lattice_instance_q31 * S,
+ uint16_t numStages,
+ q31_t * pkCoeffs,
+ q31_t * pvCoeffs,
+ q31_t * pState,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Processing function for the Q15 IIR lattice filter.
+ * @param[in] *S points to an instance of the Q15 IIR lattice structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_iir_lattice_q15(
+ const arm_iir_lattice_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+/**
+ * @brief Initialization function for the Q15 IIR lattice filter.
+ * @param[in] *S points to an instance of the fixed-point Q15 IIR lattice structure.
+ * @param[in] numStages number of stages in the filter.
+ * @param[in] *pkCoeffs points to reflection coefficient buffer. The array is of length numStages.
+ * @param[in] *pvCoeffs points to ladder coefficient buffer. The array is of length numStages+1.
+ * @param[in] *pState points to state buffer. The array is of length numStages+blockSize.
+ * @param[in] blockSize number of samples to process per call.
+ * @return none.
+ */
+
+ void arm_iir_lattice_init_q15(
+ arm_iir_lattice_instance_q15 * S,
+ uint16_t numStages,
+ q15_t * pkCoeffs,
+ q15_t * pvCoeffs,
+ q15_t * pState,
+ uint32_t blockSize);
+
+ /**
+ * @brief Instance structure for the floating-point LMS filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ float32_t mu; /**< step size that controls filter coefficient updates. */
+ } arm_lms_instance_f32;
+
+ /**
+ * @brief Processing function for floating-point LMS filter.
+ * @param[in] *S points to an instance of the floating-point LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_f32(
+ const arm_lms_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pRef,
+ float32_t * pOut,
+ float32_t * pErr,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for floating-point LMS filter.
+ * @param[in] *S points to an instance of the floating-point LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to the coefficient buffer.
+ * @param[in] *pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_init_f32(
+ arm_lms_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ float32_t mu,
+ uint32_t blockSize);
+
+ /**
+ * @brief Instance structure for the Q15 LMS filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q15_t mu; /**< step size that controls filter coefficient updates. */
+ uint32_t postShift; /**< bit shift applied to coefficients. */
+ } arm_lms_instance_q15;
+
+
+ /**
+ * @brief Initialization function for the Q15 LMS filter.
+ * @param[in] *S points to an instance of the Q15 LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to the coefficient buffer.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ * @return none.
+ */
+
+ void arm_lms_init_q15(
+ arm_lms_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ q15_t mu,
+ uint32_t blockSize,
+ uint32_t postShift);
+
+ /**
+ * @brief Processing function for Q15 LMS filter.
+ * @param[in] *S points to an instance of the Q15 LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_q15(
+ const arm_lms_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pRef,
+ q15_t * pOut,
+ q15_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q31 LMS filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q31_t mu; /**< step size that controls filter coefficient updates. */
+ uint32_t postShift; /**< bit shift applied to coefficients. */
+
+ } arm_lms_instance_q31;
+
+ /**
+ * @brief Processing function for Q31 LMS filter.
+ * @param[in] *S points to an instance of the Q15 LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_q31(
+ const arm_lms_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pRef,
+ q31_t * pOut,
+ q31_t * pErr,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for Q31 LMS filter.
+ * @param[in] *S points to an instance of the Q31 LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to coefficient buffer.
+ * @param[in] *pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ * @return none.
+ */
+
+ void arm_lms_init_q31(
+ arm_lms_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ q31_t mu,
+ uint32_t blockSize,
+ uint32_t postShift);
+
+ /**
+ * @brief Instance structure for the floating-point normalized LMS filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ float32_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ float32_t mu; /**< step size that control filter coefficient updates. */
+ float32_t energy; /**< saves previous frame energy. */
+ float32_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_f32;
+
+ /**
+ * @brief Processing function for floating-point normalized LMS filter.
+ * @param[in] *S points to an instance of the floating-point normalized LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_norm_f32(
+ arm_lms_norm_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pRef,
+ float32_t * pOut,
+ float32_t * pErr,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for floating-point normalized LMS filter.
+ * @param[in] *S points to an instance of the floating-point LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to coefficient buffer.
+ * @param[in] *pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_norm_init_f32(
+ arm_lms_norm_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ float32_t mu,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Instance structure for the Q31 normalized LMS filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ q31_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q31_t mu; /**< step size that controls filter coefficient updates. */
+ uint8_t postShift; /**< bit shift applied to coefficients. */
+ q31_t *recipTable; /**< points to the reciprocal initial value table. */
+ q31_t energy; /**< saves previous frame energy. */
+ q31_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_q31;
+
+ /**
+ * @brief Processing function for Q31 normalized LMS filter.
+ * @param[in] *S points to an instance of the Q31 normalized LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_norm_q31(
+ arm_lms_norm_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pRef,
+ q31_t * pOut,
+ q31_t * pErr,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for Q31 normalized LMS filter.
+ * @param[in] *S points to an instance of the Q31 normalized LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to coefficient buffer.
+ * @param[in] *pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ * @return none.
+ */
+
+ void arm_lms_norm_init_q31(
+ arm_lms_norm_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ q31_t mu,
+ uint32_t blockSize,
+ uint8_t postShift);
+
+ /**
+ * @brief Instance structure for the Q15 normalized LMS filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< Number of coefficients in the filter. */
+ q15_t *pState; /**< points to the state variable array. The array is of length numTaps+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps. */
+ q15_t mu; /**< step size that controls filter coefficient updates. */
+ uint8_t postShift; /**< bit shift applied to coefficients. */
+ q15_t *recipTable; /**< Points to the reciprocal initial value table. */
+ q15_t energy; /**< saves previous frame energy. */
+ q15_t x0; /**< saves previous input sample. */
+ } arm_lms_norm_instance_q15;
+
+ /**
+ * @brief Processing function for Q15 normalized LMS filter.
+ * @param[in] *S points to an instance of the Q15 normalized LMS filter structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[in] *pRef points to the block of reference data.
+ * @param[out] *pOut points to the block of output data.
+ * @param[out] *pErr points to the block of error data.
+ * @param[in] blockSize number of samples to process.
+ * @return none.
+ */
+
+ void arm_lms_norm_q15(
+ arm_lms_norm_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pRef,
+ q15_t * pOut,
+ q15_t * pErr,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for Q15 normalized LMS filter.
+ * @param[in] *S points to an instance of the Q15 normalized LMS filter structure.
+ * @param[in] numTaps number of filter coefficients.
+ * @param[in] *pCoeffs points to coefficient buffer.
+ * @param[in] *pState points to state buffer.
+ * @param[in] mu step size that controls filter coefficient updates.
+ * @param[in] blockSize number of samples to process.
+ * @param[in] postShift bit shift applied to coefficients.
+ * @return none.
+ */
+
+ void arm_lms_norm_init_q15(
+ arm_lms_norm_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ q15_t mu,
+ uint32_t blockSize,
+ uint8_t postShift);
+
+ /**
+ * @brief Correlation of floating-point sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_f32(
+ float32_t * pSrcA,
+ uint32_t srcALen,
+ float32_t * pSrcB,
+ uint32_t srcBLen,
+ float32_t * pDst);
+
+
+ /**
+ * @brief Correlation of Q15 sequences
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @return none.
+ */
+ void arm_correlate_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch);
+
+
+ /**
+ * @brief Correlation of Q15 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+ /**
+ * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_fast_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst);
+
+
+
+ /**
+ * @brief Correlation of Q15 sequences (fast version) for Cortex-M3 and Cortex-M4.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] *pScratch points to scratch buffer of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @return none.
+ */
+
+ void arm_correlate_fast_opt_q15(
+ q15_t * pSrcA,
+ uint32_t srcALen,
+ q15_t * pSrcB,
+ uint32_t srcBLen,
+ q15_t * pDst,
+ q15_t * pScratch);
+
+ /**
+ * @brief Correlation of Q31 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+ /**
+ * @brief Correlation of Q31 sequences (fast version) for Cortex-M3 and Cortex-M4
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_fast_q31(
+ q31_t * pSrcA,
+ uint32_t srcALen,
+ q31_t * pSrcB,
+ uint32_t srcBLen,
+ q31_t * pDst);
+
+
+
+ /**
+ * @brief Correlation of Q7 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @param[in] *pScratch1 points to scratch buffer(of type q15_t) of size max(srcALen, srcBLen) + 2*min(srcALen, srcBLen) - 2.
+ * @param[in] *pScratch2 points to scratch buffer (of type q15_t) of size min(srcALen, srcBLen).
+ * @return none.
+ */
+
+ void arm_correlate_opt_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst,
+ q15_t * pScratch1,
+ q15_t * pScratch2);
+
+
+ /**
+ * @brief Correlation of Q7 sequences.
+ * @param[in] *pSrcA points to the first input sequence.
+ * @param[in] srcALen length of the first input sequence.
+ * @param[in] *pSrcB points to the second input sequence.
+ * @param[in] srcBLen length of the second input sequence.
+ * @param[out] *pDst points to the block of output data Length 2 * max(srcALen, srcBLen) - 1.
+ * @return none.
+ */
+
+ void arm_correlate_q7(
+ q7_t * pSrcA,
+ uint32_t srcALen,
+ q7_t * pSrcB,
+ uint32_t srcBLen,
+ q7_t * pDst);
+
+
+ /**
+ * @brief Instance structure for the floating-point sparse FIR filter.
+ */
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ float32_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ float32_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_f32;
+
+ /**
+ * @brief Instance structure for the Q31 sparse FIR filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q31_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q31_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q31;
+
+ /**
+ * @brief Instance structure for the Q15 sparse FIR filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q15_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q15_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q15;
+
+ /**
+ * @brief Instance structure for the Q7 sparse FIR filter.
+ */
+
+ typedef struct
+ {
+ uint16_t numTaps; /**< number of coefficients in the filter. */
+ uint16_t stateIndex; /**< state buffer index. Points to the oldest sample in the state buffer. */
+ q7_t *pState; /**< points to the state buffer array. The array is of length maxDelay+blockSize-1. */
+ q7_t *pCoeffs; /**< points to the coefficient array. The array is of length numTaps.*/
+ uint16_t maxDelay; /**< maximum offset specified by the pTapDelay array. */
+ int32_t *pTapDelay; /**< points to the array of delay values. The array is of length numTaps. */
+ } arm_fir_sparse_instance_q7;
+
+ /**
+ * @brief Processing function for the floating-point sparse FIR filter.
+ * @param[in] *S points to an instance of the floating-point sparse FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_sparse_f32(
+ arm_fir_sparse_instance_f32 * S,
+ float32_t * pSrc,
+ float32_t * pDst,
+ float32_t * pScratchIn,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the floating-point sparse FIR filter.
+ * @param[in,out] *S points to an instance of the floating-point sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] *pCoeffs points to the array of filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] *pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ * @return none
+ */
+
+ void arm_fir_sparse_init_f32(
+ arm_fir_sparse_instance_f32 * S,
+ uint16_t numTaps,
+ float32_t * pCoeffs,
+ float32_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q31 sparse FIR filter.
+ * @param[in] *S points to an instance of the Q31 sparse FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_sparse_q31(
+ arm_fir_sparse_instance_q31 * S,
+ q31_t * pSrc,
+ q31_t * pDst,
+ q31_t * pScratchIn,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q31 sparse FIR filter.
+ * @param[in,out] *S points to an instance of the Q31 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] *pCoeffs points to the array of filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] *pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ * @return none
+ */
+
+ void arm_fir_sparse_init_q31(
+ arm_fir_sparse_instance_q31 * S,
+ uint16_t numTaps,
+ q31_t * pCoeffs,
+ q31_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q15 sparse FIR filter.
+ * @param[in] *S points to an instance of the Q15 sparse FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] *pScratchOut points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_sparse_q15(
+ arm_fir_sparse_instance_q15 * S,
+ q15_t * pSrc,
+ q15_t * pDst,
+ q15_t * pScratchIn,
+ q31_t * pScratchOut,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Initialization function for the Q15 sparse FIR filter.
+ * @param[in,out] *S points to an instance of the Q15 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] *pCoeffs points to the array of filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] *pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ * @return none
+ */
+
+ void arm_fir_sparse_init_q15(
+ arm_fir_sparse_instance_q15 * S,
+ uint16_t numTaps,
+ q15_t * pCoeffs,
+ q15_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+ /**
+ * @brief Processing function for the Q7 sparse FIR filter.
+ * @param[in] *S points to an instance of the Q7 sparse FIR structure.
+ * @param[in] *pSrc points to the block of input data.
+ * @param[out] *pDst points to the block of output data
+ * @param[in] *pScratchIn points to a temporary buffer of size blockSize.
+ * @param[in] *pScratchOut points to a temporary buffer of size blockSize.
+ * @param[in] blockSize number of input samples to process per call.
+ * @return none.
+ */
+
+ void arm_fir_sparse_q7(
+ arm_fir_sparse_instance_q7 * S,
+ q7_t * pSrc,
+ q7_t * pDst,
+ q7_t * pScratchIn,
+ q31_t * pScratchOut,
+ uint32_t blockSize);
+
+ /**
+ * @brief Initialization function for the Q7 sparse FIR filter.
+ * @param[in,out] *S points to an instance of the Q7 sparse FIR structure.
+ * @param[in] numTaps number of nonzero coefficients in the filter.
+ * @param[in] *pCoeffs points to the array of filter coefficients.
+ * @param[in] *pState points to the state buffer.
+ * @param[in] *pTapDelay points to the array of offset times.
+ * @param[in] maxDelay maximum offset time supported.
+ * @param[in] blockSize number of samples that will be processed per block.
+ * @return none
+ */
+
+ void arm_fir_sparse_init_q7(
+ arm_fir_sparse_instance_q7 * S,
+ uint16_t numTaps,
+ q7_t * pCoeffs,
+ q7_t * pState,
+ int32_t * pTapDelay,
+ uint16_t maxDelay,
+ uint32_t blockSize);
+
+
+ /*
+ * @brief Floating-point sin_cos function.
+ * @param[in] theta input value in degrees
+ * @param[out] *pSinVal points to the processed sine output.
+ * @param[out] *pCosVal points to the processed cos output.
+ * @return none.
+ */
+
+ void arm_sin_cos_f32(
+ float32_t theta,
+ float32_t * pSinVal,
+ float32_t * pCcosVal);
+
+ /*
+ * @brief Q31 sin_cos function.
+ * @param[in] theta scaled input value in degrees
+ * @param[out] *pSinVal points to the processed sine output.
+ * @param[out] *pCosVal points to the processed cosine output.
+ * @return none.
+ */
+
+ void arm_sin_cos_q31(
+ q31_t theta,
+ q31_t * pSinVal,
+ q31_t * pCosVal);
+
+
+ /**
+ * @brief Floating-point complex conjugate.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_conj_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex conjugate.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_conj_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q15 complex conjugate.
+ * @param[in] *pSrc points to the input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_conj_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+
+ /**
+ * @brief Floating-point complex magnitude squared
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_squared_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex magnitude squared
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_squared_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q15 complex magnitude squared
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_squared_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup PID PID Motor Control
+ *
+ * A Proportional Integral Derivative (PID) controller is a generic feedback control
+ * loop mechanism widely used in industrial control systems.
+ * A PID controller is the most commonly used type of feedback controller.
+ *
+ * This set of functions implements (PID) controllers
+ * for Q15, Q31, and floating-point data types. The functions operate on a single sample
+ * of data and each call to the function returns a single processed value.
+ * <code>S</code> points to an instance of the PID control data structure. <code>in</code>
+ * is the input sample value. The functions return the output value.
+ *
+ * \par Algorithm:
+ * <pre>
+ * y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2]
+ * A0 = Kp + Ki + Kd
+ * A1 = (-Kp ) - (2 * Kd )
+ * A2 = Kd </pre>
+ *
+ * \par
+ * where \c Kp is proportional constant, \c Ki is Integral constant and \c Kd is Derivative constant
+ *
+ * \par
+ * \image html PID.gif "Proportional Integral Derivative Controller"
+ *
+ * \par
+ * The PID controller calculates an "error" value as the difference between
+ * the measured output and the reference input.
+ * The controller attempts to minimize the error by adjusting the process control inputs.
+ * The proportional value determines the reaction to the current error,
+ * the integral value determines the reaction based on the sum of recent errors,
+ * and the derivative value determines the reaction based on the rate at which the error has been changing.
+ *
+ * \par Instance Structure
+ * The Gains A0, A1, A2 and state variables for a PID controller are stored together in an instance data structure.
+ * A separate instance structure must be defined for each PID Controller.
+ * There are separate instance structure declarations for each of the 3 supported data types.
+ *
+ * \par Reset Functions
+ * There is also an associated reset function for each data type which clears the state array.
+ *
+ * \par Initialization Functions
+ * There is also an associated initialization function for each data type.
+ * The initialization function performs the following operations:
+ * - Initializes the Gains A0, A1, A2 from Kp,Ki, Kd gains.
+ * - Zeros out the values in the state buffer.
+ *
+ * \par
+ * Instance structure cannot be placed into a const data section and it is recommended to use the initialization function.
+ *
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the fixed-point versions of the PID Controller functions.
+ * In particular, the overflow and saturation behavior of the accumulator used in each function must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup PID
+ * @{
+ */
+
+ /**
+ * @brief Process function for the floating-point PID Control.
+ * @param[in,out] *S is an instance of the floating-point PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ */
+
+
+ static __INLINE float32_t arm_pid_f32(
+ arm_pid_instance_f32 * S,
+ float32_t in)
+ {
+ float32_t out;
+
+ /* y[n] = y[n-1] + A0 * x[n] + A1 * x[n-1] + A2 * x[n-2] */
+ out = (S->A0 * in) +
+ (S->A1 * S->state[0]) + (S->A2 * S->state[1]) + (S->state[2]);
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+
+ }
+
+ /**
+ * @brief Process function for the Q31 PID Control.
+ * @param[in,out] *S points to an instance of the Q31 PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 64-bit accumulator.
+ * The accumulator has a 2.62 format and maintains full precision of the intermediate multiplication results but provides only a single guard bit.
+ * Thus, if the accumulator result overflows it wraps around rather than clip.
+ * In order to avoid overflows completely the input signal must be scaled down by 2 bits as there are four additions.
+ * After all multiply-accumulates are performed, the 2.62 accumulator is truncated to 1.32 format and then saturated to 1.31 format.
+ */
+
+ static __INLINE q31_t arm_pid_q31(
+ arm_pid_instance_q31 * S,
+ q31_t in)
+ {
+ q63_t acc;
+ q31_t out;
+
+ /* acc = A0 * x[n] */
+ acc = (q63_t) S->A0 * in;
+
+ /* acc += A1 * x[n-1] */
+ acc += (q63_t) S->A1 * S->state[0];
+
+ /* acc += A2 * x[n-2] */
+ acc += (q63_t) S->A2 * S->state[1];
+
+ /* convert output to 1.31 format to add y[n-1] */
+ out = (q31_t) (acc >> 31u);
+
+ /* out += y[n-1] */
+ out += S->state[2];
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+
+ }
+
+ /**
+ * @brief Process function for the Q15 PID Control.
+ * @param[in,out] *S points to an instance of the Q15 PID Control structure
+ * @param[in] in input sample to process
+ * @return out processed output sample.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using a 64-bit internal accumulator.
+ * Both Gains and state variables are represented in 1.15 format and multiplications yield a 2.30 result.
+ * The 2.30 intermediate results are accumulated in a 64-bit accumulator in 34.30 format.
+ * There is no risk of internal overflow with this approach and the full precision of intermediate multiplications is preserved.
+ * After all additions have been performed, the accumulator is truncated to 34.15 format by discarding low 15 bits.
+ * Lastly, the accumulator is saturated to yield a result in 1.15 format.
+ */
+
+ static __INLINE q15_t arm_pid_q15(
+ arm_pid_instance_q15 * S,
+ q15_t in)
+ {
+ q63_t acc;
+ q15_t out;
+
+#ifndef ARM_MATH_CM0_FAMILY
+ __SIMD32_TYPE *vstate;
+
+ /* Implementation of PID controller */
+
+ /* acc = A0 * x[n] */
+ acc = (q31_t) __SMUAD(S->A0, in);
+
+ /* acc += A1 * x[n-1] + A2 * x[n-2] */
+ vstate = __SIMD32_CONST(S->state);
+ acc = __SMLALD(S->A1, (q31_t) *vstate, acc);
+
+#else
+ /* acc = A0 * x[n] */
+ acc = ((q31_t) S->A0) * in;
+
+ /* acc += A1 * x[n-1] + A2 * x[n-2] */
+ acc += (q31_t) S->A1 * S->state[0];
+ acc += (q31_t) S->A2 * S->state[1];
+
+#endif
+
+ /* acc += y[n-1] */
+ acc += (q31_t) S->state[2] << 15;
+
+ /* saturate the output */
+ out = (q15_t) (__SSAT((acc >> 15), 16));
+
+ /* Update state */
+ S->state[1] = S->state[0];
+ S->state[0] = in;
+ S->state[2] = out;
+
+ /* return to application */
+ return (out);
+
+ }
+
+ /**
+ * @} end of PID group
+ */
+
+
+ /**
+ * @brief Floating-point matrix inverse.
+ * @param[in] *src points to the instance of the input floating-point matrix structure.
+ * @param[out] *dst points to the instance of the output floating-point matrix structure.
+ * @return The function returns ARM_MATH_SIZE_MISMATCH, if the dimensions do not match.
+ * If the input matrix is singular (does not have an inverse), then the algorithm terminates and returns error status ARM_MATH_SINGULAR.
+ */
+
+ arm_status arm_mat_inverse_f32(
+ const arm_matrix_instance_f32 * src,
+ arm_matrix_instance_f32 * dst);
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+
+ /**
+ * @defgroup clarke Vector Clarke Transform
+ * Forward Clarke transform converts the instantaneous stator phases into a two-coordinate time invariant vector.
+ * Generally the Clarke transform uses three-phase currents <code>Ia, Ib and Ic</code> to calculate currents
+ * in the two-phase orthogonal stator axis <code>Ialpha</code> and <code>Ibeta</code>.
+ * When <code>Ialpha</code> is superposed with <code>Ia</code> as shown in the figure below
+ * \image html clarke.gif Stator current space vector and its components in (a,b).
+ * and <code>Ia + Ib + Ic = 0</code>, in this condition <code>Ialpha</code> and <code>Ibeta</code>
+ * can be calculated using only <code>Ia</code> and <code>Ib</code>.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html clarkeFormula.gif
+ * where <code>Ia</code> and <code>Ib</code> are the instantaneous stator phases and
+ * <code>pIalpha</code> and <code>pIbeta</code> are the two coordinates of time invariant vector.
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Clarke transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup clarke
+ * @{
+ */
+
+ /**
+ *
+ * @brief Floating-point Clarke transform
+ * @param[in] Ia input three-phase coordinate <code>a</code>
+ * @param[in] Ib input three-phase coordinate <code>b</code>
+ * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
+ * @return none.
+ */
+
+ static __INLINE void arm_clarke_f32(
+ float32_t Ia,
+ float32_t Ib,
+ float32_t * pIalpha,
+ float32_t * pIbeta)
+ {
+ /* Calculate pIalpha using the equation, pIalpha = Ia */
+ *pIalpha = Ia;
+
+ /* Calculate pIbeta using the equation, pIbeta = (1/sqrt(3)) * Ia + (2/sqrt(3)) * Ib */
+ *pIbeta =
+ ((float32_t) 0.57735026919 * Ia + (float32_t) 1.15470053838 * Ib);
+
+ }
+
+ /**
+ * @brief Clarke transform for Q31 version
+ * @param[in] Ia input three-phase coordinate <code>a</code>
+ * @param[in] Ib input three-phase coordinate <code>b</code>
+ * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
+ * @return none.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition, hence there is no risk of overflow.
+ */
+
+ static __INLINE void arm_clarke_q31(
+ q31_t Ia,
+ q31_t Ib,
+ q31_t * pIalpha,
+ q31_t * pIbeta)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+
+ /* Calculating pIalpha from Ia by equation pIalpha = Ia */
+ *pIalpha = Ia;
+
+ /* Intermediate product is calculated by (1/(sqrt(3)) * Ia) */
+ product1 = (q31_t) (((q63_t) Ia * 0x24F34E8B) >> 30);
+
+ /* Intermediate product is calculated by (2/sqrt(3) * Ib) */
+ product2 = (q31_t) (((q63_t) Ib * 0x49E69D16) >> 30);
+
+ /* pIbeta is calculated by adding the intermediate products */
+ *pIbeta = __QADD(product1, product2);
+ }
+
+ /**
+ * @} end of clarke group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to Q31 vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_q7_to_q31(
+ q7_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup inv_clarke Vector Inverse Clarke Transform
+ * Inverse Clarke transform converts the two-coordinate time invariant vector into instantaneous stator phases.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html clarkeInvFormula.gif
+ * where <code>pIa</code> and <code>pIb</code> are the instantaneous stator phases and
+ * <code>Ialpha</code> and <code>Ibeta</code> are the two coordinates of time invariant vector.
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Clarke transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup inv_clarke
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Inverse Clarke transform
+ * @param[in] Ialpha input two-phase orthogonal vector axis alpha
+ * @param[in] Ibeta input two-phase orthogonal vector axis beta
+ * @param[out] *pIa points to output three-phase coordinate <code>a</code>
+ * @param[out] *pIb points to output three-phase coordinate <code>b</code>
+ * @return none.
+ */
+
+
+ static __INLINE void arm_inv_clarke_f32(
+ float32_t Ialpha,
+ float32_t Ibeta,
+ float32_t * pIa,
+ float32_t * pIb)
+ {
+ /* Calculating pIa from Ialpha by equation pIa = Ialpha */
+ *pIa = Ialpha;
+
+ /* Calculating pIb from Ialpha and Ibeta by equation pIb = -(1/2) * Ialpha + (sqrt(3)/2) * Ibeta */
+ *pIb = -0.5 * Ialpha + (float32_t) 0.8660254039 *Ibeta;
+
+ }
+
+ /**
+ * @brief Inverse Clarke transform for Q31 version
+ * @param[in] Ialpha input two-phase orthogonal vector axis alpha
+ * @param[in] Ibeta input two-phase orthogonal vector axis beta
+ * @param[out] *pIa points to output three-phase coordinate <code>a</code>
+ * @param[out] *pIb points to output three-phase coordinate <code>b</code>
+ * @return none.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the subtraction, hence there is no risk of overflow.
+ */
+
+ static __INLINE void arm_inv_clarke_q31(
+ q31_t Ialpha,
+ q31_t Ibeta,
+ q31_t * pIa,
+ q31_t * pIb)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+
+ /* Calculating pIa from Ialpha by equation pIa = Ialpha */
+ *pIa = Ialpha;
+
+ /* Intermediate product is calculated by (1/(2*sqrt(3)) * Ia) */
+ product1 = (q31_t) (((q63_t) (Ialpha) * (0x40000000)) >> 31);
+
+ /* Intermediate product is calculated by (1/sqrt(3) * pIb) */
+ product2 = (q31_t) (((q63_t) (Ibeta) * (0x6ED9EBA1)) >> 31);
+
+ /* pIb is calculated by subtracting the products */
+ *pIb = __QSUB(product2, product1);
+
+ }
+
+ /**
+ * @} end of inv_clarke group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to Q15 vector.
+ * @param[in] *pSrc input pointer
+ * @param[out] *pDst output pointer
+ * @param[in] blockSize number of samples to process
+ * @return none.
+ */
+ void arm_q7_to_q15(
+ q7_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup park Vector Park Transform
+ *
+ * Forward Park transform converts the input two-coordinate vector to flux and torque components.
+ * The Park transform can be used to realize the transformation of the <code>Ialpha</code> and the <code>Ibeta</code> currents
+ * from the stationary to the moving reference frame and control the spatial relationship between
+ * the stator vector current and rotor flux vector.
+ * If we consider the d axis aligned with the rotor flux, the diagram below shows the
+ * current vector and the relationship from the two reference frames:
+ * \image html park.gif "Stator current space vector and its component in (a,b) and in the d,q rotating reference frame"
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html parkFormula.gif
+ * where <code>Ialpha</code> and <code>Ibeta</code> are the stator vector components,
+ * <code>pId</code> and <code>pIq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
+ * cosine and sine values of theta (rotor flux position).
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Park transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup park
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Park transform
+ * @param[in] Ialpha input two-phase vector coordinate alpha
+ * @param[in] Ibeta input two-phase vector coordinate beta
+ * @param[out] *pId points to output rotor reference frame d
+ * @param[out] *pIq points to output rotor reference frame q
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ * @return none.
+ *
+ * The function implements the forward Park transform.
+ *
+ */
+
+ static __INLINE void arm_park_f32(
+ float32_t Ialpha,
+ float32_t Ibeta,
+ float32_t * pId,
+ float32_t * pIq,
+ float32_t sinVal,
+ float32_t cosVal)
+ {
+ /* Calculate pId using the equation, pId = Ialpha * cosVal + Ibeta * sinVal */
+ *pId = Ialpha * cosVal + Ibeta * sinVal;
+
+ /* Calculate pIq using the equation, pIq = - Ialpha * sinVal + Ibeta * cosVal */
+ *pIq = -Ialpha * sinVal + Ibeta * cosVal;
+
+ }
+
+ /**
+ * @brief Park transform for Q31 version
+ * @param[in] Ialpha input two-phase vector coordinate alpha
+ * @param[in] Ibeta input two-phase vector coordinate beta
+ * @param[out] *pId points to output rotor reference frame d
+ * @param[out] *pIq points to output rotor reference frame q
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ * @return none.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition and subtraction, hence there is no risk of overflow.
+ */
+
+
+ static __INLINE void arm_park_q31(
+ q31_t Ialpha,
+ q31_t Ibeta,
+ q31_t * pId,
+ q31_t * pIq,
+ q31_t sinVal,
+ q31_t cosVal)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+ q31_t product3, product4; /* Temporary variables used to store intermediate results */
+
+ /* Intermediate product is calculated by (Ialpha * cosVal) */
+ product1 = (q31_t) (((q63_t) (Ialpha) * (cosVal)) >> 31);
+
+ /* Intermediate product is calculated by (Ibeta * sinVal) */
+ product2 = (q31_t) (((q63_t) (Ibeta) * (sinVal)) >> 31);
+
+
+ /* Intermediate product is calculated by (Ialpha * sinVal) */
+ product3 = (q31_t) (((q63_t) (Ialpha) * (sinVal)) >> 31);
+
+ /* Intermediate product is calculated by (Ibeta * cosVal) */
+ product4 = (q31_t) (((q63_t) (Ibeta) * (cosVal)) >> 31);
+
+ /* Calculate pId by adding the two intermediate products 1 and 2 */
+ *pId = __QADD(product1, product2);
+
+ /* Calculate pIq by subtracting the two intermediate products 3 from 4 */
+ *pIq = __QSUB(product4, product3);
+ }
+
+ /**
+ * @} end of park group
+ */
+
+ /**
+ * @brief Converts the elements of the Q7 vector to floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q7_to_float(
+ q7_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @ingroup groupController
+ */
+
+ /**
+ * @defgroup inv_park Vector Inverse Park transform
+ * Inverse Park transform converts the input flux and torque components to two-coordinate vector.
+ *
+ * The function operates on a single sample of data and each call to the function returns the processed output.
+ * The library provides separate functions for Q31 and floating-point data types.
+ * \par Algorithm
+ * \image html parkInvFormula.gif
+ * where <code>pIalpha</code> and <code>pIbeta</code> are the stator vector components,
+ * <code>Id</code> and <code>Iq</code> are rotor vector components and <code>cosVal</code> and <code>sinVal</code> are the
+ * cosine and sine values of theta (rotor flux position).
+ * \par Fixed-Point Behavior
+ * Care must be taken when using the Q31 version of the Park transform.
+ * In particular, the overflow and saturation behavior of the accumulator used must be considered.
+ * Refer to the function specific documentation below for usage guidelines.
+ */
+
+ /**
+ * @addtogroup inv_park
+ * @{
+ */
+
+ /**
+ * @brief Floating-point Inverse Park transform
+ * @param[in] Id input coordinate of rotor reference frame d
+ * @param[in] Iq input coordinate of rotor reference frame q
+ * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ * @return none.
+ */
+
+ static __INLINE void arm_inv_park_f32(
+ float32_t Id,
+ float32_t Iq,
+ float32_t * pIalpha,
+ float32_t * pIbeta,
+ float32_t sinVal,
+ float32_t cosVal)
+ {
+ /* Calculate pIalpha using the equation, pIalpha = Id * cosVal - Iq * sinVal */
+ *pIalpha = Id * cosVal - Iq * sinVal;
+
+ /* Calculate pIbeta using the equation, pIbeta = Id * sinVal + Iq * cosVal */
+ *pIbeta = Id * sinVal + Iq * cosVal;
+
+ }
+
+
+ /**
+ * @brief Inverse Park transform for Q31 version
+ * @param[in] Id input coordinate of rotor reference frame d
+ * @param[in] Iq input coordinate of rotor reference frame q
+ * @param[out] *pIalpha points to output two-phase orthogonal vector axis alpha
+ * @param[out] *pIbeta points to output two-phase orthogonal vector axis beta
+ * @param[in] sinVal sine value of rotation angle theta
+ * @param[in] cosVal cosine value of rotation angle theta
+ * @return none.
+ *
+ * <b>Scaling and Overflow Behavior:</b>
+ * \par
+ * The function is implemented using an internal 32-bit accumulator.
+ * The accumulator maintains 1.31 format by truncating lower 31 bits of the intermediate multiplication in 2.62 format.
+ * There is saturation on the addition, hence there is no risk of overflow.
+ */
+
+
+ static __INLINE void arm_inv_park_q31(
+ q31_t Id,
+ q31_t Iq,
+ q31_t * pIalpha,
+ q31_t * pIbeta,
+ q31_t sinVal,
+ q31_t cosVal)
+ {
+ q31_t product1, product2; /* Temporary variables used to store intermediate results */
+ q31_t product3, product4; /* Temporary variables used to store intermediate results */
+
+ /* Intermediate product is calculated by (Id * cosVal) */
+ product1 = (q31_t) (((q63_t) (Id) * (cosVal)) >> 31);
+
+ /* Intermediate product is calculated by (Iq * sinVal) */
+ product2 = (q31_t) (((q63_t) (Iq) * (sinVal)) >> 31);
+
+
+ /* Intermediate product is calculated by (Id * sinVal) */
+ product3 = (q31_t) (((q63_t) (Id) * (sinVal)) >> 31);
+
+ /* Intermediate product is calculated by (Iq * cosVal) */
+ product4 = (q31_t) (((q63_t) (Iq) * (cosVal)) >> 31);
+
+ /* Calculate pIalpha by using the two intermediate products 1 and 2 */
+ *pIalpha = __QSUB(product1, product2);
+
+ /* Calculate pIbeta by using the two intermediate products 3 and 4 */
+ *pIbeta = __QADD(product4, product3);
+
+ }
+
+ /**
+ * @} end of Inverse park group
+ */
+
+
+ /**
+ * @brief Converts the elements of the Q31 vector to floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q31_to_float(
+ q31_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @ingroup groupInterpolation
+ */
+
+ /**
+ * @defgroup LinearInterpolate Linear Interpolation
+ *
+ * Linear interpolation is a method of curve fitting using linear polynomials.
+ * Linear interpolation works by effectively drawing a straight line between two neighboring samples and returning the appropriate point along that line
+ *
+ * \par
+ * \image html LinearInterp.gif "Linear interpolation"
+ *
+ * \par
+ * A Linear Interpolate function calculates an output value(y), for the input(x)
+ * using linear interpolation of the input values x0, x1( nearest input values) and the output values y0 and y1(nearest output values)
+ *
+ * \par Algorithm:
+ * <pre>
+ * y = y0 + (x - x0) * ((y1 - y0)/(x1-x0))
+ * where x0, x1 are nearest values of input x
+ * y0, y1 are nearest values to output y
+ * </pre>
+ *
+ * \par
+ * This set of functions implements Linear interpolation process
+ * for Q7, Q15, Q31, and floating-point data types. The functions operate on a single
+ * sample of data and each call to the function returns a single processed value.
+ * <code>S</code> points to an instance of the Linear Interpolate function data structure.
+ * <code>x</code> is the input sample value. The functions returns the output value.
+ *
+ * \par
+ * if x is outside of the table boundary, Linear interpolation returns first value of the table
+ * if x is below input range and returns last value of table if x is above range.
+ */
+
+ /**
+ * @addtogroup LinearInterpolate
+ * @{
+ */
+
+ /**
+ * @brief Process function for the floating-point Linear Interpolation Function.
+ * @param[in,out] *S is an instance of the floating-point Linear Interpolation structure
+ * @param[in] x input sample to process
+ * @return y processed output sample.
+ *
+ */
+
+ static __INLINE float32_t arm_linear_interp_f32(
+ arm_linear_interp_instance_f32 * S,
+ float32_t x)
+ {
+
+ float32_t y;
+ float32_t x0, x1; /* Nearest input values */
+ float32_t y0, y1; /* Nearest output values */
+ float32_t xSpacing = S->xSpacing; /* spacing between input values */
+ int32_t i; /* Index variable */
+ float32_t *pYData = S->pYData; /* pointer to output table */
+
+ /* Calculation of index */
+ i = (int32_t) ((x - S->x1) / xSpacing);
+
+ if(i < 0)
+ {
+ /* Iniatilize output for below specified range as least output value of table */
+ y = pYData[0];
+ }
+ else if((uint32_t)i >= S->nValues)
+ {
+ /* Iniatilize output for above specified range as last output value of table */
+ y = pYData[S->nValues - 1];
+ }
+ else
+ {
+ /* Calculation of nearest input values */
+ x0 = S->x1 + i * xSpacing;
+ x1 = S->x1 + (i + 1) * xSpacing;
+
+ /* Read of nearest output values */
+ y0 = pYData[i];
+ y1 = pYData[i + 1];
+
+ /* Calculation of output */
+ y = y0 + (x - x0) * ((y1 - y0) / (x1 - x0));
+
+ }
+
+ /* returns output value */
+ return (y);
+ }
+
+ /**
+ *
+ * @brief Process function for the Q31 Linear Interpolation Function.
+ * @param[in] *pYData pointer to Q31 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ *
+ */
+
+
+ static __INLINE q31_t arm_linear_interp_q31(
+ q31_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q31_t y; /* output */
+ q31_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ int32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ index = ((x & 0xFFF00000) >> 20);
+
+ if(index >= (int32_t)(nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else if(index < 0)
+ {
+ return (pYData[0]);
+ }
+ else
+ {
+
+ /* 20 bits for the fractional part */
+ /* shift left by 11 to keep fract in 1.31 format */
+ fract = (x & 0x000FFFFF) << 11;
+
+ /* Read two nearest output values from the index in 1.31(q31) format */
+ y0 = pYData[index];
+ y1 = pYData[index + 1u];
+
+ /* Calculation of y0 * (1-fract) and y is in 2.30 format */
+ y = ((q31_t) ((q63_t) y0 * (0x7FFFFFFF - fract) >> 32));
+
+ /* Calculation of y0 * (1-fract) + y1 *fract and y is in 2.30 format */
+ y += ((q31_t) (((q63_t) y1 * fract) >> 32));
+
+ /* Convert y to 1.31 format */
+ return (y << 1u);
+
+ }
+
+ }
+
+ /**
+ *
+ * @brief Process function for the Q15 Linear Interpolation Function.
+ * @param[in] *pYData pointer to Q15 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ *
+ */
+
+
+ static __INLINE q15_t arm_linear_interp_q15(
+ q15_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q63_t y; /* output */
+ q15_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ int32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ index = ((x & 0xFFF00000) >> 20u);
+
+ if(index >= (int32_t)(nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else if(index < 0)
+ {
+ return (pYData[0]);
+ }
+ else
+ {
+ /* 20 bits for the fractional part */
+ /* fract is in 12.20 format */
+ fract = (x & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y0 = pYData[index];
+ y1 = pYData[index + 1u];
+
+ /* Calculation of y0 * (1-fract) and y is in 13.35 format */
+ y = ((q63_t) y0 * (0xFFFFF - fract));
+
+ /* Calculation of (y0 * (1-fract) + y1 * fract) and y is in 13.35 format */
+ y += ((q63_t) y1 * (fract));
+
+ /* convert y to 1.15 format */
+ return (y >> 20);
+ }
+
+
+ }
+
+ /**
+ *
+ * @brief Process function for the Q7 Linear Interpolation Function.
+ * @param[in] *pYData pointer to Q7 Linear Interpolation table
+ * @param[in] x input sample to process
+ * @param[in] nValues number of table values
+ * @return y processed output sample.
+ *
+ * \par
+ * Input sample <code>x</code> is in 12.20 format which contains 12 bits for table index and 20 bits for fractional part.
+ * This function can support maximum of table size 2^12.
+ */
+
+
+ static __INLINE q7_t arm_linear_interp_q7(
+ q7_t * pYData,
+ q31_t x,
+ uint32_t nValues)
+ {
+ q31_t y; /* output */
+ q7_t y0, y1; /* Nearest output values */
+ q31_t fract; /* fractional part */
+ uint32_t index; /* Index to read nearest output values */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ if (x < 0)
+ {
+ return (pYData[0]);
+ }
+ index = (x >> 20) & 0xfff;
+
+
+ if(index >= (nValues - 1))
+ {
+ return (pYData[nValues - 1]);
+ }
+ else
+ {
+
+ /* 20 bits for the fractional part */
+ /* fract is in 12.20 format */
+ fract = (x & 0x000FFFFF);
+
+ /* Read two nearest output values from the index and are in 1.7(q7) format */
+ y0 = pYData[index];
+ y1 = pYData[index + 1u];
+
+ /* Calculation of y0 * (1-fract ) and y is in 13.27(q27) format */
+ y = ((y0 * (0xFFFFF - fract)));
+
+ /* Calculation of y1 * fract + y0 * (1-fract) and y is in 13.27(q27) format */
+ y += (y1 * fract);
+
+ /* convert y to 1.7(q7) format */
+ return (y >> 20u);
+
+ }
+
+ }
+ /**
+ * @} end of LinearInterpolate group
+ */
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for floating-point data.
+ * @param[in] x input value in radians.
+ * @return sin(x).
+ */
+
+ float32_t arm_sin_f32(
+ float32_t x);
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for Q31 data.
+ * @param[in] x Scaled input value in radians.
+ * @return sin(x).
+ */
+
+ q31_t arm_sin_q31(
+ q31_t x);
+
+ /**
+ * @brief Fast approximation to the trigonometric sine function for Q15 data.
+ * @param[in] x Scaled input value in radians.
+ * @return sin(x).
+ */
+
+ q15_t arm_sin_q15(
+ q15_t x);
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for floating-point data.
+ * @param[in] x input value in radians.
+ * @return cos(x).
+ */
+
+ float32_t arm_cos_f32(
+ float32_t x);
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for Q31 data.
+ * @param[in] x Scaled input value in radians.
+ * @return cos(x).
+ */
+
+ q31_t arm_cos_q31(
+ q31_t x);
+
+ /**
+ * @brief Fast approximation to the trigonometric cosine function for Q15 data.
+ * @param[in] x Scaled input value in radians.
+ * @return cos(x).
+ */
+
+ q15_t arm_cos_q15(
+ q15_t x);
+
+
+ /**
+ * @ingroup groupFastMath
+ */
+
+
+ /**
+ * @defgroup SQRT Square Root
+ *
+ * Computes the square root of a number.
+ * There are separate functions for Q15, Q31, and floating-point data types.
+ * The square root function is computed using the Newton-Raphson algorithm.
+ * This is an iterative algorithm of the form:
+ * <pre>
+ * x1 = x0 - f(x0)/f'(x0)
+ * </pre>
+ * where <code>x1</code> is the current estimate,
+ * <code>x0</code> is the previous estimate, and
+ * <code>f'(x0)</code> is the derivative of <code>f()</code> evaluated at <code>x0</code>.
+ * For the square root function, the algorithm reduces to:
+ * <pre>
+ * x0 = in/2 [initial guess]
+ * x1 = 1/2 * ( x0 + in / x0) [each iteration]
+ * </pre>
+ */
+
+
+ /**
+ * @addtogroup SQRT
+ * @{
+ */
+
+ /**
+ * @brief Floating-point square root function.
+ * @param[in] in input value.
+ * @param[out] *pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+
+ static __INLINE arm_status arm_sqrt_f32(
+ float32_t in,
+ float32_t * pOut)
+ {
+ if(in > 0)
+ {
+
+// #if __FPU_USED
+#if (__FPU_USED == 1) && defined ( __CC_ARM )
+ *pOut = __sqrtf(in);
+#else
+ *pOut = sqrtf(in);
+#endif
+
+ return (ARM_MATH_SUCCESS);
+ }
+ else
+ {
+ *pOut = 0.0f;
+ return (ARM_MATH_ARGUMENT_ERROR);
+ }
+
+ }
+
+
+ /**
+ * @brief Q31 square root function.
+ * @param[in] in input value. The range of the input value is [0 +1) or 0x00000000 to 0x7FFFFFFF.
+ * @param[out] *pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+ arm_status arm_sqrt_q31(
+ q31_t in,
+ q31_t * pOut);
+
+ /**
+ * @brief Q15 square root function.
+ * @param[in] in input value. The range of the input value is [0 +1) or 0x0000 to 0x7FFF.
+ * @param[out] *pOut square root of input value.
+ * @return The function returns ARM_MATH_SUCCESS if input value is positive value or ARM_MATH_ARGUMENT_ERROR if
+ * <code>in</code> is negative value and returns zero output for negative values.
+ */
+ arm_status arm_sqrt_q15(
+ q15_t in,
+ q15_t * pOut);
+
+ /**
+ * @} end of SQRT group
+ */
+
+
+
+
+
+
+ /**
+ * @brief floating-point Circular write function.
+ */
+
+ static __INLINE void arm_circularWrite_f32(
+ int32_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const int32_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0u;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if(wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = wOffset;
+ }
+
+
+
+ /**
+ * @brief floating-point Circular Read function.
+ */
+ static __INLINE void arm_circularRead_f32(
+ int32_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ int32_t * dst,
+ int32_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0u;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if(dst == (int32_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update rOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if(rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+ /**
+ * @brief Q15 Circular write function.
+ */
+
+ static __INLINE void arm_circularWrite_q15(
+ q15_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const q15_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0u;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if(wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = wOffset;
+ }
+
+
+
+ /**
+ * @brief Q15 Circular Read function.
+ */
+ static __INLINE void arm_circularRead_q15(
+ q15_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ q15_t * dst,
+ q15_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if(dst == (q15_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if(rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+
+ /**
+ * @brief Q7 Circular write function.
+ */
+
+ static __INLINE void arm_circularWrite_q7(
+ q7_t * circBuffer,
+ int32_t L,
+ uint16_t * writeOffset,
+ int32_t bufferInc,
+ const q7_t * src,
+ int32_t srcInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0u;
+ int32_t wOffset;
+
+ /* Copy the value of Index pointer that points
+ * to the current location where the input samples to be copied */
+ wOffset = *writeOffset;
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the input sample to the circular buffer */
+ circBuffer[wOffset] = *src;
+
+ /* Update the input pointer */
+ src += srcInc;
+
+ /* Circularly update wOffset. Watch out for positive and negative value */
+ wOffset += bufferInc;
+ if(wOffset >= L)
+ wOffset -= L;
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *writeOffset = wOffset;
+ }
+
+
+
+ /**
+ * @brief Q7 Circular Read function.
+ */
+ static __INLINE void arm_circularRead_q7(
+ q7_t * circBuffer,
+ int32_t L,
+ int32_t * readOffset,
+ int32_t bufferInc,
+ q7_t * dst,
+ q7_t * dst_base,
+ int32_t dst_length,
+ int32_t dstInc,
+ uint32_t blockSize)
+ {
+ uint32_t i = 0;
+ int32_t rOffset, dst_end;
+
+ /* Copy the value of Index pointer that points
+ * to the current location from where the input samples to be read */
+ rOffset = *readOffset;
+
+ dst_end = (int32_t) (dst_base + dst_length);
+
+ /* Loop over the blockSize */
+ i = blockSize;
+
+ while(i > 0u)
+ {
+ /* copy the sample from the circular buffer to the destination buffer */
+ *dst = circBuffer[rOffset];
+
+ /* Update the input pointer */
+ dst += dstInc;
+
+ if(dst == (q7_t *) dst_end)
+ {
+ dst = dst_base;
+ }
+
+ /* Circularly update rOffset. Watch out for positive and negative value */
+ rOffset += bufferInc;
+
+ if(rOffset >= L)
+ {
+ rOffset -= L;
+ }
+
+ /* Decrement the loop counter */
+ i--;
+ }
+
+ /* Update the index pointer */
+ *readOffset = rOffset;
+ }
+
+
+ /**
+ * @brief Sum of the squares of the elements of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_power_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q63_t * pResult);
+
+ /**
+ * @brief Sum of the squares of the elements of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_power_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+ /**
+ * @brief Sum of the squares of the elements of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_power_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q63_t * pResult);
+
+ /**
+ * @brief Sum of the squares of the elements of a Q7 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_power_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+ /**
+ * @brief Mean value of a Q7 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_mean_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * pResult);
+
+ /**
+ * @brief Mean value of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+ void arm_mean_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+ /**
+ * @brief Mean value of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+ void arm_mean_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+ /**
+ * @brief Mean value of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+ void arm_mean_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+ /**
+ * @brief Variance of the elements of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_var_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+ /**
+ * @brief Variance of the elements of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_var_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q63_t * pResult);
+
+ /**
+ * @brief Variance of the elements of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_var_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+ /**
+ * @brief Root Mean Square of the elements of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_rms_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+ /**
+ * @brief Root Mean Square of the elements of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_rms_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+ /**
+ * @brief Root Mean Square of the elements of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_rms_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+ /**
+ * @brief Standard deviation of the elements of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_std_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult);
+
+ /**
+ * @brief Standard deviation of the elements of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_std_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult);
+
+ /**
+ * @brief Standard deviation of the elements of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output value.
+ * @return none.
+ */
+
+ void arm_std_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult);
+
+ /**
+ * @brief Floating-point complex magnitude
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_f32(
+ float32_t * pSrc,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex magnitude
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_q31(
+ q31_t * pSrc,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q15 complex magnitude
+ * @param[in] *pSrc points to the complex input vector
+ * @param[out] *pDst points to the real output vector
+ * @param[in] numSamples number of complex samples in the input vector
+ * @return none.
+ */
+
+ void arm_cmplx_mag_q15(
+ q15_t * pSrc,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q15 complex dot product
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] *realResult real part of the result returned here
+ * @param[out] *imagResult imaginary part of the result returned here
+ * @return none.
+ */
+
+ void arm_cmplx_dot_prod_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ uint32_t numSamples,
+ q31_t * realResult,
+ q31_t * imagResult);
+
+ /**
+ * @brief Q31 complex dot product
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] *realResult real part of the result returned here
+ * @param[out] *imagResult imaginary part of the result returned here
+ * @return none.
+ */
+
+ void arm_cmplx_dot_prod_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ uint32_t numSamples,
+ q63_t * realResult,
+ q63_t * imagResult);
+
+ /**
+ * @brief Floating-point complex dot product
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @param[out] *realResult real part of the result returned here
+ * @param[out] *imagResult imaginary part of the result returned here
+ * @return none.
+ */
+
+ void arm_cmplx_dot_prod_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ uint32_t numSamples,
+ float32_t * realResult,
+ float32_t * imagResult);
+
+ /**
+ * @brief Q15 complex-by-real multiplication
+ * @param[in] *pSrcCmplx points to the complex input vector
+ * @param[in] *pSrcReal points to the real input vector
+ * @param[out] *pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_real_q15(
+ q15_t * pSrcCmplx,
+ q15_t * pSrcReal,
+ q15_t * pCmplxDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex-by-real multiplication
+ * @param[in] *pSrcCmplx points to the complex input vector
+ * @param[in] *pSrcReal points to the real input vector
+ * @param[out] *pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_real_q31(
+ q31_t * pSrcCmplx,
+ q31_t * pSrcReal,
+ q31_t * pCmplxDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Floating-point complex-by-real multiplication
+ * @param[in] *pSrcCmplx points to the complex input vector
+ * @param[in] *pSrcReal points to the real input vector
+ * @param[out] *pCmplxDst points to the complex output vector
+ * @param[in] numSamples number of samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_real_f32(
+ float32_t * pSrcCmplx,
+ float32_t * pSrcReal,
+ float32_t * pCmplxDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Minimum value of a Q7 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *result is output pointer
+ * @param[in] index is the array index of the minimum value in the input buffer.
+ * @return none.
+ */
+
+ void arm_min_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * result,
+ uint32_t * index);
+
+ /**
+ * @brief Minimum value of a Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output pointer
+ * @param[in] *pIndex is the array index of the minimum value in the input buffer.
+ * @return none.
+ */
+
+ void arm_min_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult,
+ uint32_t * pIndex);
+
+ /**
+ * @brief Minimum value of a Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output pointer
+ * @param[out] *pIndex is the array index of the minimum value in the input buffer.
+ * @return none.
+ */
+ void arm_min_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult,
+ uint32_t * pIndex);
+
+ /**
+ * @brief Minimum value of a floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[in] blockSize is the number of samples to process
+ * @param[out] *pResult is output pointer
+ * @param[out] *pIndex is the array index of the minimum value in the input buffer.
+ * @return none.
+ */
+
+ void arm_min_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult,
+ uint32_t * pIndex);
+
+/**
+ * @brief Maximum value of a Q7 vector.
+ * @param[in] *pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] *pResult maximum value returned here
+ * @param[out] *pIndex index of maximum value returned here
+ * @return none.
+ */
+
+ void arm_max_q7(
+ q7_t * pSrc,
+ uint32_t blockSize,
+ q7_t * pResult,
+ uint32_t * pIndex);
+
+/**
+ * @brief Maximum value of a Q15 vector.
+ * @param[in] *pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] *pResult maximum value returned here
+ * @param[out] *pIndex index of maximum value returned here
+ * @return none.
+ */
+
+ void arm_max_q15(
+ q15_t * pSrc,
+ uint32_t blockSize,
+ q15_t * pResult,
+ uint32_t * pIndex);
+
+/**
+ * @brief Maximum value of a Q31 vector.
+ * @param[in] *pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] *pResult maximum value returned here
+ * @param[out] *pIndex index of maximum value returned here
+ * @return none.
+ */
+
+ void arm_max_q31(
+ q31_t * pSrc,
+ uint32_t blockSize,
+ q31_t * pResult,
+ uint32_t * pIndex);
+
+/**
+ * @brief Maximum value of a floating-point vector.
+ * @param[in] *pSrc points to the input buffer
+ * @param[in] blockSize length of the input vector
+ * @param[out] *pResult maximum value returned here
+ * @param[out] *pIndex index of maximum value returned here
+ * @return none.
+ */
+
+ void arm_max_f32(
+ float32_t * pSrc,
+ uint32_t blockSize,
+ float32_t * pResult,
+ uint32_t * pIndex);
+
+ /**
+ * @brief Q15 complex-by-complex multiplication
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_cmplx_q15(
+ q15_t * pSrcA,
+ q15_t * pSrcB,
+ q15_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Q31 complex-by-complex multiplication
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_cmplx_q31(
+ q31_t * pSrcA,
+ q31_t * pSrcB,
+ q31_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Floating-point complex-by-complex multiplication
+ * @param[in] *pSrcA points to the first input vector
+ * @param[in] *pSrcB points to the second input vector
+ * @param[out] *pDst points to the output vector
+ * @param[in] numSamples number of complex samples in each vector
+ * @return none.
+ */
+
+ void arm_cmplx_mult_cmplx_f32(
+ float32_t * pSrcA,
+ float32_t * pSrcB,
+ float32_t * pDst,
+ uint32_t numSamples);
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q31 vector.
+ * @param[in] *pSrc points to the floating-point input vector
+ * @param[out] *pDst points to the Q31 output vector
+ * @param[in] blockSize length of the input vector
+ * @return none.
+ */
+ void arm_float_to_q31(
+ float32_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q15 vector.
+ * @param[in] *pSrc points to the floating-point input vector
+ * @param[out] *pDst points to the Q15 output vector
+ * @param[in] blockSize length of the input vector
+ * @return none
+ */
+ void arm_float_to_q15(
+ float32_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Converts the elements of the floating-point vector to Q7 vector.
+ * @param[in] *pSrc points to the floating-point input vector
+ * @param[out] *pDst points to the Q7 output vector
+ * @param[in] blockSize length of the input vector
+ * @return none
+ */
+ void arm_float_to_q7(
+ float32_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q31 vector to Q15 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q31_to_q15(
+ q31_t * pSrc,
+ q15_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Converts the elements of the Q31 vector to Q7 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q31_to_q7(
+ q31_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+ /**
+ * @brief Converts the elements of the Q15 vector to floating-point vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q15_to_float(
+ q15_t * pSrc,
+ float32_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q15 vector to Q31 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q15_to_q31(
+ q15_t * pSrc,
+ q31_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @brief Converts the elements of the Q15 vector to Q7 vector.
+ * @param[in] *pSrc is input pointer
+ * @param[out] *pDst is output pointer
+ * @param[in] blockSize is the number of samples to process
+ * @return none.
+ */
+ void arm_q15_to_q7(
+ q15_t * pSrc,
+ q7_t * pDst,
+ uint32_t blockSize);
+
+
+ /**
+ * @ingroup groupInterpolation
+ */
+
+ /**
+ * @defgroup BilinearInterpolate Bilinear Interpolation
+ *
+ * Bilinear interpolation is an extension of linear interpolation applied to a two dimensional grid.
+ * The underlying function <code>f(x, y)</code> is sampled on a regular grid and the interpolation process
+ * determines values between the grid points.
+ * Bilinear interpolation is equivalent to two step linear interpolation, first in the x-dimension and then in the y-dimension.
+ * Bilinear interpolation is often used in image processing to rescale images.
+ * The CMSIS DSP library provides bilinear interpolation functions for Q7, Q15, Q31, and floating-point data types.
+ *
+ * <b>Algorithm</b>
+ * \par
+ * The instance structure used by the bilinear interpolation functions describes a two dimensional data table.
+ * For floating-point, the instance structure is defined as:
+ * <pre>
+ * typedef struct
+ * {
+ * uint16_t numRows;
+ * uint16_t numCols;
+ * float32_t *pData;
+ * } arm_bilinear_interp_instance_f32;
+ * </pre>
+ *
+ * \par
+ * where <code>numRows</code> specifies the number of rows in the table;
+ * <code>numCols</code> specifies the number of columns in the table;
+ * and <code>pData</code> points to an array of size <code>numRows*numCols</code> values.
+ * The data table <code>pTable</code> is organized in row order and the supplied data values fall on integer indexes.
+ * That is, table element (x,y) is located at <code>pTable[x + y*numCols]</code> where x and y are integers.
+ *
+ * \par
+ * Let <code>(x, y)</code> specify the desired interpolation point. Then define:
+ * <pre>
+ * XF = floor(x)
+ * YF = floor(y)
+ * </pre>
+ * \par
+ * The interpolated output point is computed as:
+ * <pre>
+ * f(x, y) = f(XF, YF) * (1-(x-XF)) * (1-(y-YF))
+ * + f(XF+1, YF) * (x-XF)*(1-(y-YF))
+ * + f(XF, YF+1) * (1-(x-XF))*(y-YF)
+ * + f(XF+1, YF+1) * (x-XF)*(y-YF)
+ * </pre>
+ * Note that the coordinates (x, y) contain integer and fractional components.
+ * The integer components specify which portion of the table to use while the
+ * fractional components control the interpolation processor.
+ *
+ * \par
+ * if (x,y) are outside of the table boundary, Bilinear interpolation returns zero output.
+ */
+
+ /**
+ * @addtogroup BilinearInterpolate
+ * @{
+ */
+
+ /**
+ *
+ * @brief Floating-point bilinear interpolation.
+ * @param[in,out] *S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate.
+ * @param[in] Y interpolation coordinate.
+ * @return out interpolated value.
+ */
+
+
+ static __INLINE float32_t arm_bilinear_interp_f32(
+ const arm_bilinear_interp_instance_f32 * S,
+ float32_t X,
+ float32_t Y)
+ {
+ float32_t out;
+ float32_t f00, f01, f10, f11;
+ float32_t *pData = S->pData;
+ int32_t xIndex, yIndex, index;
+ float32_t xdiff, ydiff;
+ float32_t b1, b2, b3, b4;
+
+ xIndex = (int32_t) X;
+ yIndex = (int32_t) Y;
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if(xIndex < 0 || xIndex > (S->numRows - 1) || yIndex < 0
+ || yIndex > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* Calculation of index for two nearest points in X-direction */
+ index = (xIndex - 1) + (yIndex - 1) * S->numCols;
+
+
+ /* Read two nearest points in X-direction */
+ f00 = pData[index];
+ f01 = pData[index + 1];
+
+ /* Calculation of index for two nearest points in Y-direction */
+ index = (xIndex - 1) + (yIndex) * S->numCols;
+
+
+ /* Read two nearest points in Y-direction */
+ f10 = pData[index];
+ f11 = pData[index + 1];
+
+ /* Calculation of intermediate values */
+ b1 = f00;
+ b2 = f01 - f00;
+ b3 = f10 - f00;
+ b4 = f00 - f01 - f10 + f11;
+
+ /* Calculation of fractional part in X */
+ xdiff = X - xIndex;
+
+ /* Calculation of fractional part in Y */
+ ydiff = Y - yIndex;
+
+ /* Calculation of bi-linear interpolated output */
+ out = b1 + b2 * xdiff + b3 * ydiff + b4 * xdiff * ydiff;
+
+ /* return to application */
+ return (out);
+
+ }
+
+ /**
+ *
+ * @brief Q31 bilinear interpolation.
+ * @param[in,out] *S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+
+ static __INLINE q31_t arm_bilinear_interp_q31(
+ arm_bilinear_interp_instance_q31 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q31_t out; /* Temporary output */
+ q31_t acc = 0; /* output */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ q31_t x1, x2, y1, y2; /* Nearest output values */
+ int32_t rI, cI; /* Row and column indices */
+ q31_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & 0xFFF00000) >> 20u);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & 0xFFF00000) >> 20u);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* shift left xfract by 11 to keep 1.31 format */
+ xfract = (X & 0x000FFFFF) << 11u;
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[(rI) + nCols * (cI)];
+ x2 = pYData[(rI) + nCols * (cI) + 1u];
+
+ /* 20 bits for the fractional part */
+ /* shift left yfract by 11 to keep 1.31 format */
+ yfract = (Y & 0x000FFFFF) << 11u;
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[(rI) + nCols * (cI + 1)];
+ y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 3.29(q29) format */
+ out = ((q31_t) (((q63_t) x1 * (0x7FFFFFFF - xfract)) >> 32));
+ acc = ((q31_t) (((q63_t) out * (0x7FFFFFFF - yfract)) >> 32));
+
+ /* x2 * (xfract) * (1-yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) x2 * (0x7FFFFFFF - yfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (xfract) >> 32));
+
+ /* y1 * (1 - xfract) * (yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) y1 * (0x7FFFFFFF - xfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
+
+ /* y2 * (xfract) * (yfract) in 3.29(q29) and adding to acc */
+ out = ((q31_t) ((q63_t) y2 * (xfract) >> 32));
+ acc += ((q31_t) ((q63_t) out * (yfract) >> 32));
+
+ /* Convert acc to 1.31(q31) format */
+ return (acc << 2u);
+
+ }
+
+ /**
+ * @brief Q15 bilinear interpolation.
+ * @param[in,out] *S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+
+ static __INLINE q15_t arm_bilinear_interp_q15(
+ arm_bilinear_interp_instance_q15 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q63_t acc = 0; /* output */
+ q31_t out; /* Temporary output */
+ q15_t x1, x2, y1, y2; /* Nearest output values */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ int32_t rI, cI; /* Row and column indices */
+ q15_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & 0xFFF00000) >> 20);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & 0xFFF00000) >> 20);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* xfract should be in 12.20 format */
+ xfract = (X & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[(rI) + nCols * (cI)];
+ x2 = pYData[(rI) + nCols * (cI) + 1u];
+
+
+ /* 20 bits for the fractional part */
+ /* yfract should be in 12.20 format */
+ yfract = (Y & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[(rI) + nCols * (cI + 1)];
+ y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 13.51 format */
+
+ /* x1 is in 1.15(q15), xfract in 12.20 format and out is in 13.35 format */
+ /* convert 13.35 to 13.31 by right shifting and out is in 1.31 */
+ out = (q31_t) (((q63_t) x1 * (0xFFFFF - xfract)) >> 4u);
+ acc = ((q63_t) out * (0xFFFFF - yfract));
+
+ /* x2 * (xfract) * (1-yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) x2 * (0xFFFFF - yfract)) >> 4u);
+ acc += ((q63_t) out * (xfract));
+
+ /* y1 * (1 - xfract) * (yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) y1 * (0xFFFFF - xfract)) >> 4u);
+ acc += ((q63_t) out * (yfract));
+
+ /* y2 * (xfract) * (yfract) in 1.51 and adding to acc */
+ out = (q31_t) (((q63_t) y2 * (xfract)) >> 4u);
+ acc += ((q63_t) out * (yfract));
+
+ /* acc is in 13.51 format and down shift acc by 36 times */
+ /* Convert out to 1.15 format */
+ return (acc >> 36);
+
+ }
+
+ /**
+ * @brief Q7 bilinear interpolation.
+ * @param[in,out] *S points to an instance of the interpolation structure.
+ * @param[in] X interpolation coordinate in 12.20 format.
+ * @param[in] Y interpolation coordinate in 12.20 format.
+ * @return out interpolated value.
+ */
+
+ static __INLINE q7_t arm_bilinear_interp_q7(
+ arm_bilinear_interp_instance_q7 * S,
+ q31_t X,
+ q31_t Y)
+ {
+ q63_t acc = 0; /* output */
+ q31_t out; /* Temporary output */
+ q31_t xfract, yfract; /* X, Y fractional parts */
+ q7_t x1, x2, y1, y2; /* Nearest output values */
+ int32_t rI, cI; /* Row and column indices */
+ q7_t *pYData = S->pData; /* pointer to output table values */
+ uint32_t nCols = S->numCols; /* num of rows */
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ rI = ((X & 0xFFF00000) >> 20);
+
+ /* Input is in 12.20 format */
+ /* 12 bits for the table index */
+ /* Index value calculation */
+ cI = ((Y & 0xFFF00000) >> 20);
+
+ /* Care taken for table outside boundary */
+ /* Returns zero output when values are outside table boundary */
+ if(rI < 0 || rI > (S->numRows - 1) || cI < 0 || cI > (S->numCols - 1))
+ {
+ return (0);
+ }
+
+ /* 20 bits for the fractional part */
+ /* xfract should be in 12.20 format */
+ xfract = (X & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ x1 = pYData[(rI) + nCols * (cI)];
+ x2 = pYData[(rI) + nCols * (cI) + 1u];
+
+
+ /* 20 bits for the fractional part */
+ /* yfract should be in 12.20 format */
+ yfract = (Y & 0x000FFFFF);
+
+ /* Read two nearest output values from the index */
+ y1 = pYData[(rI) + nCols * (cI + 1)];
+ y2 = pYData[(rI) + nCols * (cI + 1) + 1u];
+
+ /* Calculation of x1 * (1-xfract ) * (1-yfract) and acc is in 16.47 format */
+ out = ((x1 * (0xFFFFF - xfract)));
+ acc = (((q63_t) out * (0xFFFFF - yfract)));
+
+ /* x2 * (xfract) * (1-yfract) in 2.22 and adding to acc */
+ out = ((x2 * (0xFFFFF - yfract)));
+ acc += (((q63_t) out * (xfract)));
+
+ /* y1 * (1 - xfract) * (yfract) in 2.22 and adding to acc */
+ out = ((y1 * (0xFFFFF - xfract)));
+ acc += (((q63_t) out * (yfract)));
+
+ /* y2 * (xfract) * (yfract) in 2.22 and adding to acc */
+ out = ((y2 * (yfract)));
+ acc += (((q63_t) out * (xfract)));
+
+ /* acc in 16.47 format and down shift by 40 to convert to 1.7 format */
+ return (acc >> 40);
+
+ }
+
+ /**
+ * @} end of BilinearInterpolate group
+ */
+
+
+#if defined ( __CC_ARM ) //Keil
+//SMMLAR
+ #define multAcc_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((((q63_t) a) << 32) + ((q63_t) x * y) + 0x80000000LL ) >> 32)
+
+//SMMLSR
+ #define multSub_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((((q63_t) a) << 32) - ((q63_t) x * y) + 0x80000000LL ) >> 32)
+
+//SMMULR
+ #define mult_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((q63_t) x * y + 0x80000000LL ) >> 32)
+
+//Enter low optimization region - place directly above function definition
+ #define LOW_OPTIMIZATION_ENTER \
+ _Pragma ("push") \
+ _Pragma ("O1")
+
+//Exit low optimization region - place directly after end of function definition
+ #define LOW_OPTIMIZATION_EXIT \
+ _Pragma ("pop")
+
+//Enter low optimization region - place directly above function definition
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+
+//Exit low optimization region - place directly after end of function definition
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined(__ICCARM__) //IAR
+ //SMMLA
+ #define multAcc_32x32_keep32_R(a, x, y) \
+ a += (q31_t) (((q63_t) x * y) >> 32)
+
+ //SMMLS
+ #define multSub_32x32_keep32_R(a, x, y) \
+ a -= (q31_t) (((q63_t) x * y) >> 32)
+
+//SMMUL
+ #define mult_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((q63_t) x * y ) >> 32)
+
+//Enter low optimization region - place directly above function definition
+ #define LOW_OPTIMIZATION_ENTER \
+ _Pragma ("optimize=low")
+
+//Exit low optimization region - place directly after end of function definition
+ #define LOW_OPTIMIZATION_EXIT
+
+//Enter low optimization region - place directly above function definition
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER \
+ _Pragma ("optimize=low")
+
+//Exit low optimization region - place directly after end of function definition
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#elif defined(__GNUC__)
+ //SMMLA
+ #define multAcc_32x32_keep32_R(a, x, y) \
+ a += (q31_t) (((q63_t) x * y) >> 32)
+
+ //SMMLS
+ #define multSub_32x32_keep32_R(a, x, y) \
+ a -= (q31_t) (((q63_t) x * y) >> 32)
+
+//SMMUL
+ #define mult_32x32_keep32_R(a, x, y) \
+ a = (q31_t) (((q63_t) x * y ) >> 32)
+
+ #define LOW_OPTIMIZATION_ENTER __attribute__(( optimize("-O1") ))
+
+ #define LOW_OPTIMIZATION_EXIT
+
+ #define IAR_ONLY_LOW_OPTIMIZATION_ENTER
+
+ #define IAR_ONLY_LOW_OPTIMIZATION_EXIT
+
+#endif
+
+
+
+
+
+#ifdef __cplusplus
+}
+#endif
+
+
+#endif /* _ARM_MATH_H */
+
+
+/**
+ *
+ * End of file.
+ */
diff --git a/src/lib/mathlib/CMSIS/Include/core_cm3.h b/src/lib/mathlib/CMSIS/Include/core_cm3.h
new file mode 100644
index 000000000..8ac6dc078
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/core_cm3.h
@@ -0,0 +1,1627 @@
+/**************************************************************************//**
+ * @file core_cm3.h
+ * @brief CMSIS Cortex-M3 Core Peripheral Access Layer Header File
+ * @version V3.20
+ * @date 25. February 2013
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2013 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#if defined ( __ICCARM__ )
+ #pragma system_include /* treat file as system include file for MISRA check */
+#endif
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#ifndef __CORE_CM3_H_GENERIC
+#define __CORE_CM3_H_GENERIC
+
+/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
+ CMSIS violates the following MISRA-C:2004 rules:
+
+ \li Required Rule 8.5, object/function definition in header file.<br>
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.<br>
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/** \ingroup Cortex_M3
+ @{
+ */
+
+/* CMSIS CM3 definitions */
+#define __CM3_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
+#define __CM3_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
+#define __CM3_CMSIS_VERSION ((__CM3_CMSIS_VERSION_MAIN << 16) | \
+ __CM3_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
+
+#define __CORTEX_M (0x03) /*!< Cortex-M Core */
+
+
+#if defined ( __CC_ARM )
+ #define __ASM __asm /*!< asm keyword for ARM Compiler */
+ #define __INLINE __inline /*!< inline keyword for ARM Compiler */
+ #define __STATIC_INLINE static __inline
+
+#elif defined ( __ICCARM__ )
+ #define __ASM __asm /*!< asm keyword for IAR Compiler */
+ #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __TMS470__ )
+ #define __ASM __asm /*!< asm keyword for TI CCS Compiler */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __GNUC__ )
+ #define __ASM __asm /*!< asm keyword for GNU Compiler */
+ #define __INLINE inline /*!< inline keyword for GNU Compiler */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __TASKING__ )
+ #define __ASM __asm /*!< asm keyword for TASKING Compiler */
+ #define __INLINE inline /*!< inline keyword for TASKING Compiler */
+ #define __STATIC_INLINE static inline
+
+#endif
+
+/** __FPU_USED indicates whether an FPU is used or not. This core does not support an FPU at all
+*/
+#define __FPU_USED 0
+
+#if defined ( __CC_ARM )
+ #if defined __TARGET_FPU_VFP
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __ICCARM__ )
+ #if defined __ARMVFP__
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __TMS470__ )
+ #if defined __TI__VFP_SUPPORT____
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __GNUC__ )
+ #if defined (__VFP_FP__) && !defined(__SOFTFP__)
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+
+#elif defined ( __TASKING__ )
+ #if defined __FPU_VFP__
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #endif
+#endif
+
+#include <stdint.h> /* standard types definitions */
+#include "core_cmInstr.h" /* Core Instruction Access */
+#include "core_cmFunc.h" /* Core Function Access */
+
+#endif /* __CORE_CM3_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_CM3_H_DEPENDANT
+#define __CORE_CM3_H_DEPENDANT
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __CM3_REV
+ #define __CM3_REV 0x0200
+ #warning "__CM3_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MPU_PRESENT
+ #define __MPU_PRESENT 0
+ #warning "__MPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 4
+ #warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
+ #endif
+
+ #ifndef __Vendor_SysTickConfig
+ #define __Vendor_SysTickConfig 0
+ #warning "__Vendor_SysTickConfig not defined in device header file; using default!"
+ #endif
+#endif
+
+/* IO definitions (access restrictions to peripheral registers) */
+/**
+ \defgroup CMSIS_glob_defs CMSIS Global Defines
+
+ <strong>IO Type Qualifiers</strong> are used
+ \li to specify the access to peripheral variables.
+ \li for automatic generation of peripheral register debug information.
+*/
+#ifdef __cplusplus
+ #define __I volatile /*!< Defines 'read only' permissions */
+#else
+ #define __I volatile const /*!< Defines 'read only' permissions */
+#endif
+#define __O volatile /*!< Defines 'write only' permissions */
+#define __IO volatile /*!< Defines 'read / write' permissions */
+
+/*@} end of group Cortex_M3 */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ ******************************************************************************/
+/** \defgroup CMSIS_core_register Defines and Type Definitions
+ \brief Type definitions and defines for Cortex-M processor based devices.
+*/
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CORE Status and Control Registers
+ \brief Core Register type definitions.
+ @{
+ */
+
+/** \brief Union type to access the Application Program Status Register (APSR).
+ */
+typedef union
+{
+ struct
+ {
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */
+#else
+ uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
+#endif
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} APSR_Type;
+
+
+/** \brief Union type to access the Interrupt Program Status Register (IPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+ uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} IPSR_Type;
+
+
+/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
+#else
+ uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
+#endif
+ uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
+ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} xPSR_Type;
+
+
+/** \brief Union type to access the Control Registers (CONTROL).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
+ uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */
+ uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/*@} end of group CMSIS_CORE */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
+ \brief Type definitions for the NVIC Registers
+ @{
+ */
+
+/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
+ */
+typedef struct
+{
+ __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[24];
+ __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[24];
+ __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[24];
+ __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[24];
+ __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[56];
+ __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED5[644];
+ __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
+} NVIC_Type;
+
+/* Software Triggered Interrupt Register Definitions */
+#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */
+#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */
+
+/*@} end of group CMSIS_NVIC */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCB System Control Block (SCB)
+ \brief Type definitions for the System Control Block Registers
+ @{
+ */
+
+/** \brief Structure type to access the System Control Block (SCB).
+ */
+typedef struct
+{
+ __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
+ __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
+ __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+ __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
+ __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
+ __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
+ __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+ __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
+ __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
+ __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
+ __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
+ __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
+ __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
+ __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
+ __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
+ __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
+ __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
+ __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
+ uint32_t RESERVED0[5];
+ __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
+} SCB_Type;
+
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
+
+#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
+#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
+
+#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */
+#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
+
+#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
+#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
+
+#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
+#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
+
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
+#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
+
+#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
+#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
+
+#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
+#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
+
+#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
+#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
+
+#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
+#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
+
+#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
+#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
+
+#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
+#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
+
+#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
+
+#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
+
+#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
+
+/* SCB Vector Table Offset Register Definitions */
+#if (__CM3_REV < 0x0201) /* core r2p1 */
+#define SCB_VTOR_TBLBASE_Pos 29 /*!< SCB VTOR: TBLBASE Position */
+#define SCB_VTOR_TBLBASE_Msk (1UL << SCB_VTOR_TBLBASE_Pos) /*!< SCB VTOR: TBLBASE Mask */
+
+#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x3FFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+#else
+#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+#endif
+
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
+
+#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
+
+#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
+#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
+
+#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
+
+#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
+
+#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
+
+#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
+#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
+
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
+#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
+
+#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
+#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
+
+#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
+#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
+
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
+#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
+
+#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
+
+#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
+#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
+
+#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
+#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+
+#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+
+#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+
+#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+
+#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
+
+/* SCB Configurable Fault Status Registers Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+
+#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+
+#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+
+/* SCB Hard Fault Status Registers Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+
+#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+
+#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+
+#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+
+#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+
+#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+
+#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
+ \brief Type definitions for the System Control and ID Register not in the SCB
+ @{
+ */
+
+/** \brief Structure type to access the System Control and ID Register not in the SCB.
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1];
+ __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
+#if ((defined __CM3_REV) && (__CM3_REV >= 0x200))
+ __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
+#else
+ uint32_t RESERVED1[1];
+#endif
+} SCnSCB_Type;
+
+/* Interrupt Controller Type Register Definitions */
+#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */
+#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */
+
+/* Auxiliary Control Register Definitions */
+
+#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */
+#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
+
+#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */
+#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
+
+#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */
+#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */
+
+/*@} end of group CMSIS_SCnotSCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SysTick System Tick Timer (SysTick)
+ \brief Type definitions for the System Timer Registers.
+ @{
+ */
+
+/** \brief Structure type to access the System Timer (SysTick).
+ */
+typedef struct
+{
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
+ __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
+ __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
+ __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
+} SysTick_Type;
+
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
+#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
+
+#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
+#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
+
+#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
+#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
+
+#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
+#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
+
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
+
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
+
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
+#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
+
+#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
+#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
+
+#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
+
+/*@} end of group CMSIS_SysTick */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM)
+ \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
+ @{
+ */
+
+/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
+ */
+typedef struct
+{
+ __O union
+ {
+ __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
+ __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
+ __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
+ } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864];
+ __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
+ uint32_t RESERVED1[15];
+ __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
+ uint32_t RESERVED2[15];
+ __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
+ uint32_t RESERVED3[29];
+ __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
+ __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
+ __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43];
+ __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
+ __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
+ uint32_t RESERVED5[6];
+ __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
+ __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
+ __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
+ __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
+ __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
+ __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
+ __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
+ __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
+ __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
+ __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
+ __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
+ __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
+} ITM_Type;
+
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
+
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+
+#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
+
+#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */
+#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
+
+#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
+#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
+
+#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+
+#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+
+#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+
+#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+
+#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
+
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
+
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
+
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
+
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+
+#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+
+#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
+
+/*@}*/ /* end of group CMSIS_ITM */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct
+{
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
+ __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
+ __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
+ __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
+ __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
+ __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
+ __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
+ __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED0[1];
+ __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
+ __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED1[1];
+ __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
+ __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED2[1];
+ __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
+ __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */
+#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
+
+#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */
+#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
+
+#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */
+#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
+
+#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */
+#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
+
+#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */
+#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
+
+#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */
+#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
+
+#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */
+#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
+
+#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */
+#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
+
+#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */
+#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
+
+#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */
+#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
+
+#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */
+#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
+
+#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */
+#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
+
+#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */
+#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */
+
+/* DWT CPI Count Register Definitions */
+#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */
+#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */
+
+/* DWT Exception Overhead Count Register Definitions */
+#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */
+#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */
+
+/* DWT Sleep Count Register Definitions */
+#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */
+#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
+
+/* DWT LSU Count Register Definitions */
+#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */
+#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */
+
+/* DWT Folded-instruction Count Register Definitions */
+#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */
+#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */
+
+/* DWT Comparator Mask Register Definitions */
+#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */
+#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */
+#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
+
+#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */
+#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */
+#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
+
+#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */
+#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
+
+#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */
+#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
+
+#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */
+#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
+
+#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */
+#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/** \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct
+{
+ __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2];
+ __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55];
+ __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131];
+ __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759];
+ __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1];
+ __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39];
+ __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8];
+ __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */
+
+#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if (__MPU_PRESENT == 1)
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/** \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct
+{
+ __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
+ __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
+ __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
+ __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
+ __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
+ __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
+} MPU_Type;
+
+/* MPU Type Register */
+#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register */
+#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register */
+#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register */
+#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+
+#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
+#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
+
+#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
+#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
+
+/* MPU Region Attribute and Size Register */
+#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */
+#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
+
+#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */
+#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
+
+#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */
+#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
+
+#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */
+#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
+
+#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */
+#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
+
+#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */
+#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
+
+#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */
+#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
+
+#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
+#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
+
+#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
+#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
+
+#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */
+#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/** \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct
+{
+ __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register */
+#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register */
+#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+
+#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+
+#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+
+#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+
+#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/*@} end of group CMSIS_CoreDebug */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_core_base Core Definitions
+ \brief Definitions for base addresses, unions, and structures.
+ @{
+ */
+
+/* Memory mapping of Cortex-M3 Hardware */
+#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
+#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
+#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */
+#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
+#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
+#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
+
+#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
+#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
+#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
+#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
+#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
+#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
+
+#if (__MPU_PRESENT == 1)
+ #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+#endif
+
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Debug Functions
+ - Core Register Access Functions
+ ******************************************************************************/
+/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
+*/
+
+
+
+/* ########################## NVIC functions #################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_NVICFunctions NVIC Functions
+ \brief Functions that manage interrupts and exceptions via the NVIC.
+ @{
+ */
+
+/** \brief Set Priority Grouping
+
+ The function sets the priority grouping field using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
+
+ \param [in] PriorityGroup Priority grouping field.
+ */
+__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
+
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
+ SCB->AIRCR = reg_value;
+}
+
+
+/** \brief Get Priority Grouping
+
+ The function reads the priority grouping field from the NVIC Interrupt Controller.
+
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void)
+{
+ return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
+}
+
+
+/** \brief Enable External Interrupt
+
+ The function enables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
+{
+ NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* enable interrupt */
+}
+
+
+/** \brief Disable External Interrupt
+
+ The function disables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
+}
+
+
+/** \brief Get Pending Interrupt
+
+ The function reads the pending register in the NVIC and returns the pending bit
+ for the specified interrupt.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not pending.
+ \return 1 Interrupt status is pending.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
+{
+ return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */
+}
+
+
+/** \brief Set Pending Interrupt
+
+ The function sets the pending bit of an external interrupt.
+
+ \param [in] IRQn Interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
+}
+
+
+/** \brief Clear Pending Interrupt
+
+ The function clears the pending bit of an external interrupt.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
+}
+
+
+/** \brief Get Active Interrupt
+
+ The function reads the active register in NVIC and returns the active bit.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ */
+__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
+{
+ return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */
+}
+
+
+/** \brief Set Interrupt Priority
+
+ The function sets the priority of an interrupt.
+
+ \note The priority cannot be set for every core interrupt.
+
+ \param [in] IRQn Interrupt number.
+ \param [in] priority Priority to set.
+ */
+__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
+{
+ if(IRQn < 0) {
+ SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */
+ else {
+ NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */
+}
+
+
+/** \brief Get Interrupt Priority
+
+ The function reads the priority of an interrupt. The interrupt
+ number can be positive to specify an external (device specific)
+ interrupt, or negative to specify an internal (core) interrupt.
+
+
+ \param [in] IRQn Interrupt number.
+ \return Interrupt Priority. Value is aligned automatically to the implemented
+ priority bits of the microcontroller.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
+{
+
+ if(IRQn < 0) {
+ return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */
+ else {
+ return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */
+}
+
+
+/** \brief Encode Priority
+
+ The function encodes the priority for an interrupt with the given priority group,
+ preemptive priority value, and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set.
+
+ \param [in] PriorityGroup Used priority group.
+ \param [in] PreemptPriority Preemptive priority value (starting from 0).
+ \param [in] SubPriority Subpriority value (starting from 0).
+ \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
+ */
+__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ return (
+ ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
+ ((SubPriority & ((1 << (SubPriorityBits )) - 1)))
+ );
+}
+
+
+/** \brief Decode Priority
+
+ The function decodes an interrupt priority value with a given priority group to
+ preemptive priority value and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
+
+ \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
+ \param [in] PriorityGroup Used priority group.
+ \param [out] pPreemptPriority Preemptive priority value (starting from 0).
+ \param [out] pSubPriority Subpriority value (starting from 0).
+ */
+__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
+ *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);
+}
+
+
+/** \brief System Reset
+
+ The function initiates a system reset request to reset the MCU.
+ */
+__STATIC_INLINE void NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+ while(1); /* wait until reset */
+}
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+
+
+/* ################################## SysTick function ############################################ */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
+ \brief Functions that configure the System.
+ @{
+ */
+
+#if (__Vendor_SysTickConfig == 0)
+
+/** \brief System Tick Configuration
+
+ The function initializes the System Timer and its interrupt, and starts the System Tick Timer.
+ Counter is in free running mode to generate periodic interrupts.
+
+ \param [in] ticks Number of ticks between two interrupts.
+
+ \return 0 Function succeeded.
+ \return 1 Function failed.
+
+ \note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ must contain a vendor-specific implementation of this function.
+
+ */
+__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
+{
+ if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
+
+ SysTick->LOAD = ticks - 1; /* set reload register */
+ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
+ SysTick->VAL = 0; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0); /* Function successful */
+}
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+/* ##################################### Debug In/Output function ########################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_core_DebugFunctions ITM Functions
+ \brief Functions that access the ITM debug interface.
+ @{
+ */
+
+extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
+#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
+
+
+/** \brief ITM Send Character
+
+ The function transmits a character via the ITM channel 0, and
+ \li Just returns when no debugger is connected that has booked the output.
+ \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
+
+ \param [in] ch Character to transmit.
+
+ \returns Character to transmit.
+ */
+__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
+{
+ if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
+ (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */
+ {
+ while (ITM->PORT[0].u32 == 0);
+ ITM->PORT[0].u8 = (uint8_t) ch;
+ }
+ return (ch);
+}
+
+
+/** \brief ITM Receive Character
+
+ The function inputs a character via the external variable \ref ITM_RxBuffer.
+
+ \return Received character.
+ \return -1 No character pending.
+ */
+__STATIC_INLINE int32_t ITM_ReceiveChar (void) {
+ int32_t ch = -1; /* no character available */
+
+ if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ }
+
+ return (ch);
+}
+
+
+/** \brief ITM Check Character
+
+ The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
+
+ \return 0 No character available.
+ \return 1 Character available.
+ */
+__STATIC_INLINE int32_t ITM_CheckChar (void) {
+
+ if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
+ return (0); /* no character available */
+ } else {
+ return (1); /* character available */
+ }
+}
+
+/*@} end of CMSIS_core_DebugFunctions */
+
+#endif /* __CORE_CM3_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/src/lib/mathlib/CMSIS/Include/core_cm4.h b/src/lib/mathlib/CMSIS/Include/core_cm4.h
new file mode 100644
index 000000000..93efd3a7a
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/core_cm4.h
@@ -0,0 +1,1772 @@
+/**************************************************************************//**
+ * @file core_cm4.h
+ * @brief CMSIS Cortex-M4 Core Peripheral Access Layer Header File
+ * @version V3.20
+ * @date 25. February 2013
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2013 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#if defined ( __ICCARM__ )
+ #pragma system_include /* treat file as system include file for MISRA check */
+#endif
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#ifndef __CORE_CM4_H_GENERIC
+#define __CORE_CM4_H_GENERIC
+
+/** \page CMSIS_MISRA_Exceptions MISRA-C:2004 Compliance Exceptions
+ CMSIS violates the following MISRA-C:2004 rules:
+
+ \li Required Rule 8.5, object/function definition in header file.<br>
+ Function definitions in header files are used to allow 'inlining'.
+
+ \li Required Rule 18.4, declaration of union type or object of union type: '{...}'.<br>
+ Unions are used for effective representation of core registers.
+
+ \li Advisory Rule 19.7, Function-like macro defined.<br>
+ Function-like macros are used to allow more efficient code.
+ */
+
+
+/*******************************************************************************
+ * CMSIS definitions
+ ******************************************************************************/
+/** \ingroup Cortex_M4
+ @{
+ */
+
+/* CMSIS CM4 definitions */
+#define __CM4_CMSIS_VERSION_MAIN (0x03) /*!< [31:16] CMSIS HAL main version */
+#define __CM4_CMSIS_VERSION_SUB (0x20) /*!< [15:0] CMSIS HAL sub version */
+#define __CM4_CMSIS_VERSION ((__CM4_CMSIS_VERSION_MAIN << 16) | \
+ __CM4_CMSIS_VERSION_SUB ) /*!< CMSIS HAL version number */
+
+#define __CORTEX_M (0x04) /*!< Cortex-M Core */
+
+
+#if defined ( __CC_ARM )
+ #define __ASM __asm /*!< asm keyword for ARM Compiler */
+ #define __INLINE __inline /*!< inline keyword for ARM Compiler */
+ #define __STATIC_INLINE static __inline
+
+#elif defined ( __ICCARM__ )
+ #define __ASM __asm /*!< asm keyword for IAR Compiler */
+ #define __INLINE inline /*!< inline keyword for IAR Compiler. Only available in High optimization mode! */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __TMS470__ )
+ #define __ASM __asm /*!< asm keyword for TI CCS Compiler */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __GNUC__ )
+ #define __ASM __asm /*!< asm keyword for GNU Compiler */
+ #define __INLINE inline /*!< inline keyword for GNU Compiler */
+ #define __STATIC_INLINE static inline
+
+#elif defined ( __TASKING__ )
+ #define __ASM __asm /*!< asm keyword for TASKING Compiler */
+ #define __INLINE inline /*!< inline keyword for TASKING Compiler */
+ #define __STATIC_INLINE static inline
+
+#endif
+
+/** __FPU_USED indicates whether an FPU is used or not. For this, __FPU_PRESENT has to be checked prior to making use of FPU specific registers and functions.
+*/
+#if defined ( __CC_ARM )
+ #if defined __TARGET_FPU_VFP
+ #if (__FPU_PRESENT == 1)
+ #define __FPU_USED 1
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0
+ #endif
+ #else
+ #define __FPU_USED 0
+ #endif
+
+#elif defined ( __ICCARM__ )
+ #if defined __ARMVFP__
+ #if (__FPU_PRESENT == 1)
+ #define __FPU_USED 1
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0
+ #endif
+ #else
+ #define __FPU_USED 0
+ #endif
+
+#elif defined ( __TMS470__ )
+ #if defined __TI_VFP_SUPPORT__
+ #if (__FPU_PRESENT == 1)
+ #define __FPU_USED 1
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0
+ #endif
+ #else
+ #define __FPU_USED 0
+ #endif
+
+#elif defined ( __GNUC__ )
+ #if defined (__VFP_FP__) && !defined(__SOFTFP__)
+ #if (__FPU_PRESENT == 1)
+ #define __FPU_USED 1
+ #else
+ #warning "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0
+ #endif
+ #else
+ #define __FPU_USED 0
+ #endif
+
+#elif defined ( __TASKING__ )
+ #if defined __FPU_VFP__
+ #if (__FPU_PRESENT == 1)
+ #define __FPU_USED 1
+ #else
+ #error "Compiler generates FPU instructions for a device without an FPU (check __FPU_PRESENT)"
+ #define __FPU_USED 0
+ #endif
+ #else
+ #define __FPU_USED 0
+ #endif
+#endif
+
+#include <stdint.h> /* standard types definitions */
+#include "core_cmInstr.h" /* Core Instruction Access */
+#include "core_cmFunc.h" /* Core Function Access */
+#include "core_cm4_simd.h" /* Compiler specific SIMD Intrinsics */
+
+#endif /* __CORE_CM4_H_GENERIC */
+
+#ifndef __CMSIS_GENERIC
+
+#ifndef __CORE_CM4_H_DEPENDANT
+#define __CORE_CM4_H_DEPENDANT
+
+/* check device defines and use defaults */
+#if defined __CHECK_DEVICE_DEFINES
+ #ifndef __CM4_REV
+ #define __CM4_REV 0x0000
+ #warning "__CM4_REV not defined in device header file; using default!"
+ #endif
+
+ #ifndef __FPU_PRESENT
+ #define __FPU_PRESENT 0
+ #warning "__FPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __MPU_PRESENT
+ #define __MPU_PRESENT 0
+ #warning "__MPU_PRESENT not defined in device header file; using default!"
+ #endif
+
+ #ifndef __NVIC_PRIO_BITS
+ #define __NVIC_PRIO_BITS 4
+ #warning "__NVIC_PRIO_BITS not defined in device header file; using default!"
+ #endif
+
+ #ifndef __Vendor_SysTickConfig
+ #define __Vendor_SysTickConfig 0
+ #warning "__Vendor_SysTickConfig not defined in device header file; using default!"
+ #endif
+#endif
+
+/* IO definitions (access restrictions to peripheral registers) */
+/**
+ \defgroup CMSIS_glob_defs CMSIS Global Defines
+
+ <strong>IO Type Qualifiers</strong> are used
+ \li to specify the access to peripheral variables.
+ \li for automatic generation of peripheral register debug information.
+*/
+#ifdef __cplusplus
+ #define __I volatile /*!< Defines 'read only' permissions */
+#else
+ #define __I volatile const /*!< Defines 'read only' permissions */
+#endif
+#define __O volatile /*!< Defines 'write only' permissions */
+#define __IO volatile /*!< Defines 'read / write' permissions */
+
+/*@} end of group Cortex_M4 */
+
+
+
+/*******************************************************************************
+ * Register Abstraction
+ Core Register contain:
+ - Core Register
+ - Core NVIC Register
+ - Core SCB Register
+ - Core SysTick Register
+ - Core Debug Register
+ - Core MPU Register
+ - Core FPU Register
+ ******************************************************************************/
+/** \defgroup CMSIS_core_register Defines and Type Definitions
+ \brief Type definitions and defines for Cortex-M processor based devices.
+*/
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CORE Status and Control Registers
+ \brief Core Register type definitions.
+ @{
+ */
+
+/** \brief Union type to access the Application Program Status Register (APSR).
+ */
+typedef union
+{
+ struct
+ {
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0:27; /*!< bit: 0..26 Reserved */
+#else
+ uint32_t _reserved0:16; /*!< bit: 0..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:7; /*!< bit: 20..26 Reserved */
+#endif
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} APSR_Type;
+
+
+/** \brief Union type to access the Interrupt Program Status Register (IPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+ uint32_t _reserved0:23; /*!< bit: 9..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} IPSR_Type;
+
+
+/** \brief Union type to access the Special-Purpose Program Status Registers (xPSR).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t ISR:9; /*!< bit: 0.. 8 Exception number */
+#if (__CORTEX_M != 0x04)
+ uint32_t _reserved0:15; /*!< bit: 9..23 Reserved */
+#else
+ uint32_t _reserved0:7; /*!< bit: 9..15 Reserved */
+ uint32_t GE:4; /*!< bit: 16..19 Greater than or Equal flags */
+ uint32_t _reserved1:4; /*!< bit: 20..23 Reserved */
+#endif
+ uint32_t T:1; /*!< bit: 24 Thumb bit (read 0) */
+ uint32_t IT:2; /*!< bit: 25..26 saved IT state (read 0) */
+ uint32_t Q:1; /*!< bit: 27 Saturation condition flag */
+ uint32_t V:1; /*!< bit: 28 Overflow condition code flag */
+ uint32_t C:1; /*!< bit: 29 Carry condition code flag */
+ uint32_t Z:1; /*!< bit: 30 Zero condition code flag */
+ uint32_t N:1; /*!< bit: 31 Negative condition code flag */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} xPSR_Type;
+
+
+/** \brief Union type to access the Control Registers (CONTROL).
+ */
+typedef union
+{
+ struct
+ {
+ uint32_t nPRIV:1; /*!< bit: 0 Execution privilege in Thread mode */
+ uint32_t SPSEL:1; /*!< bit: 1 Stack to be used */
+ uint32_t FPCA:1; /*!< bit: 2 FP extension active flag */
+ uint32_t _reserved0:29; /*!< bit: 3..31 Reserved */
+ } b; /*!< Structure used for bit access */
+ uint32_t w; /*!< Type used for word access */
+} CONTROL_Type;
+
+/*@} end of group CMSIS_CORE */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_NVIC Nested Vectored Interrupt Controller (NVIC)
+ \brief Type definitions for the NVIC Registers
+ @{
+ */
+
+/** \brief Structure type to access the Nested Vectored Interrupt Controller (NVIC).
+ */
+typedef struct
+{
+ __IO uint32_t ISER[8]; /*!< Offset: 0x000 (R/W) Interrupt Set Enable Register */
+ uint32_t RESERVED0[24];
+ __IO uint32_t ICER[8]; /*!< Offset: 0x080 (R/W) Interrupt Clear Enable Register */
+ uint32_t RSERVED1[24];
+ __IO uint32_t ISPR[8]; /*!< Offset: 0x100 (R/W) Interrupt Set Pending Register */
+ uint32_t RESERVED2[24];
+ __IO uint32_t ICPR[8]; /*!< Offset: 0x180 (R/W) Interrupt Clear Pending Register */
+ uint32_t RESERVED3[24];
+ __IO uint32_t IABR[8]; /*!< Offset: 0x200 (R/W) Interrupt Active bit Register */
+ uint32_t RESERVED4[56];
+ __IO uint8_t IP[240]; /*!< Offset: 0x300 (R/W) Interrupt Priority Register (8Bit wide) */
+ uint32_t RESERVED5[644];
+ __O uint32_t STIR; /*!< Offset: 0xE00 ( /W) Software Trigger Interrupt Register */
+} NVIC_Type;
+
+/* Software Triggered Interrupt Register Definitions */
+#define NVIC_STIR_INTID_Pos 0 /*!< STIR: INTLINESNUM Position */
+#define NVIC_STIR_INTID_Msk (0x1FFUL << NVIC_STIR_INTID_Pos) /*!< STIR: INTLINESNUM Mask */
+
+/*@} end of group CMSIS_NVIC */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCB System Control Block (SCB)
+ \brief Type definitions for the System Control Block Registers
+ @{
+ */
+
+/** \brief Structure type to access the System Control Block (SCB).
+ */
+typedef struct
+{
+ __I uint32_t CPUID; /*!< Offset: 0x000 (R/ ) CPUID Base Register */
+ __IO uint32_t ICSR; /*!< Offset: 0x004 (R/W) Interrupt Control and State Register */
+ __IO uint32_t VTOR; /*!< Offset: 0x008 (R/W) Vector Table Offset Register */
+ __IO uint32_t AIRCR; /*!< Offset: 0x00C (R/W) Application Interrupt and Reset Control Register */
+ __IO uint32_t SCR; /*!< Offset: 0x010 (R/W) System Control Register */
+ __IO uint32_t CCR; /*!< Offset: 0x014 (R/W) Configuration Control Register */
+ __IO uint8_t SHP[12]; /*!< Offset: 0x018 (R/W) System Handlers Priority Registers (4-7, 8-11, 12-15) */
+ __IO uint32_t SHCSR; /*!< Offset: 0x024 (R/W) System Handler Control and State Register */
+ __IO uint32_t CFSR; /*!< Offset: 0x028 (R/W) Configurable Fault Status Register */
+ __IO uint32_t HFSR; /*!< Offset: 0x02C (R/W) HardFault Status Register */
+ __IO uint32_t DFSR; /*!< Offset: 0x030 (R/W) Debug Fault Status Register */
+ __IO uint32_t MMFAR; /*!< Offset: 0x034 (R/W) MemManage Fault Address Register */
+ __IO uint32_t BFAR; /*!< Offset: 0x038 (R/W) BusFault Address Register */
+ __IO uint32_t AFSR; /*!< Offset: 0x03C (R/W) Auxiliary Fault Status Register */
+ __I uint32_t PFR[2]; /*!< Offset: 0x040 (R/ ) Processor Feature Register */
+ __I uint32_t DFR; /*!< Offset: 0x048 (R/ ) Debug Feature Register */
+ __I uint32_t ADR; /*!< Offset: 0x04C (R/ ) Auxiliary Feature Register */
+ __I uint32_t MMFR[4]; /*!< Offset: 0x050 (R/ ) Memory Model Feature Register */
+ __I uint32_t ISAR[5]; /*!< Offset: 0x060 (R/ ) Instruction Set Attributes Register */
+ uint32_t RESERVED0[5];
+ __IO uint32_t CPACR; /*!< Offset: 0x088 (R/W) Coprocessor Access Control Register */
+} SCB_Type;
+
+/* SCB CPUID Register Definitions */
+#define SCB_CPUID_IMPLEMENTER_Pos 24 /*!< SCB CPUID: IMPLEMENTER Position */
+#define SCB_CPUID_IMPLEMENTER_Msk (0xFFUL << SCB_CPUID_IMPLEMENTER_Pos) /*!< SCB CPUID: IMPLEMENTER Mask */
+
+#define SCB_CPUID_VARIANT_Pos 20 /*!< SCB CPUID: VARIANT Position */
+#define SCB_CPUID_VARIANT_Msk (0xFUL << SCB_CPUID_VARIANT_Pos) /*!< SCB CPUID: VARIANT Mask */
+
+#define SCB_CPUID_ARCHITECTURE_Pos 16 /*!< SCB CPUID: ARCHITECTURE Position */
+#define SCB_CPUID_ARCHITECTURE_Msk (0xFUL << SCB_CPUID_ARCHITECTURE_Pos) /*!< SCB CPUID: ARCHITECTURE Mask */
+
+#define SCB_CPUID_PARTNO_Pos 4 /*!< SCB CPUID: PARTNO Position */
+#define SCB_CPUID_PARTNO_Msk (0xFFFUL << SCB_CPUID_PARTNO_Pos) /*!< SCB CPUID: PARTNO Mask */
+
+#define SCB_CPUID_REVISION_Pos 0 /*!< SCB CPUID: REVISION Position */
+#define SCB_CPUID_REVISION_Msk (0xFUL << SCB_CPUID_REVISION_Pos) /*!< SCB CPUID: REVISION Mask */
+
+/* SCB Interrupt Control State Register Definitions */
+#define SCB_ICSR_NMIPENDSET_Pos 31 /*!< SCB ICSR: NMIPENDSET Position */
+#define SCB_ICSR_NMIPENDSET_Msk (1UL << SCB_ICSR_NMIPENDSET_Pos) /*!< SCB ICSR: NMIPENDSET Mask */
+
+#define SCB_ICSR_PENDSVSET_Pos 28 /*!< SCB ICSR: PENDSVSET Position */
+#define SCB_ICSR_PENDSVSET_Msk (1UL << SCB_ICSR_PENDSVSET_Pos) /*!< SCB ICSR: PENDSVSET Mask */
+
+#define SCB_ICSR_PENDSVCLR_Pos 27 /*!< SCB ICSR: PENDSVCLR Position */
+#define SCB_ICSR_PENDSVCLR_Msk (1UL << SCB_ICSR_PENDSVCLR_Pos) /*!< SCB ICSR: PENDSVCLR Mask */
+
+#define SCB_ICSR_PENDSTSET_Pos 26 /*!< SCB ICSR: PENDSTSET Position */
+#define SCB_ICSR_PENDSTSET_Msk (1UL << SCB_ICSR_PENDSTSET_Pos) /*!< SCB ICSR: PENDSTSET Mask */
+
+#define SCB_ICSR_PENDSTCLR_Pos 25 /*!< SCB ICSR: PENDSTCLR Position */
+#define SCB_ICSR_PENDSTCLR_Msk (1UL << SCB_ICSR_PENDSTCLR_Pos) /*!< SCB ICSR: PENDSTCLR Mask */
+
+#define SCB_ICSR_ISRPREEMPT_Pos 23 /*!< SCB ICSR: ISRPREEMPT Position */
+#define SCB_ICSR_ISRPREEMPT_Msk (1UL << SCB_ICSR_ISRPREEMPT_Pos) /*!< SCB ICSR: ISRPREEMPT Mask */
+
+#define SCB_ICSR_ISRPENDING_Pos 22 /*!< SCB ICSR: ISRPENDING Position */
+#define SCB_ICSR_ISRPENDING_Msk (1UL << SCB_ICSR_ISRPENDING_Pos) /*!< SCB ICSR: ISRPENDING Mask */
+
+#define SCB_ICSR_VECTPENDING_Pos 12 /*!< SCB ICSR: VECTPENDING Position */
+#define SCB_ICSR_VECTPENDING_Msk (0x1FFUL << SCB_ICSR_VECTPENDING_Pos) /*!< SCB ICSR: VECTPENDING Mask */
+
+#define SCB_ICSR_RETTOBASE_Pos 11 /*!< SCB ICSR: RETTOBASE Position */
+#define SCB_ICSR_RETTOBASE_Msk (1UL << SCB_ICSR_RETTOBASE_Pos) /*!< SCB ICSR: RETTOBASE Mask */
+
+#define SCB_ICSR_VECTACTIVE_Pos 0 /*!< SCB ICSR: VECTACTIVE Position */
+#define SCB_ICSR_VECTACTIVE_Msk (0x1FFUL << SCB_ICSR_VECTACTIVE_Pos) /*!< SCB ICSR: VECTACTIVE Mask */
+
+/* SCB Vector Table Offset Register Definitions */
+#define SCB_VTOR_TBLOFF_Pos 7 /*!< SCB VTOR: TBLOFF Position */
+#define SCB_VTOR_TBLOFF_Msk (0x1FFFFFFUL << SCB_VTOR_TBLOFF_Pos) /*!< SCB VTOR: TBLOFF Mask */
+
+/* SCB Application Interrupt and Reset Control Register Definitions */
+#define SCB_AIRCR_VECTKEY_Pos 16 /*!< SCB AIRCR: VECTKEY Position */
+#define SCB_AIRCR_VECTKEY_Msk (0xFFFFUL << SCB_AIRCR_VECTKEY_Pos) /*!< SCB AIRCR: VECTKEY Mask */
+
+#define SCB_AIRCR_VECTKEYSTAT_Pos 16 /*!< SCB AIRCR: VECTKEYSTAT Position */
+#define SCB_AIRCR_VECTKEYSTAT_Msk (0xFFFFUL << SCB_AIRCR_VECTKEYSTAT_Pos) /*!< SCB AIRCR: VECTKEYSTAT Mask */
+
+#define SCB_AIRCR_ENDIANESS_Pos 15 /*!< SCB AIRCR: ENDIANESS Position */
+#define SCB_AIRCR_ENDIANESS_Msk (1UL << SCB_AIRCR_ENDIANESS_Pos) /*!< SCB AIRCR: ENDIANESS Mask */
+
+#define SCB_AIRCR_PRIGROUP_Pos 8 /*!< SCB AIRCR: PRIGROUP Position */
+#define SCB_AIRCR_PRIGROUP_Msk (7UL << SCB_AIRCR_PRIGROUP_Pos) /*!< SCB AIRCR: PRIGROUP Mask */
+
+#define SCB_AIRCR_SYSRESETREQ_Pos 2 /*!< SCB AIRCR: SYSRESETREQ Position */
+#define SCB_AIRCR_SYSRESETREQ_Msk (1UL << SCB_AIRCR_SYSRESETREQ_Pos) /*!< SCB AIRCR: SYSRESETREQ Mask */
+
+#define SCB_AIRCR_VECTCLRACTIVE_Pos 1 /*!< SCB AIRCR: VECTCLRACTIVE Position */
+#define SCB_AIRCR_VECTCLRACTIVE_Msk (1UL << SCB_AIRCR_VECTCLRACTIVE_Pos) /*!< SCB AIRCR: VECTCLRACTIVE Mask */
+
+#define SCB_AIRCR_VECTRESET_Pos 0 /*!< SCB AIRCR: VECTRESET Position */
+#define SCB_AIRCR_VECTRESET_Msk (1UL << SCB_AIRCR_VECTRESET_Pos) /*!< SCB AIRCR: VECTRESET Mask */
+
+/* SCB System Control Register Definitions */
+#define SCB_SCR_SEVONPEND_Pos 4 /*!< SCB SCR: SEVONPEND Position */
+#define SCB_SCR_SEVONPEND_Msk (1UL << SCB_SCR_SEVONPEND_Pos) /*!< SCB SCR: SEVONPEND Mask */
+
+#define SCB_SCR_SLEEPDEEP_Pos 2 /*!< SCB SCR: SLEEPDEEP Position */
+#define SCB_SCR_SLEEPDEEP_Msk (1UL << SCB_SCR_SLEEPDEEP_Pos) /*!< SCB SCR: SLEEPDEEP Mask */
+
+#define SCB_SCR_SLEEPONEXIT_Pos 1 /*!< SCB SCR: SLEEPONEXIT Position */
+#define SCB_SCR_SLEEPONEXIT_Msk (1UL << SCB_SCR_SLEEPONEXIT_Pos) /*!< SCB SCR: SLEEPONEXIT Mask */
+
+/* SCB Configuration Control Register Definitions */
+#define SCB_CCR_STKALIGN_Pos 9 /*!< SCB CCR: STKALIGN Position */
+#define SCB_CCR_STKALIGN_Msk (1UL << SCB_CCR_STKALIGN_Pos) /*!< SCB CCR: STKALIGN Mask */
+
+#define SCB_CCR_BFHFNMIGN_Pos 8 /*!< SCB CCR: BFHFNMIGN Position */
+#define SCB_CCR_BFHFNMIGN_Msk (1UL << SCB_CCR_BFHFNMIGN_Pos) /*!< SCB CCR: BFHFNMIGN Mask */
+
+#define SCB_CCR_DIV_0_TRP_Pos 4 /*!< SCB CCR: DIV_0_TRP Position */
+#define SCB_CCR_DIV_0_TRP_Msk (1UL << SCB_CCR_DIV_0_TRP_Pos) /*!< SCB CCR: DIV_0_TRP Mask */
+
+#define SCB_CCR_UNALIGN_TRP_Pos 3 /*!< SCB CCR: UNALIGN_TRP Position */
+#define SCB_CCR_UNALIGN_TRP_Msk (1UL << SCB_CCR_UNALIGN_TRP_Pos) /*!< SCB CCR: UNALIGN_TRP Mask */
+
+#define SCB_CCR_USERSETMPEND_Pos 1 /*!< SCB CCR: USERSETMPEND Position */
+#define SCB_CCR_USERSETMPEND_Msk (1UL << SCB_CCR_USERSETMPEND_Pos) /*!< SCB CCR: USERSETMPEND Mask */
+
+#define SCB_CCR_NONBASETHRDENA_Pos 0 /*!< SCB CCR: NONBASETHRDENA Position */
+#define SCB_CCR_NONBASETHRDENA_Msk (1UL << SCB_CCR_NONBASETHRDENA_Pos) /*!< SCB CCR: NONBASETHRDENA Mask */
+
+/* SCB System Handler Control and State Register Definitions */
+#define SCB_SHCSR_USGFAULTENA_Pos 18 /*!< SCB SHCSR: USGFAULTENA Position */
+#define SCB_SHCSR_USGFAULTENA_Msk (1UL << SCB_SHCSR_USGFAULTENA_Pos) /*!< SCB SHCSR: USGFAULTENA Mask */
+
+#define SCB_SHCSR_BUSFAULTENA_Pos 17 /*!< SCB SHCSR: BUSFAULTENA Position */
+#define SCB_SHCSR_BUSFAULTENA_Msk (1UL << SCB_SHCSR_BUSFAULTENA_Pos) /*!< SCB SHCSR: BUSFAULTENA Mask */
+
+#define SCB_SHCSR_MEMFAULTENA_Pos 16 /*!< SCB SHCSR: MEMFAULTENA Position */
+#define SCB_SHCSR_MEMFAULTENA_Msk (1UL << SCB_SHCSR_MEMFAULTENA_Pos) /*!< SCB SHCSR: MEMFAULTENA Mask */
+
+#define SCB_SHCSR_SVCALLPENDED_Pos 15 /*!< SCB SHCSR: SVCALLPENDED Position */
+#define SCB_SHCSR_SVCALLPENDED_Msk (1UL << SCB_SHCSR_SVCALLPENDED_Pos) /*!< SCB SHCSR: SVCALLPENDED Mask */
+
+#define SCB_SHCSR_BUSFAULTPENDED_Pos 14 /*!< SCB SHCSR: BUSFAULTPENDED Position */
+#define SCB_SHCSR_BUSFAULTPENDED_Msk (1UL << SCB_SHCSR_BUSFAULTPENDED_Pos) /*!< SCB SHCSR: BUSFAULTPENDED Mask */
+
+#define SCB_SHCSR_MEMFAULTPENDED_Pos 13 /*!< SCB SHCSR: MEMFAULTPENDED Position */
+#define SCB_SHCSR_MEMFAULTPENDED_Msk (1UL << SCB_SHCSR_MEMFAULTPENDED_Pos) /*!< SCB SHCSR: MEMFAULTPENDED Mask */
+
+#define SCB_SHCSR_USGFAULTPENDED_Pos 12 /*!< SCB SHCSR: USGFAULTPENDED Position */
+#define SCB_SHCSR_USGFAULTPENDED_Msk (1UL << SCB_SHCSR_USGFAULTPENDED_Pos) /*!< SCB SHCSR: USGFAULTPENDED Mask */
+
+#define SCB_SHCSR_SYSTICKACT_Pos 11 /*!< SCB SHCSR: SYSTICKACT Position */
+#define SCB_SHCSR_SYSTICKACT_Msk (1UL << SCB_SHCSR_SYSTICKACT_Pos) /*!< SCB SHCSR: SYSTICKACT Mask */
+
+#define SCB_SHCSR_PENDSVACT_Pos 10 /*!< SCB SHCSR: PENDSVACT Position */
+#define SCB_SHCSR_PENDSVACT_Msk (1UL << SCB_SHCSR_PENDSVACT_Pos) /*!< SCB SHCSR: PENDSVACT Mask */
+
+#define SCB_SHCSR_MONITORACT_Pos 8 /*!< SCB SHCSR: MONITORACT Position */
+#define SCB_SHCSR_MONITORACT_Msk (1UL << SCB_SHCSR_MONITORACT_Pos) /*!< SCB SHCSR: MONITORACT Mask */
+
+#define SCB_SHCSR_SVCALLACT_Pos 7 /*!< SCB SHCSR: SVCALLACT Position */
+#define SCB_SHCSR_SVCALLACT_Msk (1UL << SCB_SHCSR_SVCALLACT_Pos) /*!< SCB SHCSR: SVCALLACT Mask */
+
+#define SCB_SHCSR_USGFAULTACT_Pos 3 /*!< SCB SHCSR: USGFAULTACT Position */
+#define SCB_SHCSR_USGFAULTACT_Msk (1UL << SCB_SHCSR_USGFAULTACT_Pos) /*!< SCB SHCSR: USGFAULTACT Mask */
+
+#define SCB_SHCSR_BUSFAULTACT_Pos 1 /*!< SCB SHCSR: BUSFAULTACT Position */
+#define SCB_SHCSR_BUSFAULTACT_Msk (1UL << SCB_SHCSR_BUSFAULTACT_Pos) /*!< SCB SHCSR: BUSFAULTACT Mask */
+
+#define SCB_SHCSR_MEMFAULTACT_Pos 0 /*!< SCB SHCSR: MEMFAULTACT Position */
+#define SCB_SHCSR_MEMFAULTACT_Msk (1UL << SCB_SHCSR_MEMFAULTACT_Pos) /*!< SCB SHCSR: MEMFAULTACT Mask */
+
+/* SCB Configurable Fault Status Registers Definitions */
+#define SCB_CFSR_USGFAULTSR_Pos 16 /*!< SCB CFSR: Usage Fault Status Register Position */
+#define SCB_CFSR_USGFAULTSR_Msk (0xFFFFUL << SCB_CFSR_USGFAULTSR_Pos) /*!< SCB CFSR: Usage Fault Status Register Mask */
+
+#define SCB_CFSR_BUSFAULTSR_Pos 8 /*!< SCB CFSR: Bus Fault Status Register Position */
+#define SCB_CFSR_BUSFAULTSR_Msk (0xFFUL << SCB_CFSR_BUSFAULTSR_Pos) /*!< SCB CFSR: Bus Fault Status Register Mask */
+
+#define SCB_CFSR_MEMFAULTSR_Pos 0 /*!< SCB CFSR: Memory Manage Fault Status Register Position */
+#define SCB_CFSR_MEMFAULTSR_Msk (0xFFUL << SCB_CFSR_MEMFAULTSR_Pos) /*!< SCB CFSR: Memory Manage Fault Status Register Mask */
+
+/* SCB Hard Fault Status Registers Definitions */
+#define SCB_HFSR_DEBUGEVT_Pos 31 /*!< SCB HFSR: DEBUGEVT Position */
+#define SCB_HFSR_DEBUGEVT_Msk (1UL << SCB_HFSR_DEBUGEVT_Pos) /*!< SCB HFSR: DEBUGEVT Mask */
+
+#define SCB_HFSR_FORCED_Pos 30 /*!< SCB HFSR: FORCED Position */
+#define SCB_HFSR_FORCED_Msk (1UL << SCB_HFSR_FORCED_Pos) /*!< SCB HFSR: FORCED Mask */
+
+#define SCB_HFSR_VECTTBL_Pos 1 /*!< SCB HFSR: VECTTBL Position */
+#define SCB_HFSR_VECTTBL_Msk (1UL << SCB_HFSR_VECTTBL_Pos) /*!< SCB HFSR: VECTTBL Mask */
+
+/* SCB Debug Fault Status Register Definitions */
+#define SCB_DFSR_EXTERNAL_Pos 4 /*!< SCB DFSR: EXTERNAL Position */
+#define SCB_DFSR_EXTERNAL_Msk (1UL << SCB_DFSR_EXTERNAL_Pos) /*!< SCB DFSR: EXTERNAL Mask */
+
+#define SCB_DFSR_VCATCH_Pos 3 /*!< SCB DFSR: VCATCH Position */
+#define SCB_DFSR_VCATCH_Msk (1UL << SCB_DFSR_VCATCH_Pos) /*!< SCB DFSR: VCATCH Mask */
+
+#define SCB_DFSR_DWTTRAP_Pos 2 /*!< SCB DFSR: DWTTRAP Position */
+#define SCB_DFSR_DWTTRAP_Msk (1UL << SCB_DFSR_DWTTRAP_Pos) /*!< SCB DFSR: DWTTRAP Mask */
+
+#define SCB_DFSR_BKPT_Pos 1 /*!< SCB DFSR: BKPT Position */
+#define SCB_DFSR_BKPT_Msk (1UL << SCB_DFSR_BKPT_Pos) /*!< SCB DFSR: BKPT Mask */
+
+#define SCB_DFSR_HALTED_Pos 0 /*!< SCB DFSR: HALTED Position */
+#define SCB_DFSR_HALTED_Msk (1UL << SCB_DFSR_HALTED_Pos) /*!< SCB DFSR: HALTED Mask */
+
+/*@} end of group CMSIS_SCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SCnSCB System Controls not in SCB (SCnSCB)
+ \brief Type definitions for the System Control and ID Register not in the SCB
+ @{
+ */
+
+/** \brief Structure type to access the System Control and ID Register not in the SCB.
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1];
+ __I uint32_t ICTR; /*!< Offset: 0x004 (R/ ) Interrupt Controller Type Register */
+ __IO uint32_t ACTLR; /*!< Offset: 0x008 (R/W) Auxiliary Control Register */
+} SCnSCB_Type;
+
+/* Interrupt Controller Type Register Definitions */
+#define SCnSCB_ICTR_INTLINESNUM_Pos 0 /*!< ICTR: INTLINESNUM Position */
+#define SCnSCB_ICTR_INTLINESNUM_Msk (0xFUL << SCnSCB_ICTR_INTLINESNUM_Pos) /*!< ICTR: INTLINESNUM Mask */
+
+/* Auxiliary Control Register Definitions */
+#define SCnSCB_ACTLR_DISOOFP_Pos 9 /*!< ACTLR: DISOOFP Position */
+#define SCnSCB_ACTLR_DISOOFP_Msk (1UL << SCnSCB_ACTLR_DISOOFP_Pos) /*!< ACTLR: DISOOFP Mask */
+
+#define SCnSCB_ACTLR_DISFPCA_Pos 8 /*!< ACTLR: DISFPCA Position */
+#define SCnSCB_ACTLR_DISFPCA_Msk (1UL << SCnSCB_ACTLR_DISFPCA_Pos) /*!< ACTLR: DISFPCA Mask */
+
+#define SCnSCB_ACTLR_DISFOLD_Pos 2 /*!< ACTLR: DISFOLD Position */
+#define SCnSCB_ACTLR_DISFOLD_Msk (1UL << SCnSCB_ACTLR_DISFOLD_Pos) /*!< ACTLR: DISFOLD Mask */
+
+#define SCnSCB_ACTLR_DISDEFWBUF_Pos 1 /*!< ACTLR: DISDEFWBUF Position */
+#define SCnSCB_ACTLR_DISDEFWBUF_Msk (1UL << SCnSCB_ACTLR_DISDEFWBUF_Pos) /*!< ACTLR: DISDEFWBUF Mask */
+
+#define SCnSCB_ACTLR_DISMCYCINT_Pos 0 /*!< ACTLR: DISMCYCINT Position */
+#define SCnSCB_ACTLR_DISMCYCINT_Msk (1UL << SCnSCB_ACTLR_DISMCYCINT_Pos) /*!< ACTLR: DISMCYCINT Mask */
+
+/*@} end of group CMSIS_SCnotSCB */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_SysTick System Tick Timer (SysTick)
+ \brief Type definitions for the System Timer Registers.
+ @{
+ */
+
+/** \brief Structure type to access the System Timer (SysTick).
+ */
+typedef struct
+{
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) SysTick Control and Status Register */
+ __IO uint32_t LOAD; /*!< Offset: 0x004 (R/W) SysTick Reload Value Register */
+ __IO uint32_t VAL; /*!< Offset: 0x008 (R/W) SysTick Current Value Register */
+ __I uint32_t CALIB; /*!< Offset: 0x00C (R/ ) SysTick Calibration Register */
+} SysTick_Type;
+
+/* SysTick Control / Status Register Definitions */
+#define SysTick_CTRL_COUNTFLAG_Pos 16 /*!< SysTick CTRL: COUNTFLAG Position */
+#define SysTick_CTRL_COUNTFLAG_Msk (1UL << SysTick_CTRL_COUNTFLAG_Pos) /*!< SysTick CTRL: COUNTFLAG Mask */
+
+#define SysTick_CTRL_CLKSOURCE_Pos 2 /*!< SysTick CTRL: CLKSOURCE Position */
+#define SysTick_CTRL_CLKSOURCE_Msk (1UL << SysTick_CTRL_CLKSOURCE_Pos) /*!< SysTick CTRL: CLKSOURCE Mask */
+
+#define SysTick_CTRL_TICKINT_Pos 1 /*!< SysTick CTRL: TICKINT Position */
+#define SysTick_CTRL_TICKINT_Msk (1UL << SysTick_CTRL_TICKINT_Pos) /*!< SysTick CTRL: TICKINT Mask */
+
+#define SysTick_CTRL_ENABLE_Pos 0 /*!< SysTick CTRL: ENABLE Position */
+#define SysTick_CTRL_ENABLE_Msk (1UL << SysTick_CTRL_ENABLE_Pos) /*!< SysTick CTRL: ENABLE Mask */
+
+/* SysTick Reload Register Definitions */
+#define SysTick_LOAD_RELOAD_Pos 0 /*!< SysTick LOAD: RELOAD Position */
+#define SysTick_LOAD_RELOAD_Msk (0xFFFFFFUL << SysTick_LOAD_RELOAD_Pos) /*!< SysTick LOAD: RELOAD Mask */
+
+/* SysTick Current Register Definitions */
+#define SysTick_VAL_CURRENT_Pos 0 /*!< SysTick VAL: CURRENT Position */
+#define SysTick_VAL_CURRENT_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick VAL: CURRENT Mask */
+
+/* SysTick Calibration Register Definitions */
+#define SysTick_CALIB_NOREF_Pos 31 /*!< SysTick CALIB: NOREF Position */
+#define SysTick_CALIB_NOREF_Msk (1UL << SysTick_CALIB_NOREF_Pos) /*!< SysTick CALIB: NOREF Mask */
+
+#define SysTick_CALIB_SKEW_Pos 30 /*!< SysTick CALIB: SKEW Position */
+#define SysTick_CALIB_SKEW_Msk (1UL << SysTick_CALIB_SKEW_Pos) /*!< SysTick CALIB: SKEW Mask */
+
+#define SysTick_CALIB_TENMS_Pos 0 /*!< SysTick CALIB: TENMS Position */
+#define SysTick_CALIB_TENMS_Msk (0xFFFFFFUL << SysTick_VAL_CURRENT_Pos) /*!< SysTick CALIB: TENMS Mask */
+
+/*@} end of group CMSIS_SysTick */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_ITM Instrumentation Trace Macrocell (ITM)
+ \brief Type definitions for the Instrumentation Trace Macrocell (ITM)
+ @{
+ */
+
+/** \brief Structure type to access the Instrumentation Trace Macrocell Register (ITM).
+ */
+typedef struct
+{
+ __O union
+ {
+ __O uint8_t u8; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 8-bit */
+ __O uint16_t u16; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 16-bit */
+ __O uint32_t u32; /*!< Offset: 0x000 ( /W) ITM Stimulus Port 32-bit */
+ } PORT [32]; /*!< Offset: 0x000 ( /W) ITM Stimulus Port Registers */
+ uint32_t RESERVED0[864];
+ __IO uint32_t TER; /*!< Offset: 0xE00 (R/W) ITM Trace Enable Register */
+ uint32_t RESERVED1[15];
+ __IO uint32_t TPR; /*!< Offset: 0xE40 (R/W) ITM Trace Privilege Register */
+ uint32_t RESERVED2[15];
+ __IO uint32_t TCR; /*!< Offset: 0xE80 (R/W) ITM Trace Control Register */
+ uint32_t RESERVED3[29];
+ __O uint32_t IWR; /*!< Offset: 0xEF8 ( /W) ITM Integration Write Register */
+ __I uint32_t IRR; /*!< Offset: 0xEFC (R/ ) ITM Integration Read Register */
+ __IO uint32_t IMCR; /*!< Offset: 0xF00 (R/W) ITM Integration Mode Control Register */
+ uint32_t RESERVED4[43];
+ __O uint32_t LAR; /*!< Offset: 0xFB0 ( /W) ITM Lock Access Register */
+ __I uint32_t LSR; /*!< Offset: 0xFB4 (R/ ) ITM Lock Status Register */
+ uint32_t RESERVED5[6];
+ __I uint32_t PID4; /*!< Offset: 0xFD0 (R/ ) ITM Peripheral Identification Register #4 */
+ __I uint32_t PID5; /*!< Offset: 0xFD4 (R/ ) ITM Peripheral Identification Register #5 */
+ __I uint32_t PID6; /*!< Offset: 0xFD8 (R/ ) ITM Peripheral Identification Register #6 */
+ __I uint32_t PID7; /*!< Offset: 0xFDC (R/ ) ITM Peripheral Identification Register #7 */
+ __I uint32_t PID0; /*!< Offset: 0xFE0 (R/ ) ITM Peripheral Identification Register #0 */
+ __I uint32_t PID1; /*!< Offset: 0xFE4 (R/ ) ITM Peripheral Identification Register #1 */
+ __I uint32_t PID2; /*!< Offset: 0xFE8 (R/ ) ITM Peripheral Identification Register #2 */
+ __I uint32_t PID3; /*!< Offset: 0xFEC (R/ ) ITM Peripheral Identification Register #3 */
+ __I uint32_t CID0; /*!< Offset: 0xFF0 (R/ ) ITM Component Identification Register #0 */
+ __I uint32_t CID1; /*!< Offset: 0xFF4 (R/ ) ITM Component Identification Register #1 */
+ __I uint32_t CID2; /*!< Offset: 0xFF8 (R/ ) ITM Component Identification Register #2 */
+ __I uint32_t CID3; /*!< Offset: 0xFFC (R/ ) ITM Component Identification Register #3 */
+} ITM_Type;
+
+/* ITM Trace Privilege Register Definitions */
+#define ITM_TPR_PRIVMASK_Pos 0 /*!< ITM TPR: PRIVMASK Position */
+#define ITM_TPR_PRIVMASK_Msk (0xFUL << ITM_TPR_PRIVMASK_Pos) /*!< ITM TPR: PRIVMASK Mask */
+
+/* ITM Trace Control Register Definitions */
+#define ITM_TCR_BUSY_Pos 23 /*!< ITM TCR: BUSY Position */
+#define ITM_TCR_BUSY_Msk (1UL << ITM_TCR_BUSY_Pos) /*!< ITM TCR: BUSY Mask */
+
+#define ITM_TCR_TraceBusID_Pos 16 /*!< ITM TCR: ATBID Position */
+#define ITM_TCR_TraceBusID_Msk (0x7FUL << ITM_TCR_TraceBusID_Pos) /*!< ITM TCR: ATBID Mask */
+
+#define ITM_TCR_GTSFREQ_Pos 10 /*!< ITM TCR: Global timestamp frequency Position */
+#define ITM_TCR_GTSFREQ_Msk (3UL << ITM_TCR_GTSFREQ_Pos) /*!< ITM TCR: Global timestamp frequency Mask */
+
+#define ITM_TCR_TSPrescale_Pos 8 /*!< ITM TCR: TSPrescale Position */
+#define ITM_TCR_TSPrescale_Msk (3UL << ITM_TCR_TSPrescale_Pos) /*!< ITM TCR: TSPrescale Mask */
+
+#define ITM_TCR_SWOENA_Pos 4 /*!< ITM TCR: SWOENA Position */
+#define ITM_TCR_SWOENA_Msk (1UL << ITM_TCR_SWOENA_Pos) /*!< ITM TCR: SWOENA Mask */
+
+#define ITM_TCR_DWTENA_Pos 3 /*!< ITM TCR: DWTENA Position */
+#define ITM_TCR_DWTENA_Msk (1UL << ITM_TCR_DWTENA_Pos) /*!< ITM TCR: DWTENA Mask */
+
+#define ITM_TCR_SYNCENA_Pos 2 /*!< ITM TCR: SYNCENA Position */
+#define ITM_TCR_SYNCENA_Msk (1UL << ITM_TCR_SYNCENA_Pos) /*!< ITM TCR: SYNCENA Mask */
+
+#define ITM_TCR_TSENA_Pos 1 /*!< ITM TCR: TSENA Position */
+#define ITM_TCR_TSENA_Msk (1UL << ITM_TCR_TSENA_Pos) /*!< ITM TCR: TSENA Mask */
+
+#define ITM_TCR_ITMENA_Pos 0 /*!< ITM TCR: ITM Enable bit Position */
+#define ITM_TCR_ITMENA_Msk (1UL << ITM_TCR_ITMENA_Pos) /*!< ITM TCR: ITM Enable bit Mask */
+
+/* ITM Integration Write Register Definitions */
+#define ITM_IWR_ATVALIDM_Pos 0 /*!< ITM IWR: ATVALIDM Position */
+#define ITM_IWR_ATVALIDM_Msk (1UL << ITM_IWR_ATVALIDM_Pos) /*!< ITM IWR: ATVALIDM Mask */
+
+/* ITM Integration Read Register Definitions */
+#define ITM_IRR_ATREADYM_Pos 0 /*!< ITM IRR: ATREADYM Position */
+#define ITM_IRR_ATREADYM_Msk (1UL << ITM_IRR_ATREADYM_Pos) /*!< ITM IRR: ATREADYM Mask */
+
+/* ITM Integration Mode Control Register Definitions */
+#define ITM_IMCR_INTEGRATION_Pos 0 /*!< ITM IMCR: INTEGRATION Position */
+#define ITM_IMCR_INTEGRATION_Msk (1UL << ITM_IMCR_INTEGRATION_Pos) /*!< ITM IMCR: INTEGRATION Mask */
+
+/* ITM Lock Status Register Definitions */
+#define ITM_LSR_ByteAcc_Pos 2 /*!< ITM LSR: ByteAcc Position */
+#define ITM_LSR_ByteAcc_Msk (1UL << ITM_LSR_ByteAcc_Pos) /*!< ITM LSR: ByteAcc Mask */
+
+#define ITM_LSR_Access_Pos 1 /*!< ITM LSR: Access Position */
+#define ITM_LSR_Access_Msk (1UL << ITM_LSR_Access_Pos) /*!< ITM LSR: Access Mask */
+
+#define ITM_LSR_Present_Pos 0 /*!< ITM LSR: Present Position */
+#define ITM_LSR_Present_Msk (1UL << ITM_LSR_Present_Pos) /*!< ITM LSR: Present Mask */
+
+/*@}*/ /* end of group CMSIS_ITM */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_DWT Data Watchpoint and Trace (DWT)
+ \brief Type definitions for the Data Watchpoint and Trace (DWT)
+ @{
+ */
+
+/** \brief Structure type to access the Data Watchpoint and Trace Register (DWT).
+ */
+typedef struct
+{
+ __IO uint32_t CTRL; /*!< Offset: 0x000 (R/W) Control Register */
+ __IO uint32_t CYCCNT; /*!< Offset: 0x004 (R/W) Cycle Count Register */
+ __IO uint32_t CPICNT; /*!< Offset: 0x008 (R/W) CPI Count Register */
+ __IO uint32_t EXCCNT; /*!< Offset: 0x00C (R/W) Exception Overhead Count Register */
+ __IO uint32_t SLEEPCNT; /*!< Offset: 0x010 (R/W) Sleep Count Register */
+ __IO uint32_t LSUCNT; /*!< Offset: 0x014 (R/W) LSU Count Register */
+ __IO uint32_t FOLDCNT; /*!< Offset: 0x018 (R/W) Folded-instruction Count Register */
+ __I uint32_t PCSR; /*!< Offset: 0x01C (R/ ) Program Counter Sample Register */
+ __IO uint32_t COMP0; /*!< Offset: 0x020 (R/W) Comparator Register 0 */
+ __IO uint32_t MASK0; /*!< Offset: 0x024 (R/W) Mask Register 0 */
+ __IO uint32_t FUNCTION0; /*!< Offset: 0x028 (R/W) Function Register 0 */
+ uint32_t RESERVED0[1];
+ __IO uint32_t COMP1; /*!< Offset: 0x030 (R/W) Comparator Register 1 */
+ __IO uint32_t MASK1; /*!< Offset: 0x034 (R/W) Mask Register 1 */
+ __IO uint32_t FUNCTION1; /*!< Offset: 0x038 (R/W) Function Register 1 */
+ uint32_t RESERVED1[1];
+ __IO uint32_t COMP2; /*!< Offset: 0x040 (R/W) Comparator Register 2 */
+ __IO uint32_t MASK2; /*!< Offset: 0x044 (R/W) Mask Register 2 */
+ __IO uint32_t FUNCTION2; /*!< Offset: 0x048 (R/W) Function Register 2 */
+ uint32_t RESERVED2[1];
+ __IO uint32_t COMP3; /*!< Offset: 0x050 (R/W) Comparator Register 3 */
+ __IO uint32_t MASK3; /*!< Offset: 0x054 (R/W) Mask Register 3 */
+ __IO uint32_t FUNCTION3; /*!< Offset: 0x058 (R/W) Function Register 3 */
+} DWT_Type;
+
+/* DWT Control Register Definitions */
+#define DWT_CTRL_NUMCOMP_Pos 28 /*!< DWT CTRL: NUMCOMP Position */
+#define DWT_CTRL_NUMCOMP_Msk (0xFUL << DWT_CTRL_NUMCOMP_Pos) /*!< DWT CTRL: NUMCOMP Mask */
+
+#define DWT_CTRL_NOTRCPKT_Pos 27 /*!< DWT CTRL: NOTRCPKT Position */
+#define DWT_CTRL_NOTRCPKT_Msk (0x1UL << DWT_CTRL_NOTRCPKT_Pos) /*!< DWT CTRL: NOTRCPKT Mask */
+
+#define DWT_CTRL_NOEXTTRIG_Pos 26 /*!< DWT CTRL: NOEXTTRIG Position */
+#define DWT_CTRL_NOEXTTRIG_Msk (0x1UL << DWT_CTRL_NOEXTTRIG_Pos) /*!< DWT CTRL: NOEXTTRIG Mask */
+
+#define DWT_CTRL_NOCYCCNT_Pos 25 /*!< DWT CTRL: NOCYCCNT Position */
+#define DWT_CTRL_NOCYCCNT_Msk (0x1UL << DWT_CTRL_NOCYCCNT_Pos) /*!< DWT CTRL: NOCYCCNT Mask */
+
+#define DWT_CTRL_NOPRFCNT_Pos 24 /*!< DWT CTRL: NOPRFCNT Position */
+#define DWT_CTRL_NOPRFCNT_Msk (0x1UL << DWT_CTRL_NOPRFCNT_Pos) /*!< DWT CTRL: NOPRFCNT Mask */
+
+#define DWT_CTRL_CYCEVTENA_Pos 22 /*!< DWT CTRL: CYCEVTENA Position */
+#define DWT_CTRL_CYCEVTENA_Msk (0x1UL << DWT_CTRL_CYCEVTENA_Pos) /*!< DWT CTRL: CYCEVTENA Mask */
+
+#define DWT_CTRL_FOLDEVTENA_Pos 21 /*!< DWT CTRL: FOLDEVTENA Position */
+#define DWT_CTRL_FOLDEVTENA_Msk (0x1UL << DWT_CTRL_FOLDEVTENA_Pos) /*!< DWT CTRL: FOLDEVTENA Mask */
+
+#define DWT_CTRL_LSUEVTENA_Pos 20 /*!< DWT CTRL: LSUEVTENA Position */
+#define DWT_CTRL_LSUEVTENA_Msk (0x1UL << DWT_CTRL_LSUEVTENA_Pos) /*!< DWT CTRL: LSUEVTENA Mask */
+
+#define DWT_CTRL_SLEEPEVTENA_Pos 19 /*!< DWT CTRL: SLEEPEVTENA Position */
+#define DWT_CTRL_SLEEPEVTENA_Msk (0x1UL << DWT_CTRL_SLEEPEVTENA_Pos) /*!< DWT CTRL: SLEEPEVTENA Mask */
+
+#define DWT_CTRL_EXCEVTENA_Pos 18 /*!< DWT CTRL: EXCEVTENA Position */
+#define DWT_CTRL_EXCEVTENA_Msk (0x1UL << DWT_CTRL_EXCEVTENA_Pos) /*!< DWT CTRL: EXCEVTENA Mask */
+
+#define DWT_CTRL_CPIEVTENA_Pos 17 /*!< DWT CTRL: CPIEVTENA Position */
+#define DWT_CTRL_CPIEVTENA_Msk (0x1UL << DWT_CTRL_CPIEVTENA_Pos) /*!< DWT CTRL: CPIEVTENA Mask */
+
+#define DWT_CTRL_EXCTRCENA_Pos 16 /*!< DWT CTRL: EXCTRCENA Position */
+#define DWT_CTRL_EXCTRCENA_Msk (0x1UL << DWT_CTRL_EXCTRCENA_Pos) /*!< DWT CTRL: EXCTRCENA Mask */
+
+#define DWT_CTRL_PCSAMPLENA_Pos 12 /*!< DWT CTRL: PCSAMPLENA Position */
+#define DWT_CTRL_PCSAMPLENA_Msk (0x1UL << DWT_CTRL_PCSAMPLENA_Pos) /*!< DWT CTRL: PCSAMPLENA Mask */
+
+#define DWT_CTRL_SYNCTAP_Pos 10 /*!< DWT CTRL: SYNCTAP Position */
+#define DWT_CTRL_SYNCTAP_Msk (0x3UL << DWT_CTRL_SYNCTAP_Pos) /*!< DWT CTRL: SYNCTAP Mask */
+
+#define DWT_CTRL_CYCTAP_Pos 9 /*!< DWT CTRL: CYCTAP Position */
+#define DWT_CTRL_CYCTAP_Msk (0x1UL << DWT_CTRL_CYCTAP_Pos) /*!< DWT CTRL: CYCTAP Mask */
+
+#define DWT_CTRL_POSTINIT_Pos 5 /*!< DWT CTRL: POSTINIT Position */
+#define DWT_CTRL_POSTINIT_Msk (0xFUL << DWT_CTRL_POSTINIT_Pos) /*!< DWT CTRL: POSTINIT Mask */
+
+#define DWT_CTRL_POSTPRESET_Pos 1 /*!< DWT CTRL: POSTPRESET Position */
+#define DWT_CTRL_POSTPRESET_Msk (0xFUL << DWT_CTRL_POSTPRESET_Pos) /*!< DWT CTRL: POSTPRESET Mask */
+
+#define DWT_CTRL_CYCCNTENA_Pos 0 /*!< DWT CTRL: CYCCNTENA Position */
+#define DWT_CTRL_CYCCNTENA_Msk (0x1UL << DWT_CTRL_CYCCNTENA_Pos) /*!< DWT CTRL: CYCCNTENA Mask */
+
+/* DWT CPI Count Register Definitions */
+#define DWT_CPICNT_CPICNT_Pos 0 /*!< DWT CPICNT: CPICNT Position */
+#define DWT_CPICNT_CPICNT_Msk (0xFFUL << DWT_CPICNT_CPICNT_Pos) /*!< DWT CPICNT: CPICNT Mask */
+
+/* DWT Exception Overhead Count Register Definitions */
+#define DWT_EXCCNT_EXCCNT_Pos 0 /*!< DWT EXCCNT: EXCCNT Position */
+#define DWT_EXCCNT_EXCCNT_Msk (0xFFUL << DWT_EXCCNT_EXCCNT_Pos) /*!< DWT EXCCNT: EXCCNT Mask */
+
+/* DWT Sleep Count Register Definitions */
+#define DWT_SLEEPCNT_SLEEPCNT_Pos 0 /*!< DWT SLEEPCNT: SLEEPCNT Position */
+#define DWT_SLEEPCNT_SLEEPCNT_Msk (0xFFUL << DWT_SLEEPCNT_SLEEPCNT_Pos) /*!< DWT SLEEPCNT: SLEEPCNT Mask */
+
+/* DWT LSU Count Register Definitions */
+#define DWT_LSUCNT_LSUCNT_Pos 0 /*!< DWT LSUCNT: LSUCNT Position */
+#define DWT_LSUCNT_LSUCNT_Msk (0xFFUL << DWT_LSUCNT_LSUCNT_Pos) /*!< DWT LSUCNT: LSUCNT Mask */
+
+/* DWT Folded-instruction Count Register Definitions */
+#define DWT_FOLDCNT_FOLDCNT_Pos 0 /*!< DWT FOLDCNT: FOLDCNT Position */
+#define DWT_FOLDCNT_FOLDCNT_Msk (0xFFUL << DWT_FOLDCNT_FOLDCNT_Pos) /*!< DWT FOLDCNT: FOLDCNT Mask */
+
+/* DWT Comparator Mask Register Definitions */
+#define DWT_MASK_MASK_Pos 0 /*!< DWT MASK: MASK Position */
+#define DWT_MASK_MASK_Msk (0x1FUL << DWT_MASK_MASK_Pos) /*!< DWT MASK: MASK Mask */
+
+/* DWT Comparator Function Register Definitions */
+#define DWT_FUNCTION_MATCHED_Pos 24 /*!< DWT FUNCTION: MATCHED Position */
+#define DWT_FUNCTION_MATCHED_Msk (0x1UL << DWT_FUNCTION_MATCHED_Pos) /*!< DWT FUNCTION: MATCHED Mask */
+
+#define DWT_FUNCTION_DATAVADDR1_Pos 16 /*!< DWT FUNCTION: DATAVADDR1 Position */
+#define DWT_FUNCTION_DATAVADDR1_Msk (0xFUL << DWT_FUNCTION_DATAVADDR1_Pos) /*!< DWT FUNCTION: DATAVADDR1 Mask */
+
+#define DWT_FUNCTION_DATAVADDR0_Pos 12 /*!< DWT FUNCTION: DATAVADDR0 Position */
+#define DWT_FUNCTION_DATAVADDR0_Msk (0xFUL << DWT_FUNCTION_DATAVADDR0_Pos) /*!< DWT FUNCTION: DATAVADDR0 Mask */
+
+#define DWT_FUNCTION_DATAVSIZE_Pos 10 /*!< DWT FUNCTION: DATAVSIZE Position */
+#define DWT_FUNCTION_DATAVSIZE_Msk (0x3UL << DWT_FUNCTION_DATAVSIZE_Pos) /*!< DWT FUNCTION: DATAVSIZE Mask */
+
+#define DWT_FUNCTION_LNK1ENA_Pos 9 /*!< DWT FUNCTION: LNK1ENA Position */
+#define DWT_FUNCTION_LNK1ENA_Msk (0x1UL << DWT_FUNCTION_LNK1ENA_Pos) /*!< DWT FUNCTION: LNK1ENA Mask */
+
+#define DWT_FUNCTION_DATAVMATCH_Pos 8 /*!< DWT FUNCTION: DATAVMATCH Position */
+#define DWT_FUNCTION_DATAVMATCH_Msk (0x1UL << DWT_FUNCTION_DATAVMATCH_Pos) /*!< DWT FUNCTION: DATAVMATCH Mask */
+
+#define DWT_FUNCTION_CYCMATCH_Pos 7 /*!< DWT FUNCTION: CYCMATCH Position */
+#define DWT_FUNCTION_CYCMATCH_Msk (0x1UL << DWT_FUNCTION_CYCMATCH_Pos) /*!< DWT FUNCTION: CYCMATCH Mask */
+
+#define DWT_FUNCTION_EMITRANGE_Pos 5 /*!< DWT FUNCTION: EMITRANGE Position */
+#define DWT_FUNCTION_EMITRANGE_Msk (0x1UL << DWT_FUNCTION_EMITRANGE_Pos) /*!< DWT FUNCTION: EMITRANGE Mask */
+
+#define DWT_FUNCTION_FUNCTION_Pos 0 /*!< DWT FUNCTION: FUNCTION Position */
+#define DWT_FUNCTION_FUNCTION_Msk (0xFUL << DWT_FUNCTION_FUNCTION_Pos) /*!< DWT FUNCTION: FUNCTION Mask */
+
+/*@}*/ /* end of group CMSIS_DWT */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_TPI Trace Port Interface (TPI)
+ \brief Type definitions for the Trace Port Interface (TPI)
+ @{
+ */
+
+/** \brief Structure type to access the Trace Port Interface Register (TPI).
+ */
+typedef struct
+{
+ __IO uint32_t SSPSR; /*!< Offset: 0x000 (R/ ) Supported Parallel Port Size Register */
+ __IO uint32_t CSPSR; /*!< Offset: 0x004 (R/W) Current Parallel Port Size Register */
+ uint32_t RESERVED0[2];
+ __IO uint32_t ACPR; /*!< Offset: 0x010 (R/W) Asynchronous Clock Prescaler Register */
+ uint32_t RESERVED1[55];
+ __IO uint32_t SPPR; /*!< Offset: 0x0F0 (R/W) Selected Pin Protocol Register */
+ uint32_t RESERVED2[131];
+ __I uint32_t FFSR; /*!< Offset: 0x300 (R/ ) Formatter and Flush Status Register */
+ __IO uint32_t FFCR; /*!< Offset: 0x304 (R/W) Formatter and Flush Control Register */
+ __I uint32_t FSCR; /*!< Offset: 0x308 (R/ ) Formatter Synchronization Counter Register */
+ uint32_t RESERVED3[759];
+ __I uint32_t TRIGGER; /*!< Offset: 0xEE8 (R/ ) TRIGGER */
+ __I uint32_t FIFO0; /*!< Offset: 0xEEC (R/ ) Integration ETM Data */
+ __I uint32_t ITATBCTR2; /*!< Offset: 0xEF0 (R/ ) ITATBCTR2 */
+ uint32_t RESERVED4[1];
+ __I uint32_t ITATBCTR0; /*!< Offset: 0xEF8 (R/ ) ITATBCTR0 */
+ __I uint32_t FIFO1; /*!< Offset: 0xEFC (R/ ) Integration ITM Data */
+ __IO uint32_t ITCTRL; /*!< Offset: 0xF00 (R/W) Integration Mode Control */
+ uint32_t RESERVED5[39];
+ __IO uint32_t CLAIMSET; /*!< Offset: 0xFA0 (R/W) Claim tag set */
+ __IO uint32_t CLAIMCLR; /*!< Offset: 0xFA4 (R/W) Claim tag clear */
+ uint32_t RESERVED7[8];
+ __I uint32_t DEVID; /*!< Offset: 0xFC8 (R/ ) TPIU_DEVID */
+ __I uint32_t DEVTYPE; /*!< Offset: 0xFCC (R/ ) TPIU_DEVTYPE */
+} TPI_Type;
+
+/* TPI Asynchronous Clock Prescaler Register Definitions */
+#define TPI_ACPR_PRESCALER_Pos 0 /*!< TPI ACPR: PRESCALER Position */
+#define TPI_ACPR_PRESCALER_Msk (0x1FFFUL << TPI_ACPR_PRESCALER_Pos) /*!< TPI ACPR: PRESCALER Mask */
+
+/* TPI Selected Pin Protocol Register Definitions */
+#define TPI_SPPR_TXMODE_Pos 0 /*!< TPI SPPR: TXMODE Position */
+#define TPI_SPPR_TXMODE_Msk (0x3UL << TPI_SPPR_TXMODE_Pos) /*!< TPI SPPR: TXMODE Mask */
+
+/* TPI Formatter and Flush Status Register Definitions */
+#define TPI_FFSR_FtNonStop_Pos 3 /*!< TPI FFSR: FtNonStop Position */
+#define TPI_FFSR_FtNonStop_Msk (0x1UL << TPI_FFSR_FtNonStop_Pos) /*!< TPI FFSR: FtNonStop Mask */
+
+#define TPI_FFSR_TCPresent_Pos 2 /*!< TPI FFSR: TCPresent Position */
+#define TPI_FFSR_TCPresent_Msk (0x1UL << TPI_FFSR_TCPresent_Pos) /*!< TPI FFSR: TCPresent Mask */
+
+#define TPI_FFSR_FtStopped_Pos 1 /*!< TPI FFSR: FtStopped Position */
+#define TPI_FFSR_FtStopped_Msk (0x1UL << TPI_FFSR_FtStopped_Pos) /*!< TPI FFSR: FtStopped Mask */
+
+#define TPI_FFSR_FlInProg_Pos 0 /*!< TPI FFSR: FlInProg Position */
+#define TPI_FFSR_FlInProg_Msk (0x1UL << TPI_FFSR_FlInProg_Pos) /*!< TPI FFSR: FlInProg Mask */
+
+/* TPI Formatter and Flush Control Register Definitions */
+#define TPI_FFCR_TrigIn_Pos 8 /*!< TPI FFCR: TrigIn Position */
+#define TPI_FFCR_TrigIn_Msk (0x1UL << TPI_FFCR_TrigIn_Pos) /*!< TPI FFCR: TrigIn Mask */
+
+#define TPI_FFCR_EnFCont_Pos 1 /*!< TPI FFCR: EnFCont Position */
+#define TPI_FFCR_EnFCont_Msk (0x1UL << TPI_FFCR_EnFCont_Pos) /*!< TPI FFCR: EnFCont Mask */
+
+/* TPI TRIGGER Register Definitions */
+#define TPI_TRIGGER_TRIGGER_Pos 0 /*!< TPI TRIGGER: TRIGGER Position */
+#define TPI_TRIGGER_TRIGGER_Msk (0x1UL << TPI_TRIGGER_TRIGGER_Pos) /*!< TPI TRIGGER: TRIGGER Mask */
+
+/* TPI Integration ETM Data Register Definitions (FIFO0) */
+#define TPI_FIFO0_ITM_ATVALID_Pos 29 /*!< TPI FIFO0: ITM_ATVALID Position */
+#define TPI_FIFO0_ITM_ATVALID_Msk (0x3UL << TPI_FIFO0_ITM_ATVALID_Pos) /*!< TPI FIFO0: ITM_ATVALID Mask */
+
+#define TPI_FIFO0_ITM_bytecount_Pos 27 /*!< TPI FIFO0: ITM_bytecount Position */
+#define TPI_FIFO0_ITM_bytecount_Msk (0x3UL << TPI_FIFO0_ITM_bytecount_Pos) /*!< TPI FIFO0: ITM_bytecount Mask */
+
+#define TPI_FIFO0_ETM_ATVALID_Pos 26 /*!< TPI FIFO0: ETM_ATVALID Position */
+#define TPI_FIFO0_ETM_ATVALID_Msk (0x3UL << TPI_FIFO0_ETM_ATVALID_Pos) /*!< TPI FIFO0: ETM_ATVALID Mask */
+
+#define TPI_FIFO0_ETM_bytecount_Pos 24 /*!< TPI FIFO0: ETM_bytecount Position */
+#define TPI_FIFO0_ETM_bytecount_Msk (0x3UL << TPI_FIFO0_ETM_bytecount_Pos) /*!< TPI FIFO0: ETM_bytecount Mask */
+
+#define TPI_FIFO0_ETM2_Pos 16 /*!< TPI FIFO0: ETM2 Position */
+#define TPI_FIFO0_ETM2_Msk (0xFFUL << TPI_FIFO0_ETM2_Pos) /*!< TPI FIFO0: ETM2 Mask */
+
+#define TPI_FIFO0_ETM1_Pos 8 /*!< TPI FIFO0: ETM1 Position */
+#define TPI_FIFO0_ETM1_Msk (0xFFUL << TPI_FIFO0_ETM1_Pos) /*!< TPI FIFO0: ETM1 Mask */
+
+#define TPI_FIFO0_ETM0_Pos 0 /*!< TPI FIFO0: ETM0 Position */
+#define TPI_FIFO0_ETM0_Msk (0xFFUL << TPI_FIFO0_ETM0_Pos) /*!< TPI FIFO0: ETM0 Mask */
+
+/* TPI ITATBCTR2 Register Definitions */
+#define TPI_ITATBCTR2_ATREADY_Pos 0 /*!< TPI ITATBCTR2: ATREADY Position */
+#define TPI_ITATBCTR2_ATREADY_Msk (0x1UL << TPI_ITATBCTR2_ATREADY_Pos) /*!< TPI ITATBCTR2: ATREADY Mask */
+
+/* TPI Integration ITM Data Register Definitions (FIFO1) */
+#define TPI_FIFO1_ITM_ATVALID_Pos 29 /*!< TPI FIFO1: ITM_ATVALID Position */
+#define TPI_FIFO1_ITM_ATVALID_Msk (0x3UL << TPI_FIFO1_ITM_ATVALID_Pos) /*!< TPI FIFO1: ITM_ATVALID Mask */
+
+#define TPI_FIFO1_ITM_bytecount_Pos 27 /*!< TPI FIFO1: ITM_bytecount Position */
+#define TPI_FIFO1_ITM_bytecount_Msk (0x3UL << TPI_FIFO1_ITM_bytecount_Pos) /*!< TPI FIFO1: ITM_bytecount Mask */
+
+#define TPI_FIFO1_ETM_ATVALID_Pos 26 /*!< TPI FIFO1: ETM_ATVALID Position */
+#define TPI_FIFO1_ETM_ATVALID_Msk (0x3UL << TPI_FIFO1_ETM_ATVALID_Pos) /*!< TPI FIFO1: ETM_ATVALID Mask */
+
+#define TPI_FIFO1_ETM_bytecount_Pos 24 /*!< TPI FIFO1: ETM_bytecount Position */
+#define TPI_FIFO1_ETM_bytecount_Msk (0x3UL << TPI_FIFO1_ETM_bytecount_Pos) /*!< TPI FIFO1: ETM_bytecount Mask */
+
+#define TPI_FIFO1_ITM2_Pos 16 /*!< TPI FIFO1: ITM2 Position */
+#define TPI_FIFO1_ITM2_Msk (0xFFUL << TPI_FIFO1_ITM2_Pos) /*!< TPI FIFO1: ITM2 Mask */
+
+#define TPI_FIFO1_ITM1_Pos 8 /*!< TPI FIFO1: ITM1 Position */
+#define TPI_FIFO1_ITM1_Msk (0xFFUL << TPI_FIFO1_ITM1_Pos) /*!< TPI FIFO1: ITM1 Mask */
+
+#define TPI_FIFO1_ITM0_Pos 0 /*!< TPI FIFO1: ITM0 Position */
+#define TPI_FIFO1_ITM0_Msk (0xFFUL << TPI_FIFO1_ITM0_Pos) /*!< TPI FIFO1: ITM0 Mask */
+
+/* TPI ITATBCTR0 Register Definitions */
+#define TPI_ITATBCTR0_ATREADY_Pos 0 /*!< TPI ITATBCTR0: ATREADY Position */
+#define TPI_ITATBCTR0_ATREADY_Msk (0x1UL << TPI_ITATBCTR0_ATREADY_Pos) /*!< TPI ITATBCTR0: ATREADY Mask */
+
+/* TPI Integration Mode Control Register Definitions */
+#define TPI_ITCTRL_Mode_Pos 0 /*!< TPI ITCTRL: Mode Position */
+#define TPI_ITCTRL_Mode_Msk (0x1UL << TPI_ITCTRL_Mode_Pos) /*!< TPI ITCTRL: Mode Mask */
+
+/* TPI DEVID Register Definitions */
+#define TPI_DEVID_NRZVALID_Pos 11 /*!< TPI DEVID: NRZVALID Position */
+#define TPI_DEVID_NRZVALID_Msk (0x1UL << TPI_DEVID_NRZVALID_Pos) /*!< TPI DEVID: NRZVALID Mask */
+
+#define TPI_DEVID_MANCVALID_Pos 10 /*!< TPI DEVID: MANCVALID Position */
+#define TPI_DEVID_MANCVALID_Msk (0x1UL << TPI_DEVID_MANCVALID_Pos) /*!< TPI DEVID: MANCVALID Mask */
+
+#define TPI_DEVID_PTINVALID_Pos 9 /*!< TPI DEVID: PTINVALID Position */
+#define TPI_DEVID_PTINVALID_Msk (0x1UL << TPI_DEVID_PTINVALID_Pos) /*!< TPI DEVID: PTINVALID Mask */
+
+#define TPI_DEVID_MinBufSz_Pos 6 /*!< TPI DEVID: MinBufSz Position */
+#define TPI_DEVID_MinBufSz_Msk (0x7UL << TPI_DEVID_MinBufSz_Pos) /*!< TPI DEVID: MinBufSz Mask */
+
+#define TPI_DEVID_AsynClkIn_Pos 5 /*!< TPI DEVID: AsynClkIn Position */
+#define TPI_DEVID_AsynClkIn_Msk (0x1UL << TPI_DEVID_AsynClkIn_Pos) /*!< TPI DEVID: AsynClkIn Mask */
+
+#define TPI_DEVID_NrTraceInput_Pos 0 /*!< TPI DEVID: NrTraceInput Position */
+#define TPI_DEVID_NrTraceInput_Msk (0x1FUL << TPI_DEVID_NrTraceInput_Pos) /*!< TPI DEVID: NrTraceInput Mask */
+
+/* TPI DEVTYPE Register Definitions */
+#define TPI_DEVTYPE_SubType_Pos 0 /*!< TPI DEVTYPE: SubType Position */
+#define TPI_DEVTYPE_SubType_Msk (0xFUL << TPI_DEVTYPE_SubType_Pos) /*!< TPI DEVTYPE: SubType Mask */
+
+#define TPI_DEVTYPE_MajorType_Pos 4 /*!< TPI DEVTYPE: MajorType Position */
+#define TPI_DEVTYPE_MajorType_Msk (0xFUL << TPI_DEVTYPE_MajorType_Pos) /*!< TPI DEVTYPE: MajorType Mask */
+
+/*@}*/ /* end of group CMSIS_TPI */
+
+
+#if (__MPU_PRESENT == 1)
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_MPU Memory Protection Unit (MPU)
+ \brief Type definitions for the Memory Protection Unit (MPU)
+ @{
+ */
+
+/** \brief Structure type to access the Memory Protection Unit (MPU).
+ */
+typedef struct
+{
+ __I uint32_t TYPE; /*!< Offset: 0x000 (R/ ) MPU Type Register */
+ __IO uint32_t CTRL; /*!< Offset: 0x004 (R/W) MPU Control Register */
+ __IO uint32_t RNR; /*!< Offset: 0x008 (R/W) MPU Region RNRber Register */
+ __IO uint32_t RBAR; /*!< Offset: 0x00C (R/W) MPU Region Base Address Register */
+ __IO uint32_t RASR; /*!< Offset: 0x010 (R/W) MPU Region Attribute and Size Register */
+ __IO uint32_t RBAR_A1; /*!< Offset: 0x014 (R/W) MPU Alias 1 Region Base Address Register */
+ __IO uint32_t RASR_A1; /*!< Offset: 0x018 (R/W) MPU Alias 1 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A2; /*!< Offset: 0x01C (R/W) MPU Alias 2 Region Base Address Register */
+ __IO uint32_t RASR_A2; /*!< Offset: 0x020 (R/W) MPU Alias 2 Region Attribute and Size Register */
+ __IO uint32_t RBAR_A3; /*!< Offset: 0x024 (R/W) MPU Alias 3 Region Base Address Register */
+ __IO uint32_t RASR_A3; /*!< Offset: 0x028 (R/W) MPU Alias 3 Region Attribute and Size Register */
+} MPU_Type;
+
+/* MPU Type Register */
+#define MPU_TYPE_IREGION_Pos 16 /*!< MPU TYPE: IREGION Position */
+#define MPU_TYPE_IREGION_Msk (0xFFUL << MPU_TYPE_IREGION_Pos) /*!< MPU TYPE: IREGION Mask */
+
+#define MPU_TYPE_DREGION_Pos 8 /*!< MPU TYPE: DREGION Position */
+#define MPU_TYPE_DREGION_Msk (0xFFUL << MPU_TYPE_DREGION_Pos) /*!< MPU TYPE: DREGION Mask */
+
+#define MPU_TYPE_SEPARATE_Pos 0 /*!< MPU TYPE: SEPARATE Position */
+#define MPU_TYPE_SEPARATE_Msk (1UL << MPU_TYPE_SEPARATE_Pos) /*!< MPU TYPE: SEPARATE Mask */
+
+/* MPU Control Register */
+#define MPU_CTRL_PRIVDEFENA_Pos 2 /*!< MPU CTRL: PRIVDEFENA Position */
+#define MPU_CTRL_PRIVDEFENA_Msk (1UL << MPU_CTRL_PRIVDEFENA_Pos) /*!< MPU CTRL: PRIVDEFENA Mask */
+
+#define MPU_CTRL_HFNMIENA_Pos 1 /*!< MPU CTRL: HFNMIENA Position */
+#define MPU_CTRL_HFNMIENA_Msk (1UL << MPU_CTRL_HFNMIENA_Pos) /*!< MPU CTRL: HFNMIENA Mask */
+
+#define MPU_CTRL_ENABLE_Pos 0 /*!< MPU CTRL: ENABLE Position */
+#define MPU_CTRL_ENABLE_Msk (1UL << MPU_CTRL_ENABLE_Pos) /*!< MPU CTRL: ENABLE Mask */
+
+/* MPU Region Number Register */
+#define MPU_RNR_REGION_Pos 0 /*!< MPU RNR: REGION Position */
+#define MPU_RNR_REGION_Msk (0xFFUL << MPU_RNR_REGION_Pos) /*!< MPU RNR: REGION Mask */
+
+/* MPU Region Base Address Register */
+#define MPU_RBAR_ADDR_Pos 5 /*!< MPU RBAR: ADDR Position */
+#define MPU_RBAR_ADDR_Msk (0x7FFFFFFUL << MPU_RBAR_ADDR_Pos) /*!< MPU RBAR: ADDR Mask */
+
+#define MPU_RBAR_VALID_Pos 4 /*!< MPU RBAR: VALID Position */
+#define MPU_RBAR_VALID_Msk (1UL << MPU_RBAR_VALID_Pos) /*!< MPU RBAR: VALID Mask */
+
+#define MPU_RBAR_REGION_Pos 0 /*!< MPU RBAR: REGION Position */
+#define MPU_RBAR_REGION_Msk (0xFUL << MPU_RBAR_REGION_Pos) /*!< MPU RBAR: REGION Mask */
+
+/* MPU Region Attribute and Size Register */
+#define MPU_RASR_ATTRS_Pos 16 /*!< MPU RASR: MPU Region Attribute field Position */
+#define MPU_RASR_ATTRS_Msk (0xFFFFUL << MPU_RASR_ATTRS_Pos) /*!< MPU RASR: MPU Region Attribute field Mask */
+
+#define MPU_RASR_XN_Pos 28 /*!< MPU RASR: ATTRS.XN Position */
+#define MPU_RASR_XN_Msk (1UL << MPU_RASR_XN_Pos) /*!< MPU RASR: ATTRS.XN Mask */
+
+#define MPU_RASR_AP_Pos 24 /*!< MPU RASR: ATTRS.AP Position */
+#define MPU_RASR_AP_Msk (0x7UL << MPU_RASR_AP_Pos) /*!< MPU RASR: ATTRS.AP Mask */
+
+#define MPU_RASR_TEX_Pos 19 /*!< MPU RASR: ATTRS.TEX Position */
+#define MPU_RASR_TEX_Msk (0x7UL << MPU_RASR_TEX_Pos) /*!< MPU RASR: ATTRS.TEX Mask */
+
+#define MPU_RASR_S_Pos 18 /*!< MPU RASR: ATTRS.S Position */
+#define MPU_RASR_S_Msk (1UL << MPU_RASR_S_Pos) /*!< MPU RASR: ATTRS.S Mask */
+
+#define MPU_RASR_C_Pos 17 /*!< MPU RASR: ATTRS.C Position */
+#define MPU_RASR_C_Msk (1UL << MPU_RASR_C_Pos) /*!< MPU RASR: ATTRS.C Mask */
+
+#define MPU_RASR_B_Pos 16 /*!< MPU RASR: ATTRS.B Position */
+#define MPU_RASR_B_Msk (1UL << MPU_RASR_B_Pos) /*!< MPU RASR: ATTRS.B Mask */
+
+#define MPU_RASR_SRD_Pos 8 /*!< MPU RASR: Sub-Region Disable Position */
+#define MPU_RASR_SRD_Msk (0xFFUL << MPU_RASR_SRD_Pos) /*!< MPU RASR: Sub-Region Disable Mask */
+
+#define MPU_RASR_SIZE_Pos 1 /*!< MPU RASR: Region Size Field Position */
+#define MPU_RASR_SIZE_Msk (0x1FUL << MPU_RASR_SIZE_Pos) /*!< MPU RASR: Region Size Field Mask */
+
+#define MPU_RASR_ENABLE_Pos 0 /*!< MPU RASR: Region enable bit Position */
+#define MPU_RASR_ENABLE_Msk (1UL << MPU_RASR_ENABLE_Pos) /*!< MPU RASR: Region enable bit Disable Mask */
+
+/*@} end of group CMSIS_MPU */
+#endif
+
+
+#if (__FPU_PRESENT == 1)
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_FPU Floating Point Unit (FPU)
+ \brief Type definitions for the Floating Point Unit (FPU)
+ @{
+ */
+
+/** \brief Structure type to access the Floating Point Unit (FPU).
+ */
+typedef struct
+{
+ uint32_t RESERVED0[1];
+ __IO uint32_t FPCCR; /*!< Offset: 0x004 (R/W) Floating-Point Context Control Register */
+ __IO uint32_t FPCAR; /*!< Offset: 0x008 (R/W) Floating-Point Context Address Register */
+ __IO uint32_t FPDSCR; /*!< Offset: 0x00C (R/W) Floating-Point Default Status Control Register */
+ __I uint32_t MVFR0; /*!< Offset: 0x010 (R/ ) Media and FP Feature Register 0 */
+ __I uint32_t MVFR1; /*!< Offset: 0x014 (R/ ) Media and FP Feature Register 1 */
+} FPU_Type;
+
+/* Floating-Point Context Control Register */
+#define FPU_FPCCR_ASPEN_Pos 31 /*!< FPCCR: ASPEN bit Position */
+#define FPU_FPCCR_ASPEN_Msk (1UL << FPU_FPCCR_ASPEN_Pos) /*!< FPCCR: ASPEN bit Mask */
+
+#define FPU_FPCCR_LSPEN_Pos 30 /*!< FPCCR: LSPEN Position */
+#define FPU_FPCCR_LSPEN_Msk (1UL << FPU_FPCCR_LSPEN_Pos) /*!< FPCCR: LSPEN bit Mask */
+
+#define FPU_FPCCR_MONRDY_Pos 8 /*!< FPCCR: MONRDY Position */
+#define FPU_FPCCR_MONRDY_Msk (1UL << FPU_FPCCR_MONRDY_Pos) /*!< FPCCR: MONRDY bit Mask */
+
+#define FPU_FPCCR_BFRDY_Pos 6 /*!< FPCCR: BFRDY Position */
+#define FPU_FPCCR_BFRDY_Msk (1UL << FPU_FPCCR_BFRDY_Pos) /*!< FPCCR: BFRDY bit Mask */
+
+#define FPU_FPCCR_MMRDY_Pos 5 /*!< FPCCR: MMRDY Position */
+#define FPU_FPCCR_MMRDY_Msk (1UL << FPU_FPCCR_MMRDY_Pos) /*!< FPCCR: MMRDY bit Mask */
+
+#define FPU_FPCCR_HFRDY_Pos 4 /*!< FPCCR: HFRDY Position */
+#define FPU_FPCCR_HFRDY_Msk (1UL << FPU_FPCCR_HFRDY_Pos) /*!< FPCCR: HFRDY bit Mask */
+
+#define FPU_FPCCR_THREAD_Pos 3 /*!< FPCCR: processor mode bit Position */
+#define FPU_FPCCR_THREAD_Msk (1UL << FPU_FPCCR_THREAD_Pos) /*!< FPCCR: processor mode active bit Mask */
+
+#define FPU_FPCCR_USER_Pos 1 /*!< FPCCR: privilege level bit Position */
+#define FPU_FPCCR_USER_Msk (1UL << FPU_FPCCR_USER_Pos) /*!< FPCCR: privilege level bit Mask */
+
+#define FPU_FPCCR_LSPACT_Pos 0 /*!< FPCCR: Lazy state preservation active bit Position */
+#define FPU_FPCCR_LSPACT_Msk (1UL << FPU_FPCCR_LSPACT_Pos) /*!< FPCCR: Lazy state preservation active bit Mask */
+
+/* Floating-Point Context Address Register */
+#define FPU_FPCAR_ADDRESS_Pos 3 /*!< FPCAR: ADDRESS bit Position */
+#define FPU_FPCAR_ADDRESS_Msk (0x1FFFFFFFUL << FPU_FPCAR_ADDRESS_Pos) /*!< FPCAR: ADDRESS bit Mask */
+
+/* Floating-Point Default Status Control Register */
+#define FPU_FPDSCR_AHP_Pos 26 /*!< FPDSCR: AHP bit Position */
+#define FPU_FPDSCR_AHP_Msk (1UL << FPU_FPDSCR_AHP_Pos) /*!< FPDSCR: AHP bit Mask */
+
+#define FPU_FPDSCR_DN_Pos 25 /*!< FPDSCR: DN bit Position */
+#define FPU_FPDSCR_DN_Msk (1UL << FPU_FPDSCR_DN_Pos) /*!< FPDSCR: DN bit Mask */
+
+#define FPU_FPDSCR_FZ_Pos 24 /*!< FPDSCR: FZ bit Position */
+#define FPU_FPDSCR_FZ_Msk (1UL << FPU_FPDSCR_FZ_Pos) /*!< FPDSCR: FZ bit Mask */
+
+#define FPU_FPDSCR_RMode_Pos 22 /*!< FPDSCR: RMode bit Position */
+#define FPU_FPDSCR_RMode_Msk (3UL << FPU_FPDSCR_RMode_Pos) /*!< FPDSCR: RMode bit Mask */
+
+/* Media and FP Feature Register 0 */
+#define FPU_MVFR0_FP_rounding_modes_Pos 28 /*!< MVFR0: FP rounding modes bits Position */
+#define FPU_MVFR0_FP_rounding_modes_Msk (0xFUL << FPU_MVFR0_FP_rounding_modes_Pos) /*!< MVFR0: FP rounding modes bits Mask */
+
+#define FPU_MVFR0_Short_vectors_Pos 24 /*!< MVFR0: Short vectors bits Position */
+#define FPU_MVFR0_Short_vectors_Msk (0xFUL << FPU_MVFR0_Short_vectors_Pos) /*!< MVFR0: Short vectors bits Mask */
+
+#define FPU_MVFR0_Square_root_Pos 20 /*!< MVFR0: Square root bits Position */
+#define FPU_MVFR0_Square_root_Msk (0xFUL << FPU_MVFR0_Square_root_Pos) /*!< MVFR0: Square root bits Mask */
+
+#define FPU_MVFR0_Divide_Pos 16 /*!< MVFR0: Divide bits Position */
+#define FPU_MVFR0_Divide_Msk (0xFUL << FPU_MVFR0_Divide_Pos) /*!< MVFR0: Divide bits Mask */
+
+#define FPU_MVFR0_FP_excep_trapping_Pos 12 /*!< MVFR0: FP exception trapping bits Position */
+#define FPU_MVFR0_FP_excep_trapping_Msk (0xFUL << FPU_MVFR0_FP_excep_trapping_Pos) /*!< MVFR0: FP exception trapping bits Mask */
+
+#define FPU_MVFR0_Double_precision_Pos 8 /*!< MVFR0: Double-precision bits Position */
+#define FPU_MVFR0_Double_precision_Msk (0xFUL << FPU_MVFR0_Double_precision_Pos) /*!< MVFR0: Double-precision bits Mask */
+
+#define FPU_MVFR0_Single_precision_Pos 4 /*!< MVFR0: Single-precision bits Position */
+#define FPU_MVFR0_Single_precision_Msk (0xFUL << FPU_MVFR0_Single_precision_Pos) /*!< MVFR0: Single-precision bits Mask */
+
+#define FPU_MVFR0_A_SIMD_registers_Pos 0 /*!< MVFR0: A_SIMD registers bits Position */
+#define FPU_MVFR0_A_SIMD_registers_Msk (0xFUL << FPU_MVFR0_A_SIMD_registers_Pos) /*!< MVFR0: A_SIMD registers bits Mask */
+
+/* Media and FP Feature Register 1 */
+#define FPU_MVFR1_FP_fused_MAC_Pos 28 /*!< MVFR1: FP fused MAC bits Position */
+#define FPU_MVFR1_FP_fused_MAC_Msk (0xFUL << FPU_MVFR1_FP_fused_MAC_Pos) /*!< MVFR1: FP fused MAC bits Mask */
+
+#define FPU_MVFR1_FP_HPFP_Pos 24 /*!< MVFR1: FP HPFP bits Position */
+#define FPU_MVFR1_FP_HPFP_Msk (0xFUL << FPU_MVFR1_FP_HPFP_Pos) /*!< MVFR1: FP HPFP bits Mask */
+
+#define FPU_MVFR1_D_NaN_mode_Pos 4 /*!< MVFR1: D_NaN mode bits Position */
+#define FPU_MVFR1_D_NaN_mode_Msk (0xFUL << FPU_MVFR1_D_NaN_mode_Pos) /*!< MVFR1: D_NaN mode bits Mask */
+
+#define FPU_MVFR1_FtZ_mode_Pos 0 /*!< MVFR1: FtZ mode bits Position */
+#define FPU_MVFR1_FtZ_mode_Msk (0xFUL << FPU_MVFR1_FtZ_mode_Pos) /*!< MVFR1: FtZ mode bits Mask */
+
+/*@} end of group CMSIS_FPU */
+#endif
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_CoreDebug Core Debug Registers (CoreDebug)
+ \brief Type definitions for the Core Debug Registers
+ @{
+ */
+
+/** \brief Structure type to access the Core Debug Register (CoreDebug).
+ */
+typedef struct
+{
+ __IO uint32_t DHCSR; /*!< Offset: 0x000 (R/W) Debug Halting Control and Status Register */
+ __O uint32_t DCRSR; /*!< Offset: 0x004 ( /W) Debug Core Register Selector Register */
+ __IO uint32_t DCRDR; /*!< Offset: 0x008 (R/W) Debug Core Register Data Register */
+ __IO uint32_t DEMCR; /*!< Offset: 0x00C (R/W) Debug Exception and Monitor Control Register */
+} CoreDebug_Type;
+
+/* Debug Halting Control and Status Register */
+#define CoreDebug_DHCSR_DBGKEY_Pos 16 /*!< CoreDebug DHCSR: DBGKEY Position */
+#define CoreDebug_DHCSR_DBGKEY_Msk (0xFFFFUL << CoreDebug_DHCSR_DBGKEY_Pos) /*!< CoreDebug DHCSR: DBGKEY Mask */
+
+#define CoreDebug_DHCSR_S_RESET_ST_Pos 25 /*!< CoreDebug DHCSR: S_RESET_ST Position */
+#define CoreDebug_DHCSR_S_RESET_ST_Msk (1UL << CoreDebug_DHCSR_S_RESET_ST_Pos) /*!< CoreDebug DHCSR: S_RESET_ST Mask */
+
+#define CoreDebug_DHCSR_S_RETIRE_ST_Pos 24 /*!< CoreDebug DHCSR: S_RETIRE_ST Position */
+#define CoreDebug_DHCSR_S_RETIRE_ST_Msk (1UL << CoreDebug_DHCSR_S_RETIRE_ST_Pos) /*!< CoreDebug DHCSR: S_RETIRE_ST Mask */
+
+#define CoreDebug_DHCSR_S_LOCKUP_Pos 19 /*!< CoreDebug DHCSR: S_LOCKUP Position */
+#define CoreDebug_DHCSR_S_LOCKUP_Msk (1UL << CoreDebug_DHCSR_S_LOCKUP_Pos) /*!< CoreDebug DHCSR: S_LOCKUP Mask */
+
+#define CoreDebug_DHCSR_S_SLEEP_Pos 18 /*!< CoreDebug DHCSR: S_SLEEP Position */
+#define CoreDebug_DHCSR_S_SLEEP_Msk (1UL << CoreDebug_DHCSR_S_SLEEP_Pos) /*!< CoreDebug DHCSR: S_SLEEP Mask */
+
+#define CoreDebug_DHCSR_S_HALT_Pos 17 /*!< CoreDebug DHCSR: S_HALT Position */
+#define CoreDebug_DHCSR_S_HALT_Msk (1UL << CoreDebug_DHCSR_S_HALT_Pos) /*!< CoreDebug DHCSR: S_HALT Mask */
+
+#define CoreDebug_DHCSR_S_REGRDY_Pos 16 /*!< CoreDebug DHCSR: S_REGRDY Position */
+#define CoreDebug_DHCSR_S_REGRDY_Msk (1UL << CoreDebug_DHCSR_S_REGRDY_Pos) /*!< CoreDebug DHCSR: S_REGRDY Mask */
+
+#define CoreDebug_DHCSR_C_SNAPSTALL_Pos 5 /*!< CoreDebug DHCSR: C_SNAPSTALL Position */
+#define CoreDebug_DHCSR_C_SNAPSTALL_Msk (1UL << CoreDebug_DHCSR_C_SNAPSTALL_Pos) /*!< CoreDebug DHCSR: C_SNAPSTALL Mask */
+
+#define CoreDebug_DHCSR_C_MASKINTS_Pos 3 /*!< CoreDebug DHCSR: C_MASKINTS Position */
+#define CoreDebug_DHCSR_C_MASKINTS_Msk (1UL << CoreDebug_DHCSR_C_MASKINTS_Pos) /*!< CoreDebug DHCSR: C_MASKINTS Mask */
+
+#define CoreDebug_DHCSR_C_STEP_Pos 2 /*!< CoreDebug DHCSR: C_STEP Position */
+#define CoreDebug_DHCSR_C_STEP_Msk (1UL << CoreDebug_DHCSR_C_STEP_Pos) /*!< CoreDebug DHCSR: C_STEP Mask */
+
+#define CoreDebug_DHCSR_C_HALT_Pos 1 /*!< CoreDebug DHCSR: C_HALT Position */
+#define CoreDebug_DHCSR_C_HALT_Msk (1UL << CoreDebug_DHCSR_C_HALT_Pos) /*!< CoreDebug DHCSR: C_HALT Mask */
+
+#define CoreDebug_DHCSR_C_DEBUGEN_Pos 0 /*!< CoreDebug DHCSR: C_DEBUGEN Position */
+#define CoreDebug_DHCSR_C_DEBUGEN_Msk (1UL << CoreDebug_DHCSR_C_DEBUGEN_Pos) /*!< CoreDebug DHCSR: C_DEBUGEN Mask */
+
+/* Debug Core Register Selector Register */
+#define CoreDebug_DCRSR_REGWnR_Pos 16 /*!< CoreDebug DCRSR: REGWnR Position */
+#define CoreDebug_DCRSR_REGWnR_Msk (1UL << CoreDebug_DCRSR_REGWnR_Pos) /*!< CoreDebug DCRSR: REGWnR Mask */
+
+#define CoreDebug_DCRSR_REGSEL_Pos 0 /*!< CoreDebug DCRSR: REGSEL Position */
+#define CoreDebug_DCRSR_REGSEL_Msk (0x1FUL << CoreDebug_DCRSR_REGSEL_Pos) /*!< CoreDebug DCRSR: REGSEL Mask */
+
+/* Debug Exception and Monitor Control Register */
+#define CoreDebug_DEMCR_TRCENA_Pos 24 /*!< CoreDebug DEMCR: TRCENA Position */
+#define CoreDebug_DEMCR_TRCENA_Msk (1UL << CoreDebug_DEMCR_TRCENA_Pos) /*!< CoreDebug DEMCR: TRCENA Mask */
+
+#define CoreDebug_DEMCR_MON_REQ_Pos 19 /*!< CoreDebug DEMCR: MON_REQ Position */
+#define CoreDebug_DEMCR_MON_REQ_Msk (1UL << CoreDebug_DEMCR_MON_REQ_Pos) /*!< CoreDebug DEMCR: MON_REQ Mask */
+
+#define CoreDebug_DEMCR_MON_STEP_Pos 18 /*!< CoreDebug DEMCR: MON_STEP Position */
+#define CoreDebug_DEMCR_MON_STEP_Msk (1UL << CoreDebug_DEMCR_MON_STEP_Pos) /*!< CoreDebug DEMCR: MON_STEP Mask */
+
+#define CoreDebug_DEMCR_MON_PEND_Pos 17 /*!< CoreDebug DEMCR: MON_PEND Position */
+#define CoreDebug_DEMCR_MON_PEND_Msk (1UL << CoreDebug_DEMCR_MON_PEND_Pos) /*!< CoreDebug DEMCR: MON_PEND Mask */
+
+#define CoreDebug_DEMCR_MON_EN_Pos 16 /*!< CoreDebug DEMCR: MON_EN Position */
+#define CoreDebug_DEMCR_MON_EN_Msk (1UL << CoreDebug_DEMCR_MON_EN_Pos) /*!< CoreDebug DEMCR: MON_EN Mask */
+
+#define CoreDebug_DEMCR_VC_HARDERR_Pos 10 /*!< CoreDebug DEMCR: VC_HARDERR Position */
+#define CoreDebug_DEMCR_VC_HARDERR_Msk (1UL << CoreDebug_DEMCR_VC_HARDERR_Pos) /*!< CoreDebug DEMCR: VC_HARDERR Mask */
+
+#define CoreDebug_DEMCR_VC_INTERR_Pos 9 /*!< CoreDebug DEMCR: VC_INTERR Position */
+#define CoreDebug_DEMCR_VC_INTERR_Msk (1UL << CoreDebug_DEMCR_VC_INTERR_Pos) /*!< CoreDebug DEMCR: VC_INTERR Mask */
+
+#define CoreDebug_DEMCR_VC_BUSERR_Pos 8 /*!< CoreDebug DEMCR: VC_BUSERR Position */
+#define CoreDebug_DEMCR_VC_BUSERR_Msk (1UL << CoreDebug_DEMCR_VC_BUSERR_Pos) /*!< CoreDebug DEMCR: VC_BUSERR Mask */
+
+#define CoreDebug_DEMCR_VC_STATERR_Pos 7 /*!< CoreDebug DEMCR: VC_STATERR Position */
+#define CoreDebug_DEMCR_VC_STATERR_Msk (1UL << CoreDebug_DEMCR_VC_STATERR_Pos) /*!< CoreDebug DEMCR: VC_STATERR Mask */
+
+#define CoreDebug_DEMCR_VC_CHKERR_Pos 6 /*!< CoreDebug DEMCR: VC_CHKERR Position */
+#define CoreDebug_DEMCR_VC_CHKERR_Msk (1UL << CoreDebug_DEMCR_VC_CHKERR_Pos) /*!< CoreDebug DEMCR: VC_CHKERR Mask */
+
+#define CoreDebug_DEMCR_VC_NOCPERR_Pos 5 /*!< CoreDebug DEMCR: VC_NOCPERR Position */
+#define CoreDebug_DEMCR_VC_NOCPERR_Msk (1UL << CoreDebug_DEMCR_VC_NOCPERR_Pos) /*!< CoreDebug DEMCR: VC_NOCPERR Mask */
+
+#define CoreDebug_DEMCR_VC_MMERR_Pos 4 /*!< CoreDebug DEMCR: VC_MMERR Position */
+#define CoreDebug_DEMCR_VC_MMERR_Msk (1UL << CoreDebug_DEMCR_VC_MMERR_Pos) /*!< CoreDebug DEMCR: VC_MMERR Mask */
+
+#define CoreDebug_DEMCR_VC_CORERESET_Pos 0 /*!< CoreDebug DEMCR: VC_CORERESET Position */
+#define CoreDebug_DEMCR_VC_CORERESET_Msk (1UL << CoreDebug_DEMCR_VC_CORERESET_Pos) /*!< CoreDebug DEMCR: VC_CORERESET Mask */
+
+/*@} end of group CMSIS_CoreDebug */
+
+
+/** \ingroup CMSIS_core_register
+ \defgroup CMSIS_core_base Core Definitions
+ \brief Definitions for base addresses, unions, and structures.
+ @{
+ */
+
+/* Memory mapping of Cortex-M4 Hardware */
+#define SCS_BASE (0xE000E000UL) /*!< System Control Space Base Address */
+#define ITM_BASE (0xE0000000UL) /*!< ITM Base Address */
+#define DWT_BASE (0xE0001000UL) /*!< DWT Base Address */
+#define TPI_BASE (0xE0040000UL) /*!< TPI Base Address */
+#define CoreDebug_BASE (0xE000EDF0UL) /*!< Core Debug Base Address */
+#define SysTick_BASE (SCS_BASE + 0x0010UL) /*!< SysTick Base Address */
+#define NVIC_BASE (SCS_BASE + 0x0100UL) /*!< NVIC Base Address */
+#define SCB_BASE (SCS_BASE + 0x0D00UL) /*!< System Control Block Base Address */
+
+#define SCnSCB ((SCnSCB_Type *) SCS_BASE ) /*!< System control Register not in SCB */
+#define SCB ((SCB_Type *) SCB_BASE ) /*!< SCB configuration struct */
+#define SysTick ((SysTick_Type *) SysTick_BASE ) /*!< SysTick configuration struct */
+#define NVIC ((NVIC_Type *) NVIC_BASE ) /*!< NVIC configuration struct */
+#define ITM ((ITM_Type *) ITM_BASE ) /*!< ITM configuration struct */
+#define DWT ((DWT_Type *) DWT_BASE ) /*!< DWT configuration struct */
+#define TPI ((TPI_Type *) TPI_BASE ) /*!< TPI configuration struct */
+#define CoreDebug ((CoreDebug_Type *) CoreDebug_BASE) /*!< Core Debug configuration struct */
+
+#if (__MPU_PRESENT == 1)
+ #define MPU_BASE (SCS_BASE + 0x0D90UL) /*!< Memory Protection Unit */
+ #define MPU ((MPU_Type *) MPU_BASE ) /*!< Memory Protection Unit */
+#endif
+
+#if (__FPU_PRESENT == 1)
+ #define FPU_BASE (SCS_BASE + 0x0F30UL) /*!< Floating Point Unit */
+ #define FPU ((FPU_Type *) FPU_BASE ) /*!< Floating Point Unit */
+#endif
+
+/*@} */
+
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ Core Function Interface contains:
+ - Core NVIC Functions
+ - Core SysTick Functions
+ - Core Debug Functions
+ - Core Register Access Functions
+ ******************************************************************************/
+/** \defgroup CMSIS_Core_FunctionInterface Functions and Instructions Reference
+*/
+
+
+
+/* ########################## NVIC functions #################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_NVICFunctions NVIC Functions
+ \brief Functions that manage interrupts and exceptions via the NVIC.
+ @{
+ */
+
+/** \brief Set Priority Grouping
+
+ The function sets the priority grouping field using the required unlock sequence.
+ The parameter PriorityGroup is assigned to the field SCB->AIRCR [10:8] PRIGROUP field.
+ Only values from 0..7 are used.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the smallest possible priority group is set.
+
+ \param [in] PriorityGroup Priority grouping field.
+ */
+__STATIC_INLINE void NVIC_SetPriorityGrouping(uint32_t PriorityGroup)
+{
+ uint32_t reg_value;
+ uint32_t PriorityGroupTmp = (PriorityGroup & (uint32_t)0x07); /* only values 0..7 are used */
+
+ reg_value = SCB->AIRCR; /* read old register configuration */
+ reg_value &= ~(SCB_AIRCR_VECTKEY_Msk | SCB_AIRCR_PRIGROUP_Msk); /* clear bits to change */
+ reg_value = (reg_value |
+ ((uint32_t)0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (PriorityGroupTmp << 8)); /* Insert write key and priorty group */
+ SCB->AIRCR = reg_value;
+}
+
+
+/** \brief Get Priority Grouping
+
+ The function reads the priority grouping field from the NVIC Interrupt Controller.
+
+ \return Priority grouping field (SCB->AIRCR [10:8] PRIGROUP field).
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriorityGrouping(void)
+{
+ return ((SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) >> SCB_AIRCR_PRIGROUP_Pos); /* read priority grouping field */
+}
+
+
+/** \brief Enable External Interrupt
+
+ The function enables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_EnableIRQ(IRQn_Type IRQn)
+{
+/* NVIC->ISER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); enable interrupt */
+ NVIC->ISER[(uint32_t)((int32_t)IRQn) >> 5] = (uint32_t)(1 << ((uint32_t)((int32_t)IRQn) & (uint32_t)0x1F)); /* enable interrupt */
+}
+
+
+/** \brief Disable External Interrupt
+
+ The function disables a device-specific interrupt in the NVIC interrupt controller.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_DisableIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICER[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* disable interrupt */
+}
+
+
+/** \brief Get Pending Interrupt
+
+ The function reads the pending register in the NVIC and returns the pending bit
+ for the specified interrupt.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not pending.
+ \return 1 Interrupt status is pending.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPendingIRQ(IRQn_Type IRQn)
+{
+ return((uint32_t) ((NVIC->ISPR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if pending else 0 */
+}
+
+
+/** \brief Set Pending Interrupt
+
+ The function sets the pending bit of an external interrupt.
+
+ \param [in] IRQn Interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_SetPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ISPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* set interrupt pending */
+}
+
+
+/** \brief Clear Pending Interrupt
+
+ The function clears the pending bit of an external interrupt.
+
+ \param [in] IRQn External interrupt number. Value cannot be negative.
+ */
+__STATIC_INLINE void NVIC_ClearPendingIRQ(IRQn_Type IRQn)
+{
+ NVIC->ICPR[((uint32_t)(IRQn) >> 5)] = (1 << ((uint32_t)(IRQn) & 0x1F)); /* Clear pending interrupt */
+}
+
+
+/** \brief Get Active Interrupt
+
+ The function reads the active register in NVIC and returns the active bit.
+
+ \param [in] IRQn Interrupt number.
+
+ \return 0 Interrupt status is not active.
+ \return 1 Interrupt status is active.
+ */
+__STATIC_INLINE uint32_t NVIC_GetActive(IRQn_Type IRQn)
+{
+ return((uint32_t)((NVIC->IABR[(uint32_t)(IRQn) >> 5] & (1 << ((uint32_t)(IRQn) & 0x1F)))?1:0)); /* Return 1 if active else 0 */
+}
+
+
+/** \brief Set Interrupt Priority
+
+ The function sets the priority of an interrupt.
+
+ \note The priority cannot be set for every core interrupt.
+
+ \param [in] IRQn Interrupt number.
+ \param [in] priority Priority to set.
+ */
+__STATIC_INLINE void NVIC_SetPriority(IRQn_Type IRQn, uint32_t priority)
+{
+ if(IRQn < 0) {
+ SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for Cortex-M System Interrupts */
+ else {
+ NVIC->IP[(uint32_t)(IRQn)] = ((priority << (8 - __NVIC_PRIO_BITS)) & 0xff); } /* set Priority for device specific Interrupts */
+}
+
+
+/** \brief Get Interrupt Priority
+
+ The function reads the priority of an interrupt. The interrupt
+ number can be positive to specify an external (device specific)
+ interrupt, or negative to specify an internal (core) interrupt.
+
+
+ \param [in] IRQn Interrupt number.
+ \return Interrupt Priority. Value is aligned automatically to the implemented
+ priority bits of the microcontroller.
+ */
+__STATIC_INLINE uint32_t NVIC_GetPriority(IRQn_Type IRQn)
+{
+
+ if(IRQn < 0) {
+ return((uint32_t)(SCB->SHP[((uint32_t)(IRQn) & 0xF)-4] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for Cortex-M system interrupts */
+ else {
+ return((uint32_t)(NVIC->IP[(uint32_t)(IRQn)] >> (8 - __NVIC_PRIO_BITS))); } /* get priority for device specific interrupts */
+}
+
+
+/** \brief Encode Priority
+
+ The function encodes the priority for an interrupt with the given priority group,
+ preemptive priority value, and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS), the samllest possible priority group is set.
+
+ \param [in] PriorityGroup Used priority group.
+ \param [in] PreemptPriority Preemptive priority value (starting from 0).
+ \param [in] SubPriority Subpriority value (starting from 0).
+ \return Encoded priority. Value can be used in the function \ref NVIC_SetPriority().
+ */
+__STATIC_INLINE uint32_t NVIC_EncodePriority (uint32_t PriorityGroup, uint32_t PreemptPriority, uint32_t SubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ return (
+ ((PreemptPriority & ((1 << (PreemptPriorityBits)) - 1)) << SubPriorityBits) |
+ ((SubPriority & ((1 << (SubPriorityBits )) - 1)))
+ );
+}
+
+
+/** \brief Decode Priority
+
+ The function decodes an interrupt priority value with a given priority group to
+ preemptive priority value and subpriority value.
+ In case of a conflict between priority grouping and available
+ priority bits (__NVIC_PRIO_BITS) the samllest possible priority group is set.
+
+ \param [in] Priority Priority value, which can be retrieved with the function \ref NVIC_GetPriority().
+ \param [in] PriorityGroup Used priority group.
+ \param [out] pPreemptPriority Preemptive priority value (starting from 0).
+ \param [out] pSubPriority Subpriority value (starting from 0).
+ */
+__STATIC_INLINE void NVIC_DecodePriority (uint32_t Priority, uint32_t PriorityGroup, uint32_t* pPreemptPriority, uint32_t* pSubPriority)
+{
+ uint32_t PriorityGroupTmp = (PriorityGroup & 0x07); /* only values 0..7 are used */
+ uint32_t PreemptPriorityBits;
+ uint32_t SubPriorityBits;
+
+ PreemptPriorityBits = ((7 - PriorityGroupTmp) > __NVIC_PRIO_BITS) ? __NVIC_PRIO_BITS : 7 - PriorityGroupTmp;
+ SubPriorityBits = ((PriorityGroupTmp + __NVIC_PRIO_BITS) < 7) ? 0 : PriorityGroupTmp - 7 + __NVIC_PRIO_BITS;
+
+ *pPreemptPriority = (Priority >> SubPriorityBits) & ((1 << (PreemptPriorityBits)) - 1);
+ *pSubPriority = (Priority ) & ((1 << (SubPriorityBits )) - 1);
+}
+
+
+/** \brief System Reset
+
+ The function initiates a system reset request to reset the MCU.
+ */
+__STATIC_INLINE void NVIC_SystemReset(void)
+{
+ __DSB(); /* Ensure all outstanding memory accesses included
+ buffered write are completed before reset */
+ SCB->AIRCR = ((0x5FA << SCB_AIRCR_VECTKEY_Pos) |
+ (SCB->AIRCR & SCB_AIRCR_PRIGROUP_Msk) |
+ SCB_AIRCR_SYSRESETREQ_Msk); /* Keep priority group unchanged */
+ __DSB(); /* Ensure completion of memory access */
+ while(1); /* wait until reset */
+}
+
+/*@} end of CMSIS_Core_NVICFunctions */
+
+
+
+/* ################################## SysTick function ############################################ */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_SysTickFunctions SysTick Functions
+ \brief Functions that configure the System.
+ @{
+ */
+
+#if (__Vendor_SysTickConfig == 0)
+
+/** \brief System Tick Configuration
+
+ The function initializes the System Timer and its interrupt, and starts the System Tick Timer.
+ Counter is in free running mode to generate periodic interrupts.
+
+ \param [in] ticks Number of ticks between two interrupts.
+
+ \return 0 Function succeeded.
+ \return 1 Function failed.
+
+ \note When the variable <b>__Vendor_SysTickConfig</b> is set to 1, then the
+ function <b>SysTick_Config</b> is not included. In this case, the file <b><i>device</i>.h</b>
+ must contain a vendor-specific implementation of this function.
+
+ */
+__STATIC_INLINE uint32_t SysTick_Config(uint32_t ticks)
+{
+ if ((ticks - 1) > SysTick_LOAD_RELOAD_Msk) return (1); /* Reload value impossible */
+
+ SysTick->LOAD = ticks - 1; /* set reload register */
+ NVIC_SetPriority (SysTick_IRQn, (1<<__NVIC_PRIO_BITS) - 1); /* set Priority for Systick Interrupt */
+ SysTick->VAL = 0; /* Load the SysTick Counter Value */
+ SysTick->CTRL = SysTick_CTRL_CLKSOURCE_Msk |
+ SysTick_CTRL_TICKINT_Msk |
+ SysTick_CTRL_ENABLE_Msk; /* Enable SysTick IRQ and SysTick Timer */
+ return (0); /* Function successful */
+}
+
+#endif
+
+/*@} end of CMSIS_Core_SysTickFunctions */
+
+
+
+/* ##################################### Debug In/Output function ########################################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_core_DebugFunctions ITM Functions
+ \brief Functions that access the ITM debug interface.
+ @{
+ */
+
+extern volatile int32_t ITM_RxBuffer; /*!< External variable to receive characters. */
+#define ITM_RXBUFFER_EMPTY 0x5AA55AA5 /*!< Value identifying \ref ITM_RxBuffer is ready for next character. */
+
+
+/** \brief ITM Send Character
+
+ The function transmits a character via the ITM channel 0, and
+ \li Just returns when no debugger is connected that has booked the output.
+ \li Is blocking when a debugger is connected, but the previous character sent has not been transmitted.
+
+ \param [in] ch Character to transmit.
+
+ \returns Character to transmit.
+ */
+__STATIC_INLINE uint32_t ITM_SendChar (uint32_t ch)
+{
+ if ((ITM->TCR & ITM_TCR_ITMENA_Msk) && /* ITM enabled */
+ (ITM->TER & (1UL << 0) ) ) /* ITM Port #0 enabled */
+ {
+ while (ITM->PORT[0].u32 == 0);
+ ITM->PORT[0].u8 = (uint8_t) ch;
+ }
+ return (ch);
+}
+
+
+/** \brief ITM Receive Character
+
+ The function inputs a character via the external variable \ref ITM_RxBuffer.
+
+ \return Received character.
+ \return -1 No character pending.
+ */
+__STATIC_INLINE int32_t ITM_ReceiveChar (void) {
+ int32_t ch = -1; /* no character available */
+
+ if (ITM_RxBuffer != ITM_RXBUFFER_EMPTY) {
+ ch = ITM_RxBuffer;
+ ITM_RxBuffer = ITM_RXBUFFER_EMPTY; /* ready for next character */
+ }
+
+ return (ch);
+}
+
+
+/** \brief ITM Check Character
+
+ The function checks whether a character is pending for reading in the variable \ref ITM_RxBuffer.
+
+ \return 0 No character available.
+ \return 1 Character available.
+ */
+__STATIC_INLINE int32_t ITM_CheckChar (void) {
+
+ if (ITM_RxBuffer == ITM_RXBUFFER_EMPTY) {
+ return (0); /* no character available */
+ } else {
+ return (1); /* character available */
+ }
+}
+
+/*@} end of CMSIS_core_DebugFunctions */
+
+#endif /* __CORE_CM4_H_DEPENDANT */
+
+#endif /* __CMSIS_GENERIC */
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/src/lib/mathlib/CMSIS/Include/core_cm4_simd.h b/src/lib/mathlib/CMSIS/Include/core_cm4_simd.h
new file mode 100644
index 000000000..af1831ee1
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/core_cm4_simd.h
@@ -0,0 +1,673 @@
+/**************************************************************************//**
+ * @file core_cm4_simd.h
+ * @brief CMSIS Cortex-M4 SIMD Header File
+ * @version V3.20
+ * @date 25. February 2013
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2013 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+#ifndef __CORE_CM4_SIMD_H
+#define __CORE_CM4_SIMD_H
+
+
+/*******************************************************************************
+ * Hardware Abstraction Layer
+ ******************************************************************************/
+
+
+/* ################### Compiler specific Intrinsics ########################### */
+/** \defgroup CMSIS_SIMD_intrinsics CMSIS SIMD Intrinsics
+ Access to dedicated SIMD instructions
+ @{
+*/
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+
+/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
+#define __SADD8 __sadd8
+#define __QADD8 __qadd8
+#define __SHADD8 __shadd8
+#define __UADD8 __uadd8
+#define __UQADD8 __uqadd8
+#define __UHADD8 __uhadd8
+#define __SSUB8 __ssub8
+#define __QSUB8 __qsub8
+#define __SHSUB8 __shsub8
+#define __USUB8 __usub8
+#define __UQSUB8 __uqsub8
+#define __UHSUB8 __uhsub8
+#define __SADD16 __sadd16
+#define __QADD16 __qadd16
+#define __SHADD16 __shadd16
+#define __UADD16 __uadd16
+#define __UQADD16 __uqadd16
+#define __UHADD16 __uhadd16
+#define __SSUB16 __ssub16
+#define __QSUB16 __qsub16
+#define __SHSUB16 __shsub16
+#define __USUB16 __usub16
+#define __UQSUB16 __uqsub16
+#define __UHSUB16 __uhsub16
+#define __SASX __sasx
+#define __QASX __qasx
+#define __SHASX __shasx
+#define __UASX __uasx
+#define __UQASX __uqasx
+#define __UHASX __uhasx
+#define __SSAX __ssax
+#define __QSAX __qsax
+#define __SHSAX __shsax
+#define __USAX __usax
+#define __UQSAX __uqsax
+#define __UHSAX __uhsax
+#define __USAD8 __usad8
+#define __USADA8 __usada8
+#define __SSAT16 __ssat16
+#define __USAT16 __usat16
+#define __UXTB16 __uxtb16
+#define __UXTAB16 __uxtab16
+#define __SXTB16 __sxtb16
+#define __SXTAB16 __sxtab16
+#define __SMUAD __smuad
+#define __SMUADX __smuadx
+#define __SMLAD __smlad
+#define __SMLADX __smladx
+#define __SMLALD __smlald
+#define __SMLALDX __smlaldx
+#define __SMUSD __smusd
+#define __SMUSDX __smusdx
+#define __SMLSD __smlsd
+#define __SMLSDX __smlsdx
+#define __SMLSLD __smlsld
+#define __SMLSLDX __smlsldx
+#define __SEL __sel
+#define __QADD __qadd
+#define __QSUB __qsub
+
+#define __PKHBT(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0x0000FFFFUL) | \
+ ((((uint32_t)(ARG2)) << (ARG3)) & 0xFFFF0000UL) )
+
+#define __PKHTB(ARG1,ARG2,ARG3) ( ((((uint32_t)(ARG1)) ) & 0xFFFF0000UL) | \
+ ((((uint32_t)(ARG2)) >> (ARG3)) & 0x0000FFFFUL) )
+
+#define __SMMLA(ARG1,ARG2,ARG3) ( (int32_t)((((int64_t)(ARG1) * (ARG2)) + \
+ ((int64_t)(ARG3) << 32) ) >> 32))
+
+/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
+
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+
+/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
+#include <cmsis_iar.h>
+
+/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
+
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+
+/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
+#include <cmsis_ccs.h>
+
+/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
+
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+
+/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhadd8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsub8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHADD16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhadd16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSUB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsub16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHASX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhasx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("ssax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("shsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UQSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uqsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UHSAX(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uhsax %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USAD8(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("usad8 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __USADA8(uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("usada8 %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+#define __SSAT16(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+#define __USAT16(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat16 %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile ("uxtb16 %0, %1" : "=r" (result) : "r" (op1));
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __UXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("uxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTB16(uint32_t op1)
+{
+ uint32_t result;
+
+ __ASM volatile ("sxtb16 %0, %1" : "=r" (result) : "r" (op1));
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SXTAB16(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sxtab16 %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUAD (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smuad %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUADX (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smuadx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLAD (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlad %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLADX (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smladx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+#define __SMLALD(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
+ __ASM volatile ("smlald %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
+ (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
+ })
+
+#define __SMLALDX(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((uint64_t)(ARG3) >> 32), __ARG3_L = (uint32_t)((uint64_t)(ARG3) & 0xFFFFFFFFUL); \
+ __ASM volatile ("smlaldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
+ (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
+ })
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSD (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smusd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMUSDX (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("smusdx %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSD (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlsd %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMLSDX (uint32_t op1, uint32_t op2, uint32_t op3)
+{
+ uint32_t result;
+
+ __ASM volatile ("smlsdx %0, %1, %2, %3" : "=r" (result) : "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+#define __SMLSLD(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
+ __ASM volatile ("smlsld %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
+ (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
+ })
+
+#define __SMLSLDX(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __ARG1 = (ARG1), __ARG2 = (ARG2), __ARG3_H = (uint32_t)((ARG3) >> 32), __ARG3_L = (uint32_t)((ARG3) & 0xFFFFFFFFUL); \
+ __ASM volatile ("smlsldx %0, %1, %2, %3" : "=r" (__ARG3_L), "=r" (__ARG3_H) : "r" (__ARG1), "r" (__ARG2), "0" (__ARG3_L), "1" (__ARG3_H) ); \
+ (uint64_t)(((uint64_t)__ARG3_H << 32) | __ARG3_L); \
+ })
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SEL (uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("sel %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QADD(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qadd %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __QSUB(uint32_t op1, uint32_t op2)
+{
+ uint32_t result;
+
+ __ASM volatile ("qsub %0, %1, %2" : "=r" (result) : "r" (op1), "r" (op2) );
+ return(result);
+}
+
+#define __PKHBT(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ __ASM ("pkhbt %0, %1, %2, lsl %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+
+#define __PKHTB(ARG1,ARG2,ARG3) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1), __ARG2 = (ARG2); \
+ if (ARG3 == 0) \
+ __ASM ("pkhtb %0, %1, %2" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2) ); \
+ else \
+ __ASM ("pkhtb %0, %1, %2, asr %3" : "=r" (__RES) : "r" (__ARG1), "r" (__ARG2), "I" (ARG3) ); \
+ __RES; \
+ })
+
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __SMMLA (int32_t op1, int32_t op2, int32_t op3)
+{
+ int32_t result;
+
+ __ASM volatile ("smmla %0, %1, %2, %3" : "=r" (result): "r" (op1), "r" (op2), "r" (op3) );
+ return(result);
+}
+
+/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
+
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+
+
+/*------ CM4 SIMD Intrinsics -----------------------------------------------------*/
+/* not yet supported */
+/*-- End CM4 SIMD Intrinsics -----------------------------------------------------*/
+
+
+#endif
+
+/*@} end of group CMSIS_SIMD_intrinsics */
+
+
+#endif /* __CORE_CM4_SIMD_H */
+
+#ifdef __cplusplus
+}
+#endif
diff --git a/src/lib/mathlib/CMSIS/Include/core_cmFunc.h b/src/lib/mathlib/CMSIS/Include/core_cmFunc.h
new file mode 100644
index 000000000..139bc3c5e
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/core_cmFunc.h
@@ -0,0 +1,636 @@
+/**************************************************************************//**
+ * @file core_cmFunc.h
+ * @brief CMSIS Cortex-M Core Function Access Header File
+ * @version V3.20
+ * @date 25. February 2013
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2013 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#ifndef __CORE_CMFUNC_H
+#define __CORE_CMFUNC_H
+
+
+/* ########################### Core Function Access ########################### */
+/** \ingroup CMSIS_Core_FunctionInterface
+ \defgroup CMSIS_Core_RegAccFunctions CMSIS Core Register Access Functions
+ @{
+ */
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+
+#if (__ARMCC_VERSION < 400677)
+ #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
+#endif
+
+/* intrinsic void __enable_irq(); */
+/* intrinsic void __disable_irq(); */
+
+/** \brief Get Control Register
+
+ This function returns the content of the Control Register.
+
+ \return Control Register value
+ */
+__STATIC_INLINE uint32_t __get_CONTROL(void)
+{
+ register uint32_t __regControl __ASM("control");
+ return(__regControl);
+}
+
+
+/** \brief Set Control Register
+
+ This function writes the given value to the Control Register.
+
+ \param [in] control Control Register value to set
+ */
+__STATIC_INLINE void __set_CONTROL(uint32_t control)
+{
+ register uint32_t __regControl __ASM("control");
+ __regControl = control;
+}
+
+
+/** \brief Get IPSR Register
+
+ This function returns the content of the IPSR Register.
+
+ \return IPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_IPSR(void)
+{
+ register uint32_t __regIPSR __ASM("ipsr");
+ return(__regIPSR);
+}
+
+
+/** \brief Get APSR Register
+
+ This function returns the content of the APSR Register.
+
+ \return APSR Register value
+ */
+__STATIC_INLINE uint32_t __get_APSR(void)
+{
+ register uint32_t __regAPSR __ASM("apsr");
+ return(__regAPSR);
+}
+
+
+/** \brief Get xPSR Register
+
+ This function returns the content of the xPSR Register.
+
+ \return xPSR Register value
+ */
+__STATIC_INLINE uint32_t __get_xPSR(void)
+{
+ register uint32_t __regXPSR __ASM("xpsr");
+ return(__regXPSR);
+}
+
+
+/** \brief Get Process Stack Pointer
+
+ This function returns the current value of the Process Stack Pointer (PSP).
+
+ \return PSP Register value
+ */
+__STATIC_INLINE uint32_t __get_PSP(void)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ return(__regProcessStackPointer);
+}
+
+
+/** \brief Set Process Stack Pointer
+
+ This function assigns the given value to the Process Stack Pointer (PSP).
+
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ register uint32_t __regProcessStackPointer __ASM("psp");
+ __regProcessStackPointer = topOfProcStack;
+}
+
+
+/** \brief Get Main Stack Pointer
+
+ This function returns the current value of the Main Stack Pointer (MSP).
+
+ \return MSP Register value
+ */
+__STATIC_INLINE uint32_t __get_MSP(void)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ return(__regMainStackPointer);
+}
+
+
+/** \brief Set Main Stack Pointer
+
+ This function assigns the given value to the Main Stack Pointer (MSP).
+
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ register uint32_t __regMainStackPointer __ASM("msp");
+ __regMainStackPointer = topOfMainStack;
+}
+
+
+/** \brief Get Priority Mask
+
+ This function returns the current state of the priority mask bit from the Priority Mask Register.
+
+ \return Priority Mask value
+ */
+__STATIC_INLINE uint32_t __get_PRIMASK(void)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ return(__regPriMask);
+}
+
+
+/** \brief Set Priority Mask
+
+ This function assigns the given value to the Priority Mask Register.
+
+ \param [in] priMask Priority Mask
+ */
+__STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
+{
+ register uint32_t __regPriMask __ASM("primask");
+ __regPriMask = (priMask);
+}
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Enable FIQ
+
+ This function enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __enable_fault_irq __enable_fiq
+
+
+/** \brief Disable FIQ
+
+ This function disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+#define __disable_fault_irq __disable_fiq
+
+
+/** \brief Get Base Priority
+
+ This function returns the current value of the Base Priority register.
+
+ \return Base Priority register value
+ */
+__STATIC_INLINE uint32_t __get_BASEPRI(void)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ return(__regBasePri);
+}
+
+
+/** \brief Set Base Priority
+
+ This function assigns the given value to the Base Priority register.
+
+ \param [in] basePri Base Priority value to set
+ */
+__STATIC_INLINE void __set_BASEPRI(uint32_t basePri)
+{
+ register uint32_t __regBasePri __ASM("basepri");
+ __regBasePri = (basePri & 0xff);
+}
+
+
+/** \brief Get Fault Mask
+
+ This function returns the current value of the Fault Mask register.
+
+ \return Fault Mask register value
+ */
+__STATIC_INLINE uint32_t __get_FAULTMASK(void)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ return(__regFaultMask);
+}
+
+
+/** \brief Set Fault Mask
+
+ This function assigns the given value to the Fault Mask register.
+
+ \param [in] faultMask Fault Mask value to set
+ */
+__STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ register uint32_t __regFaultMask __ASM("faultmask");
+ __regFaultMask = (faultMask & (uint32_t)1);
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+#if (__CORTEX_M == 0x04)
+
+/** \brief Get FPSCR
+
+ This function returns the current value of the Floating Point Status/Control register.
+
+ \return Floating Point Status/Control register value
+ */
+__STATIC_INLINE uint32_t __get_FPSCR(void)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ register uint32_t __regfpscr __ASM("fpscr");
+ return(__regfpscr);
+#else
+ return(0);
+#endif
+}
+
+
+/** \brief Set FPSCR
+
+ This function assigns the given value to the Floating Point Status/Control register.
+
+ \param [in] fpscr Floating Point Status/Control value to set
+ */
+__STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ register uint32_t __regfpscr __ASM("fpscr");
+ __regfpscr = (fpscr);
+#endif
+}
+
+#endif /* (__CORTEX_M == 0x04) */
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+
+#include <cmsis_iar.h>
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+
+#include <cmsis_ccs.h>
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+
+/** \brief Enable IRQ Interrupts
+
+ This function enables IRQ interrupts by clearing the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_irq(void)
+{
+ __ASM volatile ("cpsie i" : : : "memory");
+}
+
+
+/** \brief Disable IRQ Interrupts
+
+ This function disables IRQ interrupts by setting the I-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_irq(void)
+{
+ __ASM volatile ("cpsid i" : : : "memory");
+}
+
+
+/** \brief Get Control Register
+
+ This function returns the content of the Control Register.
+
+ \return Control Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_CONTROL(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, control" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Control Register
+
+ This function writes the given value to the Control Register.
+
+ \param [in] control Control Register value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_CONTROL(uint32_t control)
+{
+ __ASM volatile ("MSR control, %0" : : "r" (control) : "memory");
+}
+
+
+/** \brief Get IPSR Register
+
+ This function returns the content of the IPSR Register.
+
+ \return IPSR Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_IPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, ipsr" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Get APSR Register
+
+ This function returns the content of the APSR Register.
+
+ \return APSR Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_APSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, apsr" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Get xPSR Register
+
+ This function returns the content of the xPSR Register.
+
+ \return xPSR Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_xPSR(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, xpsr" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Get Process Stack Pointer
+
+ This function returns the current value of the Process Stack Pointer (PSP).
+
+ \return PSP Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PSP(void)
+{
+ register uint32_t result;
+
+ __ASM volatile ("MRS %0, psp\n" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Process Stack Pointer
+
+ This function assigns the given value to the Process Stack Pointer (PSP).
+
+ \param [in] topOfProcStack Process Stack Pointer value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PSP(uint32_t topOfProcStack)
+{
+ __ASM volatile ("MSR psp, %0\n" : : "r" (topOfProcStack) : "sp");
+}
+
+
+/** \brief Get Main Stack Pointer
+
+ This function returns the current value of the Main Stack Pointer (MSP).
+
+ \return MSP Register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_MSP(void)
+{
+ register uint32_t result;
+
+ __ASM volatile ("MRS %0, msp\n" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Main Stack Pointer
+
+ This function assigns the given value to the Main Stack Pointer (MSP).
+
+ \param [in] topOfMainStack Main Stack Pointer value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_MSP(uint32_t topOfMainStack)
+{
+ __ASM volatile ("MSR msp, %0\n" : : "r" (topOfMainStack) : "sp");
+}
+
+
+/** \brief Get Priority Mask
+
+ This function returns the current state of the priority mask bit from the Priority Mask Register.
+
+ \return Priority Mask value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_PRIMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, primask" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Priority Mask
+
+ This function assigns the given value to the Priority Mask Register.
+
+ \param [in] priMask Priority Mask
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_PRIMASK(uint32_t priMask)
+{
+ __ASM volatile ("MSR primask, %0" : : "r" (priMask) : "memory");
+}
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Enable FIQ
+
+ This function enables FIQ interrupts by clearing the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __enable_fault_irq(void)
+{
+ __ASM volatile ("cpsie f" : : : "memory");
+}
+
+
+/** \brief Disable FIQ
+
+ This function disables FIQ interrupts by setting the F-bit in the CPSR.
+ Can only be executed in Privileged modes.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __disable_fault_irq(void)
+{
+ __ASM volatile ("cpsid f" : : : "memory");
+}
+
+
+/** \brief Get Base Priority
+
+ This function returns the current value of the Base Priority register.
+
+ \return Base Priority register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_BASEPRI(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, basepri_max" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Base Priority
+
+ This function assigns the given value to the Base Priority register.
+
+ \param [in] basePri Base Priority value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_BASEPRI(uint32_t value)
+{
+ __ASM volatile ("MSR basepri, %0" : : "r" (value) : "memory");
+}
+
+
+/** \brief Get Fault Mask
+
+ This function returns the current value of the Fault Mask register.
+
+ \return Fault Mask register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FAULTMASK(void)
+{
+ uint32_t result;
+
+ __ASM volatile ("MRS %0, faultmask" : "=r" (result) );
+ return(result);
+}
+
+
+/** \brief Set Fault Mask
+
+ This function assigns the given value to the Fault Mask register.
+
+ \param [in] faultMask Fault Mask value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FAULTMASK(uint32_t faultMask)
+{
+ __ASM volatile ("MSR faultmask, %0" : : "r" (faultMask) : "memory");
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+#if (__CORTEX_M == 0x04)
+
+/** \brief Get FPSCR
+
+ This function returns the current value of the Floating Point Status/Control register.
+
+ \return Floating Point Status/Control register value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __get_FPSCR(void)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ uint32_t result;
+
+ /* Empty asm statement works as a scheduling barrier */
+ __ASM volatile ("");
+ __ASM volatile ("VMRS %0, fpscr" : "=r" (result) );
+ __ASM volatile ("");
+ return(result);
+#else
+ return(0);
+#endif
+}
+
+
+/** \brief Set FPSCR
+
+ This function assigns the given value to the Floating Point Status/Control register.
+
+ \param [in] fpscr Floating Point Status/Control value to set
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __set_FPSCR(uint32_t fpscr)
+{
+#if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ /* Empty asm statement works as a scheduling barrier */
+ __ASM volatile ("");
+ __ASM volatile ("VMSR fpscr, %0" : : "r" (fpscr) : "vfpcc");
+ __ASM volatile ("");
+#endif
+}
+
+#endif /* (__CORTEX_M == 0x04) */
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+
+/*
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all instrinsics,
+ * Including the CMSIS ones.
+ */
+
+#endif
+
+/*@} end of CMSIS_Core_RegAccFunctions */
+
+
+#endif /* __CORE_CMFUNC_H */
diff --git a/src/lib/mathlib/CMSIS/Include/core_cmInstr.h b/src/lib/mathlib/CMSIS/Include/core_cmInstr.h
new file mode 100644
index 000000000..8946c2c49
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/Include/core_cmInstr.h
@@ -0,0 +1,688 @@
+/**************************************************************************//**
+ * @file core_cmInstr.h
+ * @brief CMSIS Cortex-M Core Instruction Access Header File
+ * @version V3.20
+ * @date 05. March 2013
+ *
+ * @note
+ *
+ ******************************************************************************/
+/* Copyright (c) 2009 - 2013 ARM LIMITED
+
+ All rights reserved.
+ Redistribution and use in source and binary forms, with or without
+ modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
+ ---------------------------------------------------------------------------*/
+
+
+#ifndef __CORE_CMINSTR_H
+#define __CORE_CMINSTR_H
+
+
+/* ########################## Core Instruction Access ######################### */
+/** \defgroup CMSIS_Core_InstructionInterface CMSIS Core Instruction Interface
+ Access to dedicated instructions
+ @{
+*/
+
+#if defined ( __CC_ARM ) /*------------------RealView Compiler -----------------*/
+/* ARM armcc specific functions */
+
+#if (__ARMCC_VERSION < 400677)
+ #error "Please use ARM Compiler Toolchain V4.0.677 or later!"
+#endif
+
+
+/** \brief No Operation
+
+ No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+#define __NOP __nop
+
+
+/** \brief Wait For Interrupt
+
+ Wait For Interrupt is a hint instruction that suspends execution
+ until one of a number of events occurs.
+ */
+#define __WFI __wfi
+
+
+/** \brief Wait For Event
+
+ Wait For Event is a hint instruction that permits the processor to enter
+ a low-power state until one of a number of events occurs.
+ */
+#define __WFE __wfe
+
+
+/** \brief Send Event
+
+ Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+#define __SEV __sev
+
+
+/** \brief Instruction Synchronization Barrier
+
+ Instruction Synchronization Barrier flushes the pipeline in the processor,
+ so that all instructions following the ISB are fetched from cache or
+ memory, after the instruction has been completed.
+ */
+#define __ISB() __isb(0xF)
+
+
+/** \brief Data Synchronization Barrier
+
+ This function acts as a special kind of Data Memory Barrier.
+ It completes when all explicit memory accesses before this instruction complete.
+ */
+#define __DSB() __dsb(0xF)
+
+
+/** \brief Data Memory Barrier
+
+ This function ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+#define __DMB() __dmb(0xF)
+
+
+/** \brief Reverse byte order (32 bit)
+
+ This function reverses the byte order in integer value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#define __REV __rev
+
+
+/** \brief Reverse byte order (16 bit)
+
+ This function reverses the byte order in two unsigned short values.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#ifndef __NO_EMBEDDED_ASM
+__attribute__((section(".rev16_text"))) __STATIC_INLINE __ASM uint32_t __REV16(uint32_t value)
+{
+ rev16 r0, r0
+ bx lr
+}
+#endif
+
+/** \brief Reverse byte order in signed short value
+
+ This function reverses the byte order in a signed short value with sign extension to integer.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#ifndef __NO_EMBEDDED_ASM
+__attribute__((section(".revsh_text"))) __STATIC_INLINE __ASM int32_t __REVSH(int32_t value)
+{
+ revsh r0, r0
+ bx lr
+}
+#endif
+
+
+/** \brief Rotate Right in unsigned value (32 bit)
+
+ This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
+
+ \param [in] value Value to rotate
+ \param [in] value Number of Bits to rotate
+ \return Rotated value
+ */
+#define __ROR __ror
+
+
+/** \brief Breakpoint
+
+ This function causes the processor to enter Debug state.
+ Debug tools can use this to investigate system state when the instruction at a particular address is reached.
+
+ \param [in] value is ignored by the processor.
+ If required, a debugger can use it to store additional information about the breakpoint.
+ */
+#define __BKPT(value) __breakpoint(value)
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Reverse bit order of value
+
+ This function reverses the bit order of the given value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+#define __RBIT __rbit
+
+
+/** \brief LDR Exclusive (8 bit)
+
+ This function performs a exclusive LDR command for 8 bit value.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+#define __LDREXB(ptr) ((uint8_t ) __ldrex(ptr))
+
+
+/** \brief LDR Exclusive (16 bit)
+
+ This function performs a exclusive LDR command for 16 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+#define __LDREXH(ptr) ((uint16_t) __ldrex(ptr))
+
+
+/** \brief LDR Exclusive (32 bit)
+
+ This function performs a exclusive LDR command for 32 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+#define __LDREXW(ptr) ((uint32_t ) __ldrex(ptr))
+
+
+/** \brief STR Exclusive (8 bit)
+
+ This function performs a exclusive STR command for 8 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXB(value, ptr) __strex(value, ptr)
+
+
+/** \brief STR Exclusive (16 bit)
+
+ This function performs a exclusive STR command for 16 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXH(value, ptr) __strex(value, ptr)
+
+
+/** \brief STR Exclusive (32 bit)
+
+ This function performs a exclusive STR command for 32 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+#define __STREXW(value, ptr) __strex(value, ptr)
+
+
+/** \brief Remove the exclusive lock
+
+ This function removes the exclusive lock which is created by LDREX.
+
+ */
+#define __CLREX __clrex
+
+
+/** \brief Signed Saturate
+
+ This function saturates a signed value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT __ssat
+
+
+/** \brief Unsigned Saturate
+
+ This function saturates an unsigned value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+#define __USAT __usat
+
+
+/** \brief Count leading zeros
+
+ This function counts the number of leading zeros of a data value.
+
+ \param [in] value Value to count the leading zeros
+ \return number of leading zeros in value
+ */
+#define __CLZ __clz
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+
+#elif defined ( __ICCARM__ ) /*------------------ ICC Compiler -------------------*/
+/* IAR iccarm specific functions */
+
+#include <cmsis_iar.h>
+
+
+#elif defined ( __TMS470__ ) /*---------------- TI CCS Compiler ------------------*/
+/* TI CCS specific functions */
+
+#include <cmsis_ccs.h>
+
+
+#elif defined ( __GNUC__ ) /*------------------ GNU Compiler ---------------------*/
+/* GNU gcc specific functions */
+
+/* Define macros for porting to both thumb1 and thumb2.
+ * For thumb1, use low register (r0-r7), specified by constrant "l"
+ * Otherwise, use general registers, specified by constrant "r" */
+#if defined (__thumb__) && !defined (__thumb2__)
+#define __CMSIS_GCC_OUT_REG(r) "=l" (r)
+#define __CMSIS_GCC_USE_REG(r) "l" (r)
+#else
+#define __CMSIS_GCC_OUT_REG(r) "=r" (r)
+#define __CMSIS_GCC_USE_REG(r) "r" (r)
+#endif
+
+/** \brief No Operation
+
+ No Operation does nothing. This instruction can be used for code alignment purposes.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __NOP(void)
+{
+ __ASM volatile ("nop");
+}
+
+
+/** \brief Wait For Interrupt
+
+ Wait For Interrupt is a hint instruction that suspends execution
+ until one of a number of events occurs.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFI(void)
+{
+ __ASM volatile ("wfi");
+}
+
+
+/** \brief Wait For Event
+
+ Wait For Event is a hint instruction that permits the processor to enter
+ a low-power state until one of a number of events occurs.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __WFE(void)
+{
+ __ASM volatile ("wfe");
+}
+
+
+/** \brief Send Event
+
+ Send Event is a hint instruction. It causes an event to be signaled to the CPU.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __SEV(void)
+{
+ __ASM volatile ("sev");
+}
+
+
+/** \brief Instruction Synchronization Barrier
+
+ Instruction Synchronization Barrier flushes the pipeline in the processor,
+ so that all instructions following the ISB are fetched from cache or
+ memory, after the instruction has been completed.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __ISB(void)
+{
+ __ASM volatile ("isb");
+}
+
+
+/** \brief Data Synchronization Barrier
+
+ This function acts as a special kind of Data Memory Barrier.
+ It completes when all explicit memory accesses before this instruction complete.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __DSB(void)
+{
+ __ASM volatile ("dsb");
+}
+
+
+/** \brief Data Memory Barrier
+
+ This function ensures the apparent order of the explicit memory operations before
+ and after the instruction, without ensuring their completion.
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __DMB(void)
+{
+ __ASM volatile ("dmb");
+}
+
+
+/** \brief Reverse byte order (32 bit)
+
+ This function reverses the byte order in integer value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV(uint32_t value)
+{
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 5)
+ return __builtin_bswap32(value);
+#else
+ uint32_t result;
+
+ __ASM volatile ("rev %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return(result);
+#endif
+}
+
+
+/** \brief Reverse byte order (16 bit)
+
+ This function reverses the byte order in two unsigned short values.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __REV16(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile ("rev16 %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return(result);
+}
+
+
+/** \brief Reverse byte order in signed short value
+
+ This function reverses the byte order in a signed short value with sign extension to integer.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE int32_t __REVSH(int32_t value)
+{
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ return (short)__builtin_bswap16(value);
+#else
+ uint32_t result;
+
+ __ASM volatile ("revsh %0, %1" : __CMSIS_GCC_OUT_REG (result) : __CMSIS_GCC_USE_REG (value) );
+ return(result);
+#endif
+}
+
+
+/** \brief Rotate Right in unsigned value (32 bit)
+
+ This function Rotate Right (immediate) provides the value of the contents of a register rotated by a variable number of bits.
+
+ \param [in] value Value to rotate
+ \param [in] value Number of Bits to rotate
+ \return Rotated value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __ROR(uint32_t op1, uint32_t op2)
+{
+ return (op1 >> op2) | (op1 << (32 - op2));
+}
+
+
+/** \brief Breakpoint
+
+ This function causes the processor to enter Debug state.
+ Debug tools can use this to investigate system state when the instruction at a particular address is reached.
+
+ \param [in] value is ignored by the processor.
+ If required, a debugger can use it to store additional information about the breakpoint.
+ */
+#define __BKPT(value) __ASM volatile ("bkpt "#value)
+
+
+#if (__CORTEX_M >= 0x03)
+
+/** \brief Reverse bit order of value
+
+ This function reverses the bit order of the given value.
+
+ \param [in] value Value to reverse
+ \return Reversed value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __RBIT(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile ("rbit %0, %1" : "=r" (result) : "r" (value) );
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (8 bit)
+
+ This function performs a exclusive LDR command for 8 bit value.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint8_t at (*ptr)
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __LDREXB(volatile uint8_t *addr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrexb %0, %1" : "=r" (result) : "Q" (*addr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrexb %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
+#endif
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (16 bit)
+
+ This function performs a exclusive LDR command for 16 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint16_t at (*ptr)
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint16_t __LDREXH(volatile uint16_t *addr)
+{
+ uint32_t result;
+
+#if (__GNUC__ > 4) || (__GNUC__ == 4 && __GNUC_MINOR__ >= 8)
+ __ASM volatile ("ldrexh %0, %1" : "=r" (result) : "Q" (*addr) );
+#else
+ /* Prior to GCC 4.8, "Q" will be expanded to [rx, #0] which is not
+ accepted by assembler. So has to use following less efficient pattern.
+ */
+ __ASM volatile ("ldrexh %0, [%1]" : "=r" (result) : "r" (addr) : "memory" );
+#endif
+ return(result);
+}
+
+
+/** \brief LDR Exclusive (32 bit)
+
+ This function performs a exclusive LDR command for 32 bit values.
+
+ \param [in] ptr Pointer to data
+ \return value of type uint32_t at (*ptr)
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __LDREXW(volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("ldrex %0, %1" : "=r" (result) : "Q" (*addr) );
+ return(result);
+}
+
+
+/** \brief STR Exclusive (8 bit)
+
+ This function performs a exclusive STR command for 8 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXB(uint8_t value, volatile uint8_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strexb %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
+ return(result);
+}
+
+
+/** \brief STR Exclusive (16 bit)
+
+ This function performs a exclusive STR command for 16 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXH(uint16_t value, volatile uint16_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strexh %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
+ return(result);
+}
+
+
+/** \brief STR Exclusive (32 bit)
+
+ This function performs a exclusive STR command for 32 bit values.
+
+ \param [in] value Value to store
+ \param [in] ptr Pointer to location
+ \return 0 Function succeeded
+ \return 1 Function failed
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint32_t __STREXW(uint32_t value, volatile uint32_t *addr)
+{
+ uint32_t result;
+
+ __ASM volatile ("strex %0, %2, %1" : "=&r" (result), "=Q" (*addr) : "r" (value) );
+ return(result);
+}
+
+
+/** \brief Remove the exclusive lock
+
+ This function removes the exclusive lock which is created by LDREX.
+
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE void __CLREX(void)
+{
+ __ASM volatile ("clrex" ::: "memory");
+}
+
+
+/** \brief Signed Saturate
+
+ This function saturates a signed value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (1..32)
+ \return Saturated value
+ */
+#define __SSAT(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("ssat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/** \brief Unsigned Saturate
+
+ This function saturates an unsigned value.
+
+ \param [in] value Value to be saturated
+ \param [in] sat Bit position to saturate to (0..31)
+ \return Saturated value
+ */
+#define __USAT(ARG1,ARG2) \
+({ \
+ uint32_t __RES, __ARG1 = (ARG1); \
+ __ASM ("usat %0, %1, %2" : "=r" (__RES) : "I" (ARG2), "r" (__ARG1) ); \
+ __RES; \
+ })
+
+
+/** \brief Count leading zeros
+
+ This function counts the number of leading zeros of a data value.
+
+ \param [in] value Value to count the leading zeros
+ \return number of leading zeros in value
+ */
+__attribute__( ( always_inline ) ) __STATIC_INLINE uint8_t __CLZ(uint32_t value)
+{
+ uint32_t result;
+
+ __ASM volatile ("clz %0, %1" : "=r" (result) : "r" (value) );
+ return(result);
+}
+
+#endif /* (__CORTEX_M >= 0x03) */
+
+
+
+
+#elif defined ( __TASKING__ ) /*------------------ TASKING Compiler --------------*/
+/* TASKING carm specific functions */
+
+/*
+ * The CMSIS functions have been implemented as intrinsics in the compiler.
+ * Please use "carm -?i" to get an up to date list of all intrinsics,
+ * Including the CMSIS ones.
+ */
+
+#endif
+
+/*@}*/ /* end of group CMSIS_Core_InstructionInterface */
+
+#endif /* __CORE_CMINSTR_H */
diff --git a/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a b/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a
new file mode 100644
index 000000000..6898bc27d
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/libarm_cortexM3l_math.a
Binary files differ
diff --git a/src/lib/mathlib/CMSIS/libarm_cortexM4l_math.a b/src/lib/mathlib/CMSIS/libarm_cortexM4l_math.a
new file mode 100755
index 000000000..a0185eaa9
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/libarm_cortexM4l_math.a
Binary files differ
diff --git a/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a b/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a
new file mode 100755
index 000000000..94525528e
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/libarm_cortexM4lf_math.a
Binary files differ
diff --git a/src/lib/mathlib/CMSIS/library.mk b/src/lib/mathlib/CMSIS/library.mk
new file mode 100644
index 000000000..0cc1b559d
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/library.mk
@@ -0,0 +1,46 @@
+############################################################################
+#
+# Copyright (c) 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# 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.
+#
+############################################################################
+
+#
+# ARM CMSIS DSP library
+#
+
+ifeq ($(CONFIG_ARCH),CORTEXM4F)
+PREBUILT_LIB := libarm_cortexM4lf_math.a
+else ifeq ($(CONFIG_ARCH),CORTEXM4)
+PREBUILT_LIB := libarm_cortexM4l_math.a
+else ifeq ($(CONFIG_ARCH),CORTEXM3)
+PREBUILT_LIB := libarm_cortexM3l_math.a
+else
+$(error CONFIG_ARCH value '$(CONFIG_ARCH)' not supported by the DSP library)
+endif
diff --git a/src/lib/mathlib/CMSIS/license.txt b/src/lib/mathlib/CMSIS/license.txt
new file mode 100644
index 000000000..31afac1ec
--- /dev/null
+++ b/src/lib/mathlib/CMSIS/license.txt
@@ -0,0 +1,27 @@
+All pre-built libraries are guided by the following license:
+
+Copyright (C) 2009-2012 ARM Limited.
+All rights reserved.
+
+Redistribution and use in source and binary forms, with or without
+modification, are permitted provided that the following conditions are met:
+ - Redistributions of source code must retain the above copyright
+ notice, this list of conditions and the following disclaimer.
+ - 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.
+ - Neither the name of ARM 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 COPYRIGHT HOLDERS AND 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.
diff --git a/src/lib/mathlib/math/Dcm.cpp b/src/lib/mathlib/math/Dcm.cpp
new file mode 100644
index 000000000..5c15d4d6d
--- /dev/null
+++ b/src/lib/mathlib/math/Dcm.cpp
@@ -0,0 +1,179 @@
+/****************************************************************************
+ *
+ * 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 Dcm.cpp
+ *
+ * math direction cosine matrix
+ */
+
+#include <mathlib/math/test/test.hpp>
+
+#include "Dcm.hpp"
+#include "Quaternion.hpp"
+#include "EulerAngles.hpp"
+#include "Vector3.hpp"
+
+namespace math
+{
+
+Dcm::Dcm() :
+ Matrix(Matrix::identity(3))
+{
+}
+
+Dcm::Dcm(float c00, float c01, float c02,
+ float c10, float c11, float c12,
+ float c20, float c21, float c22) :
+ Matrix(3, 3)
+{
+ Dcm &dcm = *this;
+ dcm(0, 0) = c00;
+ dcm(0, 1) = c01;
+ dcm(0, 2) = c02;
+ dcm(1, 0) = c10;
+ dcm(1, 1) = c11;
+ dcm(1, 2) = c12;
+ dcm(2, 0) = c20;
+ dcm(2, 1) = c21;
+ dcm(2, 2) = c22;
+}
+
+Dcm::Dcm(const float data[3][3]) :
+ Matrix(3, 3)
+{
+ Dcm &dcm = *this;
+ /* set rotation matrix */
+ for (int i = 0; i < 3; i++) for (int j = 0; j < 3; j++)
+ dcm(i, j) = data[i][j];
+}
+
+Dcm::Dcm(const float *data) :
+ Matrix(3, 3, data)
+{
+}
+
+Dcm::Dcm(const Quaternion &q) :
+ Matrix(3, 3)
+{
+ Dcm &dcm = *this;
+ double a = q.getA();
+ double b = q.getB();
+ double c = q.getC();
+ double d = q.getD();
+ double aSq = a * a;
+ double bSq = b * b;
+ double cSq = c * c;
+ double dSq = d * d;
+ dcm(0, 0) = aSq + bSq - cSq - dSq;
+ dcm(0, 1) = 2.0 * (b * c - a * d);
+ dcm(0, 2) = 2.0 * (a * c + b * d);
+ dcm(1, 0) = 2.0 * (b * c + a * d);
+ dcm(1, 1) = aSq - bSq + cSq - dSq;
+ dcm(1, 2) = 2.0 * (c * d - a * b);
+ dcm(2, 0) = 2.0 * (b * d - a * c);
+ dcm(2, 1) = 2.0 * (a * b + c * d);
+ dcm(2, 2) = aSq - bSq - cSq + dSq;
+}
+
+Dcm::Dcm(const EulerAngles &euler) :
+ Matrix(3, 3)
+{
+ Dcm &dcm = *this;
+ double cosPhi = cos(euler.getPhi());
+ double sinPhi = sin(euler.getPhi());
+ double cosThe = cos(euler.getTheta());
+ double sinThe = sin(euler.getTheta());
+ double cosPsi = cos(euler.getPsi());
+ double sinPsi = sin(euler.getPsi());
+
+ dcm(0, 0) = cosThe * cosPsi;
+ dcm(0, 1) = -cosPhi * sinPsi + sinPhi * sinThe * cosPsi;
+ dcm(0, 2) = sinPhi * sinPsi + cosPhi * sinThe * cosPsi;
+
+ dcm(1, 0) = cosThe * sinPsi;
+ dcm(1, 1) = cosPhi * cosPsi + sinPhi * sinThe * sinPsi;
+ dcm(1, 2) = -sinPhi * cosPsi + cosPhi * sinThe * sinPsi;
+
+ dcm(2, 0) = -sinThe;
+ dcm(2, 1) = sinPhi * cosThe;
+ dcm(2, 2) = cosPhi * cosThe;
+}
+
+Dcm::Dcm(const Dcm &right) :
+ Matrix(right)
+{
+}
+
+Dcm::Dcm(const Matrix &right) :
+ Matrix(right)
+{
+}
+
+Dcm::~Dcm()
+{
+}
+
+int __EXPORT dcmTest()
+{
+ printf("Test DCM\t\t: ");
+ // default ctor
+ ASSERT(matrixEqual(Dcm(),
+ Matrix::identity(3)));
+ // quaternion ctor
+ ASSERT(matrixEqual(
+ Dcm(Quaternion(0.983347f, 0.034271f, 0.106021f, 0.143572f)),
+ Dcm(0.9362934f, -0.2750958f, 0.2183507f,
+ 0.2896295f, 0.9564251f, -0.0369570f,
+ -0.1986693f, 0.0978434f, 0.9751703f)));
+ // euler angle ctor
+ ASSERT(matrixEqual(
+ Dcm(EulerAngles(0.1f, 0.2f, 0.3f)),
+ Dcm(0.9362934f, -0.2750958f, 0.2183507f,
+ 0.2896295f, 0.9564251f, -0.0369570f,
+ -0.1986693f, 0.0978434f, 0.9751703f)));
+ // rotations
+ Vector3 vB(1, 2, 3);
+ ASSERT(vectorEqual(Vector3(-2.0f, 1.0f, 3.0f),
+ Dcm(EulerAngles(0.0f, 0.0f, M_PI_2_F))*vB));
+ ASSERT(vectorEqual(Vector3(3.0f, 2.0f, -1.0f),
+ Dcm(EulerAngles(0.0f, M_PI_2_F, 0.0f))*vB));
+ ASSERT(vectorEqual(Vector3(1.0f, -3.0f, 2.0f),
+ Dcm(EulerAngles(M_PI_2_F, 0.0f, 0.0f))*vB));
+ ASSERT(vectorEqual(Vector3(3.0f, 2.0f, -1.0f),
+ Dcm(EulerAngles(
+ M_PI_2_F, M_PI_2_F, M_PI_2_F))*vB));
+ printf("PASS\n");
+ return 0;
+}
+} // namespace math
diff --git a/src/lib/mathlib/math/Dcm.hpp b/src/lib/mathlib/math/Dcm.hpp
new file mode 100644
index 000000000..38f697c15
--- /dev/null
+++ b/src/lib/mathlib/math/Dcm.hpp
@@ -0,0 +1,113 @@
+/****************************************************************************
+ *
+ * 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 Dcm.hpp
+ *
+ * math direction cosine matrix
+ */
+
+//#pragma once
+
+#include "Vector.hpp"
+#include "Matrix.hpp"
+
+namespace math
+{
+
+class Quaternion;
+class EulerAngles;
+
+/**
+ * This is a Tait Bryan, Body 3-2-1 sequence.
+ * (yaw)-(pitch)-(roll)
+ * The Dcm transforms a vector in the body frame
+ * to the navigation frame, typically represented
+ * as C_nb. C_bn can be obtained through use
+ * of the transpose() method.
+ */
+class __EXPORT Dcm : public Matrix
+{
+public:
+ /**
+ * default ctor
+ */
+ Dcm();
+
+ /**
+ * scalar ctor
+ */
+ Dcm(float c00, float c01, float c02,
+ float c10, float c11, float c12,
+ float c20, float c21, float c22);
+
+ /**
+ * data ctor
+ */
+ Dcm(const float *data);
+
+ /**
+ * array ctor
+ */
+ Dcm(const float data[3][3]);
+
+ /**
+ * quaternion ctor
+ */
+ Dcm(const Quaternion &q);
+
+ /**
+ * euler angles ctor
+ */
+ Dcm(const EulerAngles &euler);
+
+ /**
+ * copy ctor (deep)
+ */
+ Dcm(const Dcm &right);
+
+ /**
+ * copy ctor (deep)
+ */
+ Dcm(const Matrix &right);
+
+ /**
+ * dtor
+ */
+ virtual ~Dcm();
+};
+
+int __EXPORT dcmTest();
+
+} // math
+
diff --git a/src/lib/mathlib/math/EulerAngles.cpp b/src/lib/mathlib/math/EulerAngles.cpp
new file mode 100644
index 000000000..e733d23bb
--- /dev/null
+++ b/src/lib/mathlib/math/EulerAngles.cpp
@@ -0,0 +1,126 @@
+/****************************************************************************
+ *
+ * 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 Vector.cpp
+ *
+ * math vector
+ */
+
+#include "test/test.hpp"
+
+#include "EulerAngles.hpp"
+#include "Quaternion.hpp"
+#include "Dcm.hpp"
+#include "Vector3.hpp"
+
+namespace math
+{
+
+EulerAngles::EulerAngles() :
+ Vector(3)
+{
+ setPhi(0.0f);
+ setTheta(0.0f);
+ setPsi(0.0f);
+}
+
+EulerAngles::EulerAngles(float phi, float theta, float psi) :
+ Vector(3)
+{
+ setPhi(phi);
+ setTheta(theta);
+ setPsi(psi);
+}
+
+EulerAngles::EulerAngles(const Quaternion &q) :
+ Vector(3)
+{
+ (*this) = EulerAngles(Dcm(q));
+}
+
+EulerAngles::EulerAngles(const Dcm &dcm) :
+ Vector(3)
+{
+ setTheta(asinf(-dcm(2, 0)));
+
+ if (fabsf(getTheta() - M_PI_2_F) < 1.0e-3f) {
+ setPhi(0.0f);
+ setPsi(atan2f(dcm(1, 2) - dcm(0, 1),
+ dcm(0, 2) + dcm(1, 1)) + getPhi());
+
+ } else if (fabsf(getTheta() + M_PI_2_F) < 1.0e-3f) {
+ setPhi(0.0f);
+ setPsi(atan2f(dcm(1, 2) - dcm(0, 1),
+ dcm(0, 2) + dcm(1, 1)) - getPhi());
+
+ } else {
+ setPhi(atan2f(dcm(2, 1), dcm(2, 2)));
+ setPsi(atan2f(dcm(1, 0), dcm(0, 0)));
+ }
+}
+
+EulerAngles::~EulerAngles()
+{
+}
+
+int __EXPORT eulerAnglesTest()
+{
+ printf("Test EulerAngles\t: ");
+ EulerAngles euler(0.1f, 0.2f, 0.3f);
+
+ // test ctor
+ ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
+ ASSERT(equal(euler.getPhi(), 0.1f));
+ ASSERT(equal(euler.getTheta(), 0.2f));
+ ASSERT(equal(euler.getPsi(), 0.3f));
+
+ // test dcm ctor
+ euler = Dcm(EulerAngles(0.1f, 0.2f, 0.3f));
+ ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
+
+ // test quat ctor
+ euler = Quaternion(EulerAngles(0.1f, 0.2f, 0.3f));
+ ASSERT(vectorEqual(Vector3(0.1f, 0.2f, 0.3f), euler));
+
+ // test assignment
+ euler.setPhi(0.4f);
+ euler.setTheta(0.5f);
+ euler.setPsi(0.6f);
+ ASSERT(vectorEqual(Vector3(0.4f, 0.5f, 0.6f), euler));
+
+ printf("PASS\n");
+ return 0;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/EulerAngles.hpp b/src/lib/mathlib/math/EulerAngles.hpp
new file mode 100644
index 000000000..399eecfa7
--- /dev/null
+++ b/src/lib/mathlib/math/EulerAngles.hpp
@@ -0,0 +1,74 @@
+/****************************************************************************
+ *
+ * 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 Vector.h
+ *
+ * math vector
+ */
+
+#pragma once
+
+#include "Vector.hpp"
+
+namespace math
+{
+
+class Quaternion;
+class Dcm;
+
+class __EXPORT EulerAngles : public Vector
+{
+public:
+ EulerAngles();
+ EulerAngles(float phi, float theta, float psi);
+ EulerAngles(const Quaternion &q);
+ EulerAngles(const Dcm &dcm);
+ virtual ~EulerAngles();
+
+ // alias
+ void setPhi(float phi) { (*this)(0) = phi; }
+ void setTheta(float theta) { (*this)(1) = theta; }
+ void setPsi(float psi) { (*this)(2) = psi; }
+
+ // const accessors
+ const float &getPhi() const { return (*this)(0); }
+ const float &getTheta() const { return (*this)(1); }
+ const float &getPsi() const { return (*this)(2); }
+
+};
+
+int __EXPORT eulerAnglesTest();
+
+} // math
+
diff --git a/src/lib/mathlib/math/Limits.cpp b/src/lib/mathlib/math/Limits.cpp
new file mode 100644
index 000000000..d4c892d8a
--- /dev/null
+++ b/src/lib/mathlib/math/Limits.cpp
@@ -0,0 +1,146 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 Limits.cpp
+ *
+ * Limiting / constrain helper functions
+ */
+
+
+#include <math.h>
+#include <stdint.h>
+
+#include "Limits.hpp"
+
+
+namespace math {
+
+
+float __EXPORT min(float val1, float val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+int __EXPORT min(int val1, int val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+unsigned __EXPORT min(unsigned val1, unsigned val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+uint64_t __EXPORT min(uint64_t val1, uint64_t val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+double __EXPORT min(double val1, double val2)
+{
+ return (val1 < val2) ? val1 : val2;
+}
+
+float __EXPORT max(float val1, float val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
+int __EXPORT max(int val1, int val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
+unsigned __EXPORT max(unsigned val1, unsigned val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
+uint64_t __EXPORT max(uint64_t val1, uint64_t val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
+double __EXPORT max(double val1, double val2)
+{
+ return (val1 > val2) ? val1 : val2;
+}
+
+
+float __EXPORT constrain(float val, float min, float max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
+int __EXPORT constrain(int val, int min, int max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
+unsigned __EXPORT constrain(unsigned val, unsigned min, unsigned max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
+uint64_t __EXPORT constrain(uint64_t val, uint64_t min, uint64_t max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
+double __EXPORT constrain(double val, double min, double max)
+{
+ return (val < min) ? min : ((val > max) ? max : val);
+}
+
+float __EXPORT radians(float degrees)
+{
+ return (degrees / 180.0f) * M_PI_F;
+}
+
+double __EXPORT radians(double degrees)
+{
+ return (degrees / 180.0) * M_PI;
+}
+
+float __EXPORT degrees(float radians)
+{
+ return (radians / M_PI_F) * 180.0f;
+}
+
+double __EXPORT degrees(double radians)
+{
+ return (radians / M_PI) * 180.0;
+}
+
+} \ No newline at end of file
diff --git a/src/lib/mathlib/math/Limits.hpp b/src/lib/mathlib/math/Limits.hpp
new file mode 100644
index 000000000..fb778dd66
--- /dev/null
+++ b/src/lib/mathlib/math/Limits.hpp
@@ -0,0 +1,87 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 Limits.hpp
+ *
+ * Limiting / constrain helper functions
+ */
+
+#pragma once
+
+#include <nuttx/config.h>
+#include <stdint.h>
+
+namespace math {
+
+
+float __EXPORT min(float val1, float val2);
+
+int __EXPORT min(int val1, int val2);
+
+unsigned __EXPORT min(unsigned val1, unsigned val2);
+
+uint64_t __EXPORT min(uint64_t val1, uint64_t val2);
+
+double __EXPORT min(double val1, double val2);
+
+float __EXPORT max(float val1, float val2);
+
+int __EXPORT max(int val1, int val2);
+
+unsigned __EXPORT max(unsigned val1, unsigned val2);
+
+uint64_t __EXPORT max(uint64_t val1, uint64_t val2);
+
+double __EXPORT max(double val1, double val2);
+
+
+float __EXPORT constrain(float val, float min, float max);
+
+int __EXPORT constrain(int val, int min, int max);
+
+unsigned __EXPORT constrain(unsigned val, unsigned min, unsigned max);
+
+uint64_t __EXPORT constrain(uint64_t val, uint64_t min, uint64_t max);
+
+double __EXPORT constrain(double val, double min, double max);
+
+float __EXPORT radians(float degrees);
+
+double __EXPORT radians(double degrees);
+
+float __EXPORT degrees(float radians);
+
+double __EXPORT degrees(double radians);
+
+} \ No newline at end of file
diff --git a/src/lib/mathlib/math/Matrix.cpp b/src/lib/mathlib/math/Matrix.cpp
new file mode 100644
index 000000000..ebd1aeda3
--- /dev/null
+++ b/src/lib/mathlib/math/Matrix.cpp
@@ -0,0 +1,193 @@
+/****************************************************************************
+ *
+ * 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 Matrix.cpp
+ *
+ * matrix code
+ */
+
+#include "test/test.hpp"
+#include <math.h>
+
+#include "Matrix.hpp"
+
+namespace math
+{
+
+static const float data_testA[] = {
+ 1, 2, 3,
+ 4, 5, 6
+};
+static Matrix testA(2, 3, data_testA);
+
+static const float data_testB[] = {
+ 0, 1, 3,
+ 7, -1, 2
+};
+static Matrix testB(2, 3, data_testB);
+
+static const float data_testC[] = {
+ 0, 1,
+ 2, 1,
+ 3, 2
+};
+static Matrix testC(3, 2, data_testC);
+
+static const float data_testD[] = {
+ 0, 1, 2,
+ 2, 1, 4,
+ 5, 2, 0
+};
+static Matrix testD(3, 3, data_testD);
+
+static const float data_testE[] = {
+ 1, -1, 2,
+ 0, 2, 3,
+ 2, -1, 1
+};
+static Matrix testE(3, 3, data_testE);
+
+static const float data_testF[] = {
+ 3.777e006f, 2.915e007f, 0.000e000f,
+ 2.938e007f, 2.267e008f, 0.000e000f,
+ 0.000e000f, 0.000e000f, 6.033e008f
+};
+static Matrix testF(3, 3, data_testF);
+
+int __EXPORT matrixTest()
+{
+ matrixAddTest();
+ matrixSubTest();
+ matrixMultTest();
+ matrixInvTest();
+ matrixDivTest();
+ return 0;
+}
+
+int matrixAddTest()
+{
+ printf("Test Matrix Add\t\t: ");
+ Matrix r = testA + testB;
+ float data_test[] = {
+ 1.0f, 3.0f, 6.0f,
+ 11.0f, 4.0f, 8.0f
+ };
+ ASSERT(matrixEqual(Matrix(2, 3, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+int matrixSubTest()
+{
+ printf("Test Matrix Sub\t\t: ");
+ Matrix r = testA - testB;
+ float data_test[] = {
+ 1.0f, 1.0f, 0.0f,
+ -3.0f, 6.0f, 4.0f
+ };
+ ASSERT(matrixEqual(Matrix(2, 3, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+int matrixMultTest()
+{
+ printf("Test Matrix Mult\t: ");
+ Matrix r = testC * testB;
+ float data_test[] = {
+ 7.0f, -1.0f, 2.0f,
+ 7.0f, 1.0f, 8.0f,
+ 14.0f, 1.0f, 13.0f
+ };
+ ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+int matrixInvTest()
+{
+ printf("Test Matrix Inv\t\t: ");
+ Matrix origF = testF;
+ Matrix r = testF.inverse();
+ float data_test[] = {
+ -0.0012518f, 0.0001610f, 0.0000000f,
+ 0.0001622f, -0.0000209f, 0.0000000f,
+ 0.0000000f, 0.0000000f, 1.6580e-9f
+ };
+ ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
+ // make sure F in unchanged
+ ASSERT(matrixEqual(origF, testF));
+ printf("PASS\n");
+ return 0;
+}
+
+int matrixDivTest()
+{
+ printf("Test Matrix Div\t\t: ");
+ Matrix r = testD / testE;
+ float data_test[] = {
+ 0.2222222f, 0.5555556f, -0.1111111f,
+ 0.0f, 1.0f, 1.0,
+ -4.1111111f, 1.2222222f, 4.5555556f
+ };
+ ASSERT(matrixEqual(Matrix(3, 3, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+bool matrixEqual(const Matrix &a, const Matrix &b, float eps)
+{
+ if (a.getRows() != b.getRows()) {
+ printf("row number not equal a: %d, b:%d\n", a.getRows(), b.getRows());
+ return false;
+
+ } else if (a.getCols() != b.getCols()) {
+ printf("column number not equal a: %d, b:%d\n", a.getCols(), b.getCols());
+ return false;
+ }
+
+ bool ret = true;
+
+ for (size_t i = 0; i < a.getRows(); i++)
+ for (size_t j = 0; j < a.getCols(); j++) {
+ if (!equal(a(i, j), b(i, j), eps)) {
+ printf("element mismatch (%d, %d)\n", i, j);
+ ret = false;
+ }
+ }
+
+ return ret;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/Matrix.hpp b/src/lib/mathlib/math/Matrix.hpp
new file mode 100644
index 000000000..f19db15ec
--- /dev/null
+++ b/src/lib/mathlib/math/Matrix.hpp
@@ -0,0 +1,61 @@
+/****************************************************************************
+ *
+ * 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 Matrix.h
+ *
+ * matrix code
+ */
+
+#pragma once
+
+#include <nuttx/config.h>
+
+#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
+#include "arm/Matrix.hpp"
+#else
+#include "generic/Matrix.hpp"
+#endif
+
+namespace math
+{
+class Matrix;
+int matrixTest();
+int matrixAddTest();
+int matrixSubTest();
+int matrixMultTest();
+int matrixInvTest();
+int matrixDivTest();
+int matrixArmTest();
+bool matrixEqual(const Matrix &a, const Matrix &b, float eps = 1.0e-5f);
+} // namespace math
diff --git a/src/lib/mathlib/math/Quaternion.cpp b/src/lib/mathlib/math/Quaternion.cpp
new file mode 100644
index 000000000..02fec4ca6
--- /dev/null
+++ b/src/lib/mathlib/math/Quaternion.cpp
@@ -0,0 +1,174 @@
+/****************************************************************************
+ *
+ * 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 Quaternion.cpp
+ *
+ * math vector
+ */
+
+#include "test/test.hpp"
+
+
+#include "Quaternion.hpp"
+#include "Dcm.hpp"
+#include "EulerAngles.hpp"
+
+namespace math
+{
+
+Quaternion::Quaternion() :
+ Vector(4)
+{
+ setA(1.0f);
+ setB(0.0f);
+ setC(0.0f);
+ setD(0.0f);
+}
+
+Quaternion::Quaternion(float a, float b,
+ float c, float d) :
+ Vector(4)
+{
+ setA(a);
+ setB(b);
+ setC(c);
+ setD(d);
+}
+
+Quaternion::Quaternion(const float *data) :
+ Vector(4, data)
+{
+}
+
+Quaternion::Quaternion(const Vector &v) :
+ Vector(v)
+{
+}
+
+Quaternion::Quaternion(const Dcm &dcm) :
+ Vector(4)
+{
+ // avoiding singularities by not using
+ // division equations
+ setA(0.5 * sqrt(1.0 +
+ double(dcm(0, 0) + dcm(1, 1) + dcm(2, 2))));
+ setB(0.5 * sqrt(1.0 +
+ double(dcm(0, 0) - dcm(1, 1) - dcm(2, 2))));
+ setC(0.5 * sqrt(1.0 +
+ double(-dcm(0, 0) + dcm(1, 1) - dcm(2, 2))));
+ setD(0.5 * sqrt(1.0 +
+ double(-dcm(0, 0) - dcm(1, 1) + dcm(2, 2))));
+}
+
+Quaternion::Quaternion(const EulerAngles &euler) :
+ Vector(4)
+{
+ double cosPhi_2 = cos(double(euler.getPhi()) / 2.0);
+ double sinPhi_2 = sin(double(euler.getPhi()) / 2.0);
+ double cosTheta_2 = cos(double(euler.getTheta()) / 2.0);
+ double sinTheta_2 = sin(double(euler.getTheta()) / 2.0);
+ double cosPsi_2 = cos(double(euler.getPsi()) / 2.0);
+ double sinPsi_2 = sin(double(euler.getPsi()) / 2.0);
+ setA(cosPhi_2 * cosTheta_2 * cosPsi_2 +
+ sinPhi_2 * sinTheta_2 * sinPsi_2);
+ setB(sinPhi_2 * cosTheta_2 * cosPsi_2 -
+ cosPhi_2 * sinTheta_2 * sinPsi_2);
+ setC(cosPhi_2 * sinTheta_2 * cosPsi_2 +
+ sinPhi_2 * cosTheta_2 * sinPsi_2);
+ setD(cosPhi_2 * cosTheta_2 * sinPsi_2 -
+ sinPhi_2 * sinTheta_2 * cosPsi_2);
+}
+
+Quaternion::Quaternion(const Quaternion &right) :
+ Vector(right)
+{
+}
+
+Quaternion::~Quaternion()
+{
+}
+
+Vector Quaternion::derivative(const Vector &w)
+{
+#ifdef QUATERNION_ASSERT
+ ASSERT(w.getRows() == 3);
+#endif
+ float dataQ[] = {
+ getA(), -getB(), -getC(), -getD(),
+ getB(), getA(), -getD(), getC(),
+ getC(), getD(), getA(), -getB(),
+ getD(), -getC(), getB(), getA()
+ };
+ Vector v(4);
+ v(0) = 0.0f;
+ v(1) = w(0);
+ v(2) = w(1);
+ v(3) = w(2);
+ Matrix Q(4, 4, dataQ);
+ return Q * v * 0.5f;
+}
+
+int __EXPORT quaternionTest()
+{
+ printf("Test Quaternion\t\t: ");
+ // test default ctor
+ Quaternion q;
+ ASSERT(equal(q.getA(), 1.0f));
+ ASSERT(equal(q.getB(), 0.0f));
+ ASSERT(equal(q.getC(), 0.0f));
+ ASSERT(equal(q.getD(), 0.0f));
+ // test float ctor
+ q = Quaternion(0.1825742f, 0.3651484f, 0.5477226f, 0.7302967f);
+ ASSERT(equal(q.getA(), 0.1825742f));
+ ASSERT(equal(q.getB(), 0.3651484f));
+ ASSERT(equal(q.getC(), 0.5477226f));
+ ASSERT(equal(q.getD(), 0.7302967f));
+ // test euler ctor
+ q = Quaternion(EulerAngles(0.1f, 0.2f, 0.3f));
+ ASSERT(vectorEqual(q, Quaternion(0.983347f, 0.034271f, 0.106021f, 0.143572f)));
+ // test dcm ctor
+ q = Quaternion(Dcm());
+ ASSERT(vectorEqual(q, Quaternion(1.0f, 0.0f, 0.0f, 0.0f)));
+ // TODO test derivative
+ // test accessors
+ q.setA(0.1f);
+ q.setB(0.2f);
+ q.setC(0.3f);
+ q.setD(0.4f);
+ ASSERT(vectorEqual(q, Quaternion(0.1f, 0.2f, 0.3f, 0.4f)));
+ printf("PASS\n");
+ return 0;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/Quaternion.hpp b/src/lib/mathlib/math/Quaternion.hpp
new file mode 100644
index 000000000..048a55d33
--- /dev/null
+++ b/src/lib/mathlib/math/Quaternion.hpp
@@ -0,0 +1,115 @@
+/****************************************************************************
+ *
+ * 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 Quaternion.hpp
+ *
+ * math quaternion lib
+ */
+
+#pragma once
+
+#include "Vector.hpp"
+#include "Matrix.hpp"
+
+namespace math
+{
+
+class Dcm;
+class EulerAngles;
+
+class __EXPORT Quaternion : public Vector
+{
+public:
+
+ /**
+ * default ctor
+ */
+ Quaternion();
+
+ /**
+ * ctor from floats
+ */
+ Quaternion(float a, float b, float c, float d);
+
+ /**
+ * ctor from data
+ */
+ Quaternion(const float *data);
+
+ /**
+ * ctor from Vector
+ */
+ Quaternion(const Vector &v);
+
+ /**
+ * ctor from EulerAngles
+ */
+ Quaternion(const EulerAngles &euler);
+
+ /**
+ * ctor from Dcm
+ */
+ Quaternion(const Dcm &dcm);
+
+ /**
+ * deep copy ctor
+ */
+ Quaternion(const Quaternion &right);
+
+ /**
+ * dtor
+ */
+ virtual ~Quaternion();
+
+ /**
+ * derivative
+ */
+ Vector derivative(const Vector &w);
+
+ /**
+ * accessors
+ */
+ void setA(float a) { (*this)(0) = a; }
+ void setB(float b) { (*this)(1) = b; }
+ void setC(float c) { (*this)(2) = c; }
+ void setD(float d) { (*this)(3) = d; }
+ const float &getA() const { return (*this)(0); }
+ const float &getB() const { return (*this)(1); }
+ const float &getC() const { return (*this)(2); }
+ const float &getD() const { return (*this)(3); }
+};
+
+int __EXPORT quaternionTest();
+} // math
+
diff --git a/src/lib/mathlib/math/Vector.cpp b/src/lib/mathlib/math/Vector.cpp
new file mode 100644
index 000000000..35158a396
--- /dev/null
+++ b/src/lib/mathlib/math/Vector.cpp
@@ -0,0 +1,100 @@
+/****************************************************************************
+ *
+ * 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 Vector.cpp
+ *
+ * math vector
+ */
+
+#include "test/test.hpp"
+
+#include "Vector.hpp"
+
+namespace math
+{
+
+static const float data_testA[] = {1, 3};
+static const float data_testB[] = {4, 1};
+
+static Vector testA(2, data_testA);
+static Vector testB(2, data_testB);
+
+int __EXPORT vectorTest()
+{
+ vectorAddTest();
+ vectorSubTest();
+ return 0;
+}
+
+int vectorAddTest()
+{
+ printf("Test Vector Add\t\t: ");
+ Vector r = testA + testB;
+ float data_test[] = {5.0f, 4.0f};
+ ASSERT(vectorEqual(Vector(2, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+int vectorSubTest()
+{
+ printf("Test Vector Sub\t\t: ");
+ Vector r(2);
+ r = testA - testB;
+ float data_test[] = { -3.0f, 2.0f};
+ ASSERT(vectorEqual(Vector(2, data_test), r));
+ printf("PASS\n");
+ return 0;
+}
+
+bool vectorEqual(const Vector &a, const Vector &b, float eps)
+{
+ if (a.getRows() != b.getRows()) {
+ printf("row number not equal a: %d, b:%d\n", a.getRows(), b.getRows());
+ return false;
+ }
+
+ bool ret = true;
+
+ for (size_t i = 0; i < a.getRows(); i++) {
+ if (!equal(a(i), b(i), eps)) {
+ printf("element mismatch (%d)\n", i);
+ ret = false;
+ }
+ }
+
+ return ret;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/Vector.hpp b/src/lib/mathlib/math/Vector.hpp
new file mode 100644
index 000000000..73de793d5
--- /dev/null
+++ b/src/lib/mathlib/math/Vector.hpp
@@ -0,0 +1,57 @@
+/****************************************************************************
+ *
+ * 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 Vector.h
+ *
+ * math vector
+ */
+
+#pragma once
+
+#include <nuttx/config.h>
+
+#if defined(CONFIG_ARCH_CORTEXM4) && defined(CONFIG_ARCH_FPU)
+#include "arm/Vector.hpp"
+#else
+#include "generic/Vector.hpp"
+#endif
+
+namespace math
+{
+class Vector;
+int __EXPORT vectorTest();
+int __EXPORT vectorAddTest();
+int __EXPORT vectorSubTest();
+bool vectorEqual(const Vector &a, const Vector &b, float eps = 1.0e-5f);
+} // math
diff --git a/src/lib/mathlib/math/Vector2f.cpp b/src/lib/mathlib/math/Vector2f.cpp
new file mode 100644
index 000000000..68e741817
--- /dev/null
+++ b/src/lib/mathlib/math/Vector2f.cpp
@@ -0,0 +1,103 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 Vector2f.cpp
+ *
+ * math vector
+ */
+
+#include "test/test.hpp"
+
+#include "Vector2f.hpp"
+
+namespace math
+{
+
+Vector2f::Vector2f() :
+ Vector(2)
+{
+}
+
+Vector2f::Vector2f(const Vector &right) :
+ Vector(right)
+{
+#ifdef VECTOR_ASSERT
+ ASSERT(right.getRows() == 2);
+#endif
+}
+
+Vector2f::Vector2f(float x, float y) :
+ Vector(2)
+{
+ setX(x);
+ setY(y);
+}
+
+Vector2f::Vector2f(const float *data) :
+ Vector(2, data)
+{
+}
+
+Vector2f::~Vector2f()
+{
+}
+
+float Vector2f::cross(const Vector2f &b) const
+{
+ const Vector2f &a = *this;
+ return a(0)*b(1) - a(1)*b(0);
+}
+
+float Vector2f::operator %(const Vector2f &v) const
+{
+ return cross(v);
+}
+
+float Vector2f::operator *(const Vector2f &v) const
+{
+ return dot(v);
+}
+
+int __EXPORT vector2fTest()
+{
+ printf("Test Vector2f\t\t: ");
+ // test float ctor
+ Vector2f v(1, 2);
+ ASSERT(equal(v(0), 1));
+ ASSERT(equal(v(1), 2));
+ printf("PASS\n");
+ return 0;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/Vector2f.hpp b/src/lib/mathlib/math/Vector2f.hpp
new file mode 100644
index 000000000..ecd62e81c
--- /dev/null
+++ b/src/lib/mathlib/math/Vector2f.hpp
@@ -0,0 +1,79 @@
+/****************************************************************************
+ *
+ * Copyright (c) 2013 PX4 Development Team. All rights reserved.
+ *
+ * Redistribution and use in source and binary forms, with or without
+ * modification, are permitted provided that the following conditions
+ * 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 Vector2f.hpp
+ *
+ * math 3 vector
+ */
+
+#pragma once
+
+#include "Vector.hpp"
+
+namespace math
+{
+
+class __EXPORT Vector2f :
+ public Vector
+{
+public:
+ Vector2f();
+ Vector2f(const Vector &right);
+ Vector2f(float x, float y);
+ Vector2f(const float *data);
+ virtual ~Vector2f();
+ float cross(const Vector2f &b) const;
+ float operator %(const Vector2f &v) const;
+ float operator *(const Vector2f &v) const;
+ inline Vector2f operator*(const float &right) const {
+ return Vector::operator*(right);
+ }
+
+ /**
+ * accessors
+ */
+ void setX(float x) { (*this)(0) = x; }
+ void setY(float y) { (*this)(1) = y; }
+ const float &getX() const { return (*this)(0); }
+ const float &getY() const { return (*this)(1); }
+};
+
+class __EXPORT Vector2 :
+ public Vector2f
+{
+};
+
+int __EXPORT vector2fTest();
+} // math
+
diff --git a/src/lib/mathlib/math/Vector3.cpp b/src/lib/mathlib/math/Vector3.cpp
new file mode 100644
index 000000000..3936650c6
--- /dev/null
+++ b/src/lib/mathlib/math/Vector3.cpp
@@ -0,0 +1,109 @@
+/****************************************************************************
+ *
+ * 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 Vector3.cpp
+ *
+ * math vector
+ */
+
+#include "test/test.hpp"
+
+#include "Vector3.hpp"
+
+namespace math
+{
+
+Vector3::Vector3() :
+ Vector(3)
+{
+}
+
+Vector3::Vector3(const Vector &right) :
+ Vector(right)
+{
+#ifdef VECTOR_ASSERT
+ ASSERT(right.getRows() == 3);
+#endif
+}
+
+Vector3::Vector3(float x, float y, float z) :
+ Vector(3)
+{
+ setX(x);
+ setY(y);
+ setZ(z);
+}
+
+Vector3::Vector3(const float *data) :
+ Vector(3, data)
+{
+}
+
+Vector3::~Vector3()
+{
+}
+
+Vector3 Vector3::cross(const Vector3 &b) const
+{
+ const Vector3 &a = *this;
+ Vector3 result;
+ result(0) = a(1) * b(2) - a(2) * b(1);
+ result(1) = a(2) * b(0) - a(0) * b(2);
+ result(2) = a(0) * b(1) - a(1) * b(0);
+ return result;
+}
+
+Vector3 Vector3::operator %(const Vector3 &v) const
+{
+ return cross(v);
+}
+
+float Vector3::operator *(const Vector3 &v) const
+{
+ return dot(v);
+}
+
+int __EXPORT vector3Test()
+{
+ printf("Test Vector3\t\t: ");
+ // test float ctor
+ Vector3 v(1, 2, 3);
+ ASSERT(equal(v(0), 1));
+ ASSERT(equal(v(1), 2));
+ ASSERT(equal(v(2), 3));
+ printf("PASS\n");
+ return 0;
+}
+
+} // namespace math
diff --git a/src/lib/mathlib/math/Vector3.hpp b/src/lib/mathlib/math/Vector3.hpp
new file mode 100644
index 000000000..2bf00f26b
--- /dev/null
+++ b/src/lib/mathlib/math/Vector3.hpp
@@ -0,0 +1,78 @@
+/****************************************************************************
+ *
+ * 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 Vector3.hpp
+ *
+ * math 3 vector
+ */
+
+#pragma once
+
+#include "Vector.hpp"
+
+namespace math
+{
+
+class __EXPORT Vector3 :
+ public Vector
+{
+public:
+ Vector3();
+ Vector3(const Vector &right);
+ Vector3(float x, float y, float z);
+ Vector3(const float *data);
+ virtual ~Vector3();
+ Vector3 cross(const Vector3 &b) const;
+ Vector3 operator %(const Vector3 &v) const;
+ float operator *(const Vector3 &v) const;
+
+ /**
+ * accessors
+ */
+ void setX(float x) { (*this)(0) = x; }
+ void setY(float y) { (*this)(1) = y; }
+ void setZ(float z) { (*this)(2) = z; }
+ const float &getX() const { return (*this)(0); }
+ const float &getY() const { return (*this)(1); }
+ const float &getZ() const { return (*this)(2); }
+};
+
+class __EXPORT Vector3f :
+ public Vector3
+{
+};
+
+int __EXPORT vector3Test();
+} // math
+
diff --git a/src/lib/mathlib/math/arm/Matrix.cpp b/src/lib/mathlib/math/arm/Matrix.cpp
new file mode 100644
index 000000000..21661622a
--- /dev/null
+++ b/src/lib/mathlib/math/arm/Matrix.cpp
@@ -0,0 +1,40 @@
+/****************************************************************************
+ *
+ * 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 Matrix.cpp
+ *
+ * matrix code
+ */
+
+#include "Matrix.hpp"
diff --git a/src/lib/mathlib/math/arm/Matrix.hpp b/src/lib/mathlib/math/arm/Matrix.hpp
new file mode 100644
index 000000000..1945bb02d
--- /dev/null
+++ b/src/lib/mathlib/math/arm/Matrix.hpp
@@ -0,0 +1,292 @@
+/****************************************************************************
+ *
+ * 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 Matrix.h
+ *
+ * matrix code
+ */
+
+#pragma once
+
+
+#include <inttypes.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "../Vector.hpp"
+#include "../Matrix.hpp"
+
+// arm specific
+#include "../../CMSIS/Include/arm_math.h"
+
+namespace math
+{
+
+class __EXPORT Matrix
+{
+public:
+ // constructor
+ Matrix(size_t rows, size_t cols) :
+ _matrix() {
+ arm_mat_init_f32(&_matrix,
+ rows, cols,
+ (float *)calloc(rows * cols, sizeof(float)));
+ }
+ Matrix(size_t rows, size_t cols, const float *data) :
+ _matrix() {
+ arm_mat_init_f32(&_matrix,
+ rows, cols,
+ (float *)malloc(rows * cols * sizeof(float)));
+ memcpy(getData(), data, getSize());
+ }
+ // deconstructor
+ virtual ~Matrix() {
+ delete [] _matrix.pData;
+ }
+ // copy constructor (deep)
+ Matrix(const Matrix &right) :
+ _matrix() {
+ arm_mat_init_f32(&_matrix,
+ right.getRows(), right.getCols(),
+ (float *)malloc(right.getRows()*
+ right.getCols()*sizeof(float)));
+ memcpy(getData(), right.getData(),
+ getSize());
+ }
+ // assignment
+ inline Matrix &operator=(const Matrix &right) {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+
+ if (this != &right) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+
+ return *this;
+ }
+ // element accessors
+ inline float &operator()(size_t i, size_t j) {
+#ifdef MATRIX_ASSERT
+ ASSERT(i < getRows());
+ ASSERT(j < getCols());
+#endif
+ return getData()[i * getCols() + j];
+ }
+ inline const float &operator()(size_t i, size_t j) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(i < getRows());
+ ASSERT(j < getCols());
+#endif
+ return getData()[i * getCols() + j];
+ }
+ // output
+ inline void print() const {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ float sig;
+ int exponent;
+ float num = (*this)(i, j);
+ float2SigExp(num, sig, exponent);
+ printf("%6.3fe%03d ", (double)sig, exponent);
+ }
+
+ printf("\n");
+ }
+ }
+ // boolean ops
+ inline bool operator==(const Matrix &right) const {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ if (fabsf((*this)(i, j) - right(i, j)) > 1e-30f)
+ return false;
+ }
+ }
+
+ return true;
+ }
+ // scalar ops
+ inline Matrix operator+(float right) const {
+ Matrix result(getRows(), getCols());
+ arm_offset_f32((float *)getData(), right,
+ (float *)result.getData(), getRows()*getCols());
+ return result;
+ }
+ inline Matrix operator-(float right) const {
+ Matrix result(getRows(), getCols());
+ arm_offset_f32((float *)getData(), -right,
+ (float *)result.getData(), getRows()*getCols());
+ return result;
+ }
+ inline Matrix operator*(float right) const {
+ Matrix result(getRows(), getCols());
+ arm_mat_scale_f32(&_matrix, right,
+ &(result._matrix));
+ return result;
+ }
+ inline Matrix operator/(float right) const {
+ Matrix result(getRows(), getCols());
+ arm_mat_scale_f32(&_matrix, 1.0f / right,
+ &(result._matrix));
+ return result;
+ }
+ // vector ops
+ inline Vector operator*(const Vector &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getCols() == right.getRows());
+#endif
+ Matrix resultMat = (*this) *
+ Matrix(right.getRows(), 1, right.getData());
+ return Vector(getRows(), resultMat.getData());
+ }
+ // matrix ops
+ inline Matrix operator+(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+ Matrix result(getRows(), getCols());
+ arm_mat_add_f32(&_matrix, &(right._matrix),
+ &(result._matrix));
+ return result;
+ }
+ inline Matrix operator-(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+ Matrix result(getRows(), getCols());
+ arm_mat_sub_f32(&_matrix, &(right._matrix),
+ &(result._matrix));
+ return result;
+ }
+ inline Matrix operator*(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getCols() == right.getRows());
+#endif
+ Matrix result(getRows(), right.getCols());
+ arm_mat_mult_f32(&_matrix, &(right._matrix),
+ &(result._matrix));
+ return result;
+ }
+ inline Matrix operator/(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(right.getRows() == right.getCols());
+ ASSERT(getCols() == right.getCols());
+#endif
+ return (*this) * right.inverse();
+ }
+ // other functions
+ inline Matrix transpose() const {
+ Matrix result(getCols(), getRows());
+ arm_mat_trans_f32(&_matrix, &(result._matrix));
+ return result;
+ }
+ inline void swapRows(size_t a, size_t b) {
+ if (a == b) return;
+
+ for (size_t j = 0; j < getCols(); j++) {
+ float tmp = (*this)(a, j);
+ (*this)(a, j) = (*this)(b, j);
+ (*this)(b, j) = tmp;
+ }
+ }
+ inline void swapCols(size_t a, size_t b) {
+ if (a == b) return;
+
+ for (size_t i = 0; i < getRows(); i++) {
+ float tmp = (*this)(i, a);
+ (*this)(i, a) = (*this)(i, b);
+ (*this)(i, b) = tmp;
+ }
+ }
+ /**
+ * inverse based on LU factorization with partial pivotting
+ */
+ Matrix inverse() const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == getCols());
+#endif
+ Matrix result(getRows(), getCols());
+ Matrix work = (*this);
+ arm_mat_inverse_f32(&(work._matrix),
+ &(result._matrix));
+ return result;
+ }
+ inline void setAll(const float &val) {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ (*this)(i, j) = val;
+ }
+ }
+ }
+ inline void set(const float *data) {
+ memcpy(getData(), data, getSize());
+ }
+ inline size_t getRows() const { return _matrix.numRows; }
+ inline size_t getCols() const { return _matrix.numCols; }
+ inline static Matrix identity(size_t size) {
+ Matrix result(size, size);
+
+ for (size_t i = 0; i < size; i++) {
+ result(i, i) = 1.0f;
+ }
+
+ return result;
+ }
+ inline static Matrix zero(size_t size) {
+ Matrix result(size, size);
+ result.setAll(0.0f);
+ return result;
+ }
+ inline static Matrix zero(size_t m, size_t n) {
+ Matrix result(m, n);
+ result.setAll(0.0f);
+ return result;
+ }
+protected:
+ inline size_t getSize() const { return sizeof(float) * getRows() * getCols(); }
+ inline float *getData() { return _matrix.pData; }
+ inline const float *getData() const { return _matrix.pData; }
+ inline void setData(float *data) { _matrix.pData = data; }
+private:
+ arm_matrix_instance_f32 _matrix;
+};
+
+} // namespace math
diff --git a/src/lib/mathlib/math/arm/Vector.cpp b/src/lib/mathlib/math/arm/Vector.cpp
new file mode 100644
index 000000000..7ea6496bb
--- /dev/null
+++ b/src/lib/mathlib/math/arm/Vector.cpp
@@ -0,0 +1,40 @@
+/****************************************************************************
+ *
+ * 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 Vector.cpp
+ *
+ * math vector
+ */
+
+#include "Vector.hpp"
diff --git a/src/lib/mathlib/math/arm/Vector.hpp b/src/lib/mathlib/math/arm/Vector.hpp
new file mode 100644
index 000000000..a2526d0a2
--- /dev/null
+++ b/src/lib/mathlib/math/arm/Vector.hpp
@@ -0,0 +1,236 @@
+/****************************************************************************
+ *
+ * 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 Vector.h
+ *
+ * math vector
+ */
+
+#pragma once
+
+#include <inttypes.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "../Vector.hpp"
+#include "../test/test.hpp"
+
+// arm specific
+#include "../../CMSIS/Include/arm_math.h"
+
+namespace math
+{
+
+class __EXPORT Vector
+{
+public:
+ // constructor
+ Vector(size_t rows) :
+ _rows(rows),
+ _data((float *)calloc(rows, sizeof(float))) {
+ }
+ Vector(size_t rows, const float *data) :
+ _rows(rows),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), data, getSize());
+ }
+ // deconstructor
+ virtual ~Vector() {
+ delete [] getData();
+ }
+ // copy constructor (deep)
+ Vector(const Vector &right) :
+ _rows(right.getRows()),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+ // assignment
+ inline Vector &operator=(const Vector &right) {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+
+ if (this != &right) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+
+ return *this;
+ }
+ // element accessors
+ inline float &operator()(size_t i) {
+#ifdef VECTOR_ASSERT
+ ASSERT(i < getRows());
+#endif
+ return getData()[i];
+ }
+ inline const float &operator()(size_t i) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(i < getRows());
+#endif
+ return getData()[i];
+ }
+ // output
+ inline void print() const {
+ for (size_t i = 0; i < getRows(); i++) {
+ float sig;
+ int exponent;
+ float num = (*this)(i);
+ float2SigExp(num, sig, exponent);
+ printf("%6.3fe%03d ", (double)sig, exponent);
+ }
+
+ printf("\n");
+ }
+ // boolean ops
+ inline bool operator==(const Vector &right) const {
+ for (size_t i = 0; i < getRows(); i++) {
+ if (fabsf(((*this)(i) - right(i))) > 1e-30f)
+ return false;
+ }
+
+ return true;
+ }
+ // scalar ops
+ inline Vector operator+(float right) const {
+ Vector result(getRows());
+ arm_offset_f32((float *)getData(),
+ right, result.getData(),
+ getRows());
+ return result;
+ }
+ inline Vector operator-(float right) const {
+ Vector result(getRows());
+ arm_offset_f32((float *)getData(),
+ -right, result.getData(),
+ getRows());
+ return result;
+ }
+ inline Vector operator*(const float &right) const {
+ Vector result(getRows());
+ arm_scale_f32((float *)getData(),
+ right, result.getData(),
+ getRows());
+ return result;
+ }
+ inline Vector operator/(float right) const {
+ Vector result(getRows());
+ arm_scale_f32((float *)getData(),
+ 1.0f / right, result.getData(),
+ getRows());
+ return result;
+ }
+ // vector ops
+ inline Vector operator+(const Vector &right) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+ Vector result(getRows());
+ arm_add_f32((float *)getData(),
+ (float *)right.getData(),
+ result.getData(),
+ getRows());
+ return result;
+ }
+ inline Vector operator-(const Vector &right) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+ Vector result(getRows());
+ arm_sub_f32((float *)getData(),
+ (float *)right.getData(),
+ result.getData(),
+ getRows());
+ return result;
+ }
+ inline Vector operator-(void) const {
+ Vector result(getRows());
+ arm_negate_f32((float *)getData(),
+ result.getData(),
+ getRows());
+ return result;
+ }
+ // other functions
+ inline float dot(const Vector &right) const {
+ float result = 0;
+ arm_dot_prod_f32((float *)getData(),
+ (float *)right.getData(),
+ getRows(),
+ &result);
+ return result;
+ }
+ inline float norm() const {
+ return sqrtf(dot(*this));
+ }
+ inline float length() const {
+ return norm();
+ }
+ inline Vector unit() const {
+ return (*this) / norm();
+ }
+ inline Vector normalized() const {
+ return unit();
+ }
+ inline void normalize() {
+ (*this) = (*this) / norm();
+ }
+ inline static Vector zero(size_t rows) {
+ Vector result(rows);
+ // calloc returns zeroed memory
+ return result;
+ }
+ inline void setAll(const float &val) {
+ for (size_t i = 0; i < getRows(); i++) {
+ (*this)(i) = val;
+ }
+ }
+ inline void set(const float *data) {
+ memcpy(getData(), data, getSize());
+ }
+ inline size_t getRows() const { return _rows; }
+ inline const float *getData() const { return _data; }
+protected:
+ inline size_t getSize() const { return sizeof(float) * getRows(); }
+ inline float *getData() { return _data; }
+ inline void setData(float *data) { _data = data; }
+private:
+ size_t _rows;
+ float *_data;
+};
+
+} // math
diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.cpp b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp
new file mode 100644
index 000000000..efb17225d
--- /dev/null
+++ b/src/lib/mathlib/math/filter/LowPassFilter2p.cpp
@@ -0,0 +1,77 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+
+/****************************************************************************
+ *
+ * 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 LowPassFilter.cpp
+/// @brief A class to implement a second order low pass filter
+/// Author: Leonard Hall <LeonardTHall@gmail.com>
+
+#include "LowPassFilter2p.hpp"
+#include "math.h"
+
+namespace math
+{
+
+void LowPassFilter2p::set_cutoff_frequency(float sample_freq, float cutoff_freq)
+{
+ _cutoff_freq = cutoff_freq;
+ float fr = sample_freq/_cutoff_freq;
+ float ohm = tanf(M_PI_F/fr);
+ float c = 1.0f+2.0f*cosf(M_PI_F/4.0f)*ohm + ohm*ohm;
+ _b0 = ohm*ohm/c;
+ _b1 = 2.0f*_b0;
+ _b2 = _b0;
+ _a1 = 2.0f*(ohm*ohm-1.0f)/c;
+ _a2 = (1.0f-2.0f*cosf(M_PI_F/4.0f)*ohm+ohm*ohm)/c;
+}
+
+float LowPassFilter2p::apply(float sample)
+{
+ // do the filtering
+ float delay_element_0 = sample - _delay_element_1 * _a1 - _delay_element_2 * _a2;
+ if (isnan(delay_element_0) || isinf(delay_element_0)) {
+ // don't allow bad values to propogate via the filter
+ delay_element_0 = sample;
+ }
+ float output = delay_element_0 * _b0 + _delay_element_1 * _b1 + _delay_element_2 * _b2;
+
+ _delay_element_2 = _delay_element_1;
+ _delay_element_1 = delay_element_0;
+
+ // return the value. Should be no need to check limits
+ return output;
+}
+
+} // namespace math
+
diff --git a/src/lib/mathlib/math/filter/LowPassFilter2p.hpp b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp
new file mode 100644
index 000000000..208ec98d4
--- /dev/null
+++ b/src/lib/mathlib/math/filter/LowPassFilter2p.hpp
@@ -0,0 +1,78 @@
+// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
+
+/****************************************************************************
+ *
+ * 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 LowPassFilter.h
+/// @brief A class to implement a second order low pass filter
+/// Author: Leonard Hall <LeonardTHall@gmail.com>
+/// Adapted for PX4 by Andrew Tridgell
+
+#pragma once
+
+namespace math
+{
+class __EXPORT LowPassFilter2p
+{
+public:
+ // constructor
+ LowPassFilter2p(float sample_freq, float cutoff_freq) {
+ // set initial parameters
+ set_cutoff_frequency(sample_freq, cutoff_freq);
+ _delay_element_1 = _delay_element_2 = 0;
+ }
+
+ // change parameters
+ void set_cutoff_frequency(float sample_freq, float cutoff_freq);
+
+ // apply - Add a new raw value to the filter
+ // and retrieve the filtered result
+ float apply(float sample);
+
+ // return the cutoff frequency
+ float get_cutoff_freq(void) const {
+ return _cutoff_freq;
+ }
+
+private:
+ float _cutoff_freq;
+ float _a1;
+ float _a2;
+ float _b0;
+ float _b1;
+ float _b2;
+ float _delay_element_1; // buffered sample -1
+ float _delay_element_2; // buffered sample -2
+};
+
+} // namespace math
diff --git a/src/lib/mathlib/math/filter/module.mk b/src/lib/mathlib/math/filter/module.mk
new file mode 100644
index 000000000..f5c0647c8
--- /dev/null
+++ b/src/lib/mathlib/math/filter/module.mk
@@ -0,0 +1,43 @@
+############################################################################
+#
+# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# 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.
+#
+############################################################################
+
+#
+# filter library
+#
+SRCS = LowPassFilter2p.cpp
+
+#
+# In order to include .config we first have to save off the
+# current makefile name, since app.mk needs it.
+#
+APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
diff --git a/src/lib/mathlib/math/generic/Matrix.cpp b/src/lib/mathlib/math/generic/Matrix.cpp
new file mode 100644
index 000000000..21661622a
--- /dev/null
+++ b/src/lib/mathlib/math/generic/Matrix.cpp
@@ -0,0 +1,40 @@
+/****************************************************************************
+ *
+ * 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 Matrix.cpp
+ *
+ * matrix code
+ */
+
+#include "Matrix.hpp"
diff --git a/src/lib/mathlib/math/generic/Matrix.hpp b/src/lib/mathlib/math/generic/Matrix.hpp
new file mode 100644
index 000000000..5601a3447
--- /dev/null
+++ b/src/lib/mathlib/math/generic/Matrix.hpp
@@ -0,0 +1,437 @@
+/****************************************************************************
+ *
+ * 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 Matrix.h
+ *
+ * matrix code
+ */
+
+#pragma once
+
+
+#include <inttypes.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "../Vector.hpp"
+#include "../Matrix.hpp"
+
+namespace math
+{
+
+class __EXPORT Matrix
+{
+public:
+ // constructor
+ Matrix(size_t rows, size_t cols) :
+ _rows(rows),
+ _cols(cols),
+ _data((float *)calloc(rows *cols, sizeof(float))) {
+ }
+ Matrix(size_t rows, size_t cols, const float *data) :
+ _rows(rows),
+ _cols(cols),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), data, getSize());
+ }
+ // deconstructor
+ virtual ~Matrix() {
+ delete [] getData();
+ }
+ // copy constructor (deep)
+ Matrix(const Matrix &right) :
+ _rows(right.getRows()),
+ _cols(right.getCols()),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+ // assignment
+ inline Matrix &operator=(const Matrix &right) {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+
+ if (this != &right) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+
+ return *this;
+ }
+ // element accessors
+ inline float &operator()(size_t i, size_t j) {
+#ifdef MATRIX_ASSERT
+ ASSERT(i < getRows());
+ ASSERT(j < getCols());
+#endif
+ return getData()[i * getCols() + j];
+ }
+ inline const float &operator()(size_t i, size_t j) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(i < getRows());
+ ASSERT(j < getCols());
+#endif
+ return getData()[i * getCols() + j];
+ }
+ // output
+ inline void print() const {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ float sig;
+ int exp;
+ float num = (*this)(i, j);
+ float2SigExp(num, sig, exp);
+ printf("%6.3fe%03.3d,", (double)sig, exp);
+ }
+
+ printf("\n");
+ }
+ }
+ // boolean ops
+ inline bool operator==(const Matrix &right) const {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ if (fabsf((*this)(i, j) - right(i, j)) > 1e-30f)
+ return false;
+ }
+ }
+
+ return true;
+ }
+ // scalar ops
+ inline Matrix operator+(const float &right) const {
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) + right;
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator-(const float &right) const {
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) - right;
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator*(const float &right) const {
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) * right;
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator/(const float &right) const {
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) / right;
+ }
+ }
+
+ return result;
+ }
+ // vector ops
+ inline Vector operator*(const Vector &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getCols() == right.getRows());
+#endif
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i) += (*this)(i, j) * right(j);
+ }
+ }
+
+ return result;
+ }
+ // matrix ops
+ inline Matrix operator+(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) + right(i, j);
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator-(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == right.getRows());
+ ASSERT(getCols() == right.getCols());
+#endif
+ Matrix result(getRows(), getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(i, j) = (*this)(i, j) - right(i, j);
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator*(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getCols() == right.getRows());
+#endif
+ Matrix result(getRows(), right.getCols());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < right.getCols(); j++) {
+ for (size_t k = 0; k < right.getRows(); k++) {
+ result(i, j) += (*this)(i, k) * right(k, j);
+ }
+ }
+ }
+
+ return result;
+ }
+ inline Matrix operator/(const Matrix &right) const {
+#ifdef MATRIX_ASSERT
+ ASSERT(right.getRows() == right.getCols());
+ ASSERT(getCols() == right.getCols());
+#endif
+ return (*this) * right.inverse();
+ }
+ // other functions
+ inline Matrix transpose() const {
+ Matrix result(getCols(), getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ result(j, i) = (*this)(i, j);
+ }
+ }
+
+ return result;
+ }
+ inline void swapRows(size_t a, size_t b) {
+ if (a == b) return;
+
+ for (size_t j = 0; j < getCols(); j++) {
+ float tmp = (*this)(a, j);
+ (*this)(a, j) = (*this)(b, j);
+ (*this)(b, j) = tmp;
+ }
+ }
+ inline void swapCols(size_t a, size_t b) {
+ if (a == b) return;
+
+ for (size_t i = 0; i < getRows(); i++) {
+ float tmp = (*this)(i, a);
+ (*this)(i, a) = (*this)(i, b);
+ (*this)(i, b) = tmp;
+ }
+ }
+ /**
+ * inverse based on LU factorization with partial pivotting
+ */
+ Matrix inverse() const {
+#ifdef MATRIX_ASSERT
+ ASSERT(getRows() == getCols());
+#endif
+ size_t N = getRows();
+ Matrix L = identity(N);
+ const Matrix &A = (*this);
+ Matrix U = A;
+ Matrix P = identity(N);
+
+ //printf("A:\n"); A.print();
+
+ // for all diagonal elements
+ for (size_t n = 0; n < N; n++) {
+
+ // if diagonal is zero, swap with row below
+ if (fabsf(U(n, n)) < 1e-8f) {
+ //printf("trying pivot for row %d\n",n);
+ for (size_t i = 0; i < N; i++) {
+ if (i == n) continue;
+
+ //printf("\ttrying row %d\n",i);
+ if (fabsf(U(i, n)) > 1e-8f) {
+ //printf("swapped %d\n",i);
+ U.swapRows(i, n);
+ P.swapRows(i, n);
+ }
+ }
+ }
+
+#ifdef MATRIX_ASSERT
+ //printf("A:\n"); A.print();
+ //printf("U:\n"); U.print();
+ //printf("P:\n"); P.print();
+ //fflush(stdout);
+ ASSERT(fabsf(U(n, n)) > 1e-8f);
+#endif
+
+ // failsafe, return zero matrix
+ if (fabsf(U(n, n)) < 1e-8f) {
+ return Matrix::zero(n);
+ }
+
+ // for all rows below diagonal
+ for (size_t i = (n + 1); i < N; i++) {
+ L(i, n) = U(i, n) / U(n, n);
+
+ // add i-th row and n-th row
+ // multiplied by: -a(i,n)/a(n,n)
+ for (size_t k = n; k < N; k++) {
+ U(i, k) -= L(i, n) * U(n, k);
+ }
+ }
+ }
+
+ //printf("L:\n"); L.print();
+ //printf("U:\n"); U.print();
+
+ // solve LY=P*I for Y by forward subst
+ Matrix Y = P;
+
+ // for all columns of Y
+ for (size_t c = 0; c < N; c++) {
+ // for all rows of L
+ for (size_t i = 0; i < N; i++) {
+ // for all columns of L
+ for (size_t j = 0; j < i; j++) {
+ // for all existing y
+ // subtract the component they
+ // contribute to the solution
+ Y(i, c) -= L(i, j) * Y(j, c);
+ }
+
+ // divide by the factor
+ // on current
+ // term to be solved
+ // Y(i,c) /= L(i,i);
+ // but L(i,i) = 1.0
+ }
+ }
+
+ //printf("Y:\n"); Y.print();
+
+ // solve Ux=y for x by back subst
+ Matrix X = Y;
+
+ // for all columns of X
+ for (size_t c = 0; c < N; c++) {
+ // for all rows of U
+ for (size_t k = 0; k < N; k++) {
+ // have to go in reverse order
+ size_t i = N - 1 - k;
+
+ // for all columns of U
+ for (size_t j = i + 1; j < N; j++) {
+ // for all existing x
+ // subtract the component they
+ // contribute to the solution
+ X(i, c) -= U(i, j) * X(j, c);
+ }
+
+ // divide by the factor
+ // on current
+ // term to be solved
+ X(i, c) /= U(i, i);
+ }
+ }
+
+ //printf("X:\n"); X.print();
+ return X;
+ }
+ inline void setAll(const float &val) {
+ for (size_t i = 0; i < getRows(); i++) {
+ for (size_t j = 0; j < getCols(); j++) {
+ (*this)(i, j) = val;
+ }
+ }
+ }
+ inline void set(const float *data) {
+ memcpy(getData(), data, getSize());
+ }
+ inline size_t getRows() const { return _rows; }
+ inline size_t getCols() const { return _cols; }
+ inline static Matrix identity(size_t size) {
+ Matrix result(size, size);
+
+ for (size_t i = 0; i < size; i++) {
+ result(i, i) = 1.0f;
+ }
+
+ return result;
+ }
+ inline static Matrix zero(size_t size) {
+ Matrix result(size, size);
+ result.setAll(0.0f);
+ return result;
+ }
+ inline static Matrix zero(size_t m, size_t n) {
+ Matrix result(m, n);
+ result.setAll(0.0f);
+ return result;
+ }
+protected:
+ inline size_t getSize() const { return sizeof(float) * getRows() * getCols(); }
+ inline float *getData() { return _data; }
+ inline const float *getData() const { return _data; }
+ inline void setData(float *data) { _data = data; }
+private:
+ size_t _rows;
+ size_t _cols;
+ float *_data;
+};
+
+} // namespace math
diff --git a/src/lib/mathlib/math/generic/Vector.cpp b/src/lib/mathlib/math/generic/Vector.cpp
new file mode 100644
index 000000000..7ea6496bb
--- /dev/null
+++ b/src/lib/mathlib/math/generic/Vector.cpp
@@ -0,0 +1,40 @@
+/****************************************************************************
+ *
+ * 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 Vector.cpp
+ *
+ * math vector
+ */
+
+#include "Vector.hpp"
diff --git a/src/lib/mathlib/math/generic/Vector.hpp b/src/lib/mathlib/math/generic/Vector.hpp
new file mode 100644
index 000000000..8cfdc676d
--- /dev/null
+++ b/src/lib/mathlib/math/generic/Vector.hpp
@@ -0,0 +1,245 @@
+/****************************************************************************
+ *
+ * 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 Vector.h
+ *
+ * math vector
+ */
+
+#pragma once
+
+#include <inttypes.h>
+#include <assert.h>
+#include <stdlib.h>
+#include <string.h>
+#include <stdio.h>
+#include <math.h>
+
+#include "../Vector.hpp"
+
+namespace math
+{
+
+class __EXPORT Vector
+{
+public:
+ // constructor
+ Vector(size_t rows) :
+ _rows(rows),
+ _data((float *)calloc(rows, sizeof(float))) {
+ }
+ Vector(size_t rows, const float *data) :
+ _rows(rows),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), data, getSize());
+ }
+ // deconstructor
+ virtual ~Vector() {
+ delete [] getData();
+ }
+ // copy constructor (deep)
+ Vector(const Vector &right) :
+ _rows(right.getRows()),
+ _data((float *)malloc(getSize())) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+ // assignment
+ inline Vector &operator=(const Vector &right) {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+
+ if (this != &right) {
+ memcpy(getData(), right.getData(),
+ right.getSize());
+ }
+
+ return *this;
+ }
+ // element accessors
+ inline float &operator()(size_t i) {
+#ifdef VECTOR_ASSERT
+ ASSERT(i < getRows());
+#endif
+ return getData()[i];
+ }
+ inline const float &operator()(size_t i) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(i < getRows());
+#endif
+ return getData()[i];
+ }
+ // output
+ inline void print() const {
+ for (size_t i = 0; i < getRows(); i++) {
+ float sig;
+ int exp;
+ float num = (*this)(i);
+ float2SigExp(num, sig, exp);
+ printf("%6.3fe%03.3d,", (double)sig, exp);
+ }
+
+ printf("\n");
+ }
+ // boolean ops
+ inline bool operator==(const Vector &right) const {
+ for (size_t i = 0; i < getRows(); i++) {
+ if (fabsf(((*this)(i) - right(i))) > 1e-30f)
+ return false;
+ }
+
+ return true;
+ }
+ // scalar ops
+ inline Vector operator+(const float &right) const {
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) + right;
+ }
+
+ return result;
+ }
+ inline Vector operator-(const float &right) const {
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) - right;
+ }
+
+ return result;
+ }
+ inline Vector operator*(const float &right) const {
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) * right;
+ }
+
+ return result;
+ }
+ inline Vector operator/(const float &right) const {
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) / right;
+ }
+
+ return result;
+ }
+ // vector ops
+ inline Vector operator+(const Vector &right) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) + right(i);
+ }
+
+ return result;
+ }
+ inline Vector operator-(const Vector &right) const {
+#ifdef VECTOR_ASSERT
+ ASSERT(getRows() == right.getRows());
+#endif
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = (*this)(i) - right(i);
+ }
+
+ return result;
+ }
+ inline Vector operator-(void) const {
+ Vector result(getRows());
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result(i) = -((*this)(i));
+ }
+
+ return result;
+ }
+ // other functions
+ inline float dot(const Vector &right) const {
+ float result = 0;
+
+ for (size_t i = 0; i < getRows(); i++) {
+ result += (*this)(i) * (*this)(i);
+ }
+
+ return result;
+ }
+ inline float norm() const {
+ return sqrtf(dot(*this));
+ }
+ inline float length() const {
+ return norm();
+ }
+ inline Vector unit() const {
+ return (*this) / norm();
+ }
+ inline Vector normalized() const {
+ return unit();
+ }
+ inline void normalize() {
+ (*this) = (*this) / norm();
+ }
+ inline static Vector zero(size_t rows) {
+ Vector result(rows);
+ // calloc returns zeroed memory
+ return result;
+ }
+ inline void setAll(const float &val) {
+ for (size_t i = 0; i < getRows(); i++) {
+ (*this)(i) = val;
+ }
+ }
+ inline void set(const float *data) {
+ memcpy(getData(), data, getSize());
+ }
+ inline size_t getRows() const { return _rows; }
+protected:
+ inline size_t getSize() const { return sizeof(float) * getRows(); }
+ inline float *getData() { return _data; }
+ inline const float *getData() const { return _data; }
+ inline void setData(float *data) { _data = data; }
+private:
+ size_t _rows;
+ float *_data;
+};
+
+} // math
diff --git a/src/lib/mathlib/math/nasa_rotation_def.pdf b/src/lib/mathlib/math/nasa_rotation_def.pdf
new file mode 100644
index 000000000..eb67a4bfc
--- /dev/null
+++ b/src/lib/mathlib/math/nasa_rotation_def.pdf
Binary files differ
diff --git a/src/lib/mathlib/math/test/test.cpp b/src/lib/mathlib/math/test/test.cpp
new file mode 100644
index 000000000..2fa2f7e7c
--- /dev/null
+++ b/src/lib/mathlib/math/test/test.cpp
@@ -0,0 +1,94 @@
+/****************************************************************************
+ *
+ * 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 test.cpp
+ *
+ * Test library code
+ */
+
+#include <stdio.h>
+#include <math.h>
+#include <stdlib.h>
+
+#include "test.hpp"
+
+bool __EXPORT equal(float a, float b, float epsilon)
+{
+ float diff = fabsf(a - b);
+
+ if (diff > epsilon) {
+ printf("not equal ->\n\ta: %12.8f\n\tb: %12.8f\n", double(a), double(b));
+ return false;
+
+ } else return true;
+}
+
+void __EXPORT float2SigExp(
+ const float &num,
+ float &sig,
+ int &exp)
+{
+ if (isnan(num) || isinf(num)) {
+ sig = 0.0f;
+ exp = -99;
+ return;
+ }
+
+ if (fabsf(num) < 1.0e-38f) {
+ sig = 0;
+ exp = 0;
+ return;
+ }
+
+ exp = log10f(fabsf(num));
+
+ if (exp > 0) {
+ exp = ceil(exp);
+
+ } else {
+ exp = floor(exp);
+ }
+
+ sig = num;
+
+ // cheap power since it is integer
+ if (exp > 0) {
+ for (int i = 0; i < abs(exp); i++) sig /= 10;
+
+ } else {
+ for (int i = 0; i < abs(exp); i++) sig *= 10;
+ }
+}
+
+
diff --git a/src/lib/mathlib/math/test/test.hpp b/src/lib/mathlib/math/test/test.hpp
new file mode 100644
index 000000000..2027bb827
--- /dev/null
+++ b/src/lib/mathlib/math/test/test.hpp
@@ -0,0 +1,50 @@
+/****************************************************************************
+ *
+ * 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 test.hpp
+ *
+ * Controller library code
+ */
+
+#pragma once
+
+//#include <assert.h>
+//#include <time.h>
+//#include <stdlib.h>
+
+bool equal(float a, float b, float eps = 1e-5);
+void float2SigExp(
+ const float &num,
+ float &sig,
+ int &exp);
diff --git a/src/lib/mathlib/math/test_math.sce b/src/lib/mathlib/math/test_math.sce
new file mode 100644
index 000000000..c3fba4729
--- /dev/null
+++ b/src/lib/mathlib/math/test_math.sce
@@ -0,0 +1,63 @@
+clc
+clear
+function out = float_truncate(in, digits)
+ out = round(in*10^digits)
+ out = out/10^digits
+endfunction
+
+phi = 0.1
+theta = 0.2
+psi = 0.3
+
+cosPhi = cos(phi)
+cosPhi_2 = cos(phi/2)
+sinPhi = sin(phi)
+sinPhi_2 = sin(phi/2)
+
+cosTheta = cos(theta)
+cosTheta_2 = cos(theta/2)
+sinTheta = sin(theta)
+sinTheta_2 = sin(theta/2)
+
+cosPsi = cos(psi)
+cosPsi_2 = cos(psi/2)
+sinPsi = sin(psi)
+sinPsi_2 = sin(psi/2)
+
+C_nb = [cosTheta*cosPsi, -cosPhi*sinPsi + sinPhi*sinTheta*cosPsi, sinPhi*sinPsi + cosPhi*sinTheta*cosPsi;
+ cosTheta*sinPsi, cosPhi*cosPsi + sinPhi*sinTheta*sinPsi, -sinPhi*cosPsi + cosPhi*sinTheta*sinPsi;
+ -sinTheta, sinPhi*cosTheta, cosPhi*cosTheta]
+
+disp(C_nb)
+//C_nb = float_truncate(C_nb,3)
+//disp(C_nb)
+
+theta = asin(-C_nb(3,1))
+phi = atan(C_nb(3,2), C_nb(3,3))
+psi = atan(C_nb(2,1), C_nb(1,1))
+printf('phi %f\n', phi)
+printf('theta %f\n', theta)
+printf('psi %f\n', psi)
+
+q = [cosPhi_2*cosTheta_2*cosPsi_2 + sinPhi_2*sinTheta_2*sinPsi_2;
+ sinPhi_2*cosTheta_2*cosPsi_2 - cosPhi_2*sinTheta_2*sinPsi_2;
+ cosPhi_2*sinTheta_2*cosPsi_2 + sinPhi_2*cosTheta_2*sinPsi_2;
+ cosPhi_2*cosTheta_2*sinPsi_2 - sinPhi_2*sinTheta_2*cosPsi_2]
+
+//q = float_truncate(q,3)
+
+a = q(1)
+b = q(2)
+c = q(3)
+d = q(4)
+printf('q: %f %f %f %f\n', a, b, c, d)
+a2 = a*a
+b2 = b*b
+c2 = c*c
+d2 = d*d
+
+C2_nb = [a2 + b2 - c2 - d2, 2*(b*c - a*d), 2*(b*d + a*c);
+ 2*(b*c + a*d), a2 - b2 + c2 - d2, 2*(c*d - a*b);
+ 2*(b*d - a*c), 2*(c*d + a*b), a2 - b2 - c2 + d2]
+
+disp(C2_nb)
diff --git a/src/lib/mathlib/mathlib.h b/src/lib/mathlib/mathlib.h
new file mode 100644
index 000000000..40ffb22bc
--- /dev/null
+++ b/src/lib/mathlib/mathlib.h
@@ -0,0 +1,59 @@
+/****************************************************************************
+ *
+ * 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
+
+#pragma once
+
+#include "math/Dcm.hpp"
+#include "math/EulerAngles.hpp"
+#include "math/Matrix.hpp"
+#include "math/Quaternion.hpp"
+#include "math/Vector.hpp"
+#include "math/Vector3.hpp"
+#include "math/Vector2f.hpp"
+#include "math/Limits.hpp"
+
+#endif
+
+#ifdef CONFIG_ARCH_ARM
+
+#include "CMSIS/Include/arm_math.h"
+
+#endif \ No newline at end of file
diff --git a/src/lib/mathlib/module.mk b/src/lib/mathlib/module.mk
new file mode 100644
index 000000000..72bc7db8a
--- /dev/null
+++ b/src/lib/mathlib/module.mk
@@ -0,0 +1,61 @@
+############################################################################
+#
+# Copyright (c) 2012, 2013 PX4 Development Team. All rights reserved.
+#
+# Redistribution and use in source and binary forms, with or without
+# modification, are permitted provided that the following conditions
+# 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.
+#
+############################################################################
+
+#
+# Math library
+#
+SRCS = math/test/test.cpp \
+ math/Vector.cpp \
+ math/Vector2f.cpp \
+ math/Vector3.cpp \
+ math/EulerAngles.cpp \
+ math/Quaternion.cpp \
+ math/Dcm.cpp \
+ math/Matrix.cpp \
+ math/Limits.cpp
+
+#
+# In order to include .config we first have to save off the
+# current makefile name, since app.mk needs it.
+#
+APP_MAKEFILE := $(lastword $(MAKEFILE_LIST))
+
+ifeq ($(CONFIG_ARCH_CORTEXM4)$(CONFIG_ARCH_FPU),yy)
+INCLUDE_DIRS += math/arm
+SRCS += math/arm/Vector.cpp \
+ math/arm/Matrix.cpp
+else
+#INCLUDE_DIRS += math/generic
+#SRCS += math/generic/Vector.cpp \
+# math/generic/Matrix.cpp
+endif