aboutsummaryrefslogtreecommitdiff
path: root/src/lib/ecl
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/ecl
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/ecl')
-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
10 files changed, 1384 insertions, 0 deletions
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