aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorJulian Oes <julian@oes.ch>2013-11-20 13:17:49 +0100
committerJulian Oes <julian@oes.ch>2013-11-20 13:17:49 +0100
commitc33d61693519ee48f50e49fa086602f52eab47ec (patch)
tree9c1028e93fe34d275594b6d0edec95afdd985b4a /src/lib
parenta27c7e831945f0a6b95b50b9ac68364b28a49362 (diff)
parent37ef10ceead77876108847e31f56ae68015f5784 (diff)
downloadpx4-firmware-c33d61693519ee48f50e49fa086602f52eab47ec.tar.gz
px4-firmware-c33d61693519ee48f50e49fa086602f52eab47ec.tar.bz2
px4-firmware-c33d61693519ee48f50e49fa086602f52eab47ec.zip
Merge remote-tracking branch 'thomasgubler_private/fw_autoland_att_tecs' into navigator_wip_merge_test
Conflicts: src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp109
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h28
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp75
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h27
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp116
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h74
-rw-r--r--src/lib/ecl/l1/ecl_l1_pos_controller.cpp2
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp61
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h7
9 files changed, 381 insertions, 118 deletions
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 2eb58abd6..d7dbbebd4 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -45,39 +45,30 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_PitchController::ECL_PitchController() :
_last_run(0),
+ _tc(0.1f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate_pos(0.0f),
+ _max_rate_neg(0.0f),
+ _roll_ff(0.0f),
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _bodyrate_setpoint(0.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)
+float ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, 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;
@@ -105,29 +96,72 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
if (inverted)
turn_offset = -turn_offset;
+ /* Calculate the error */
float pitch_error = pitch_setpoint - pitch;
- /* rate setpoint from current error and time constant */
- _rate_setpoint = pitch_error / _tc;
+
+ /* Apply P controller: 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;
+ /* limit the rate */ //XXX: move to body angluar rates
+ if (_max_rate_pos > 0.01f && _max_rate_neg > 0.01f) {
+ if (_rate_setpoint > 0.0f) {
+ _rate_setpoint = (_rate_setpoint > _max_rate_pos) ? _max_rate_pos : _rate_setpoint;
+ } else {
+ _rate_setpoint = (_rate_setpoint < -_max_rate_neg) ? -_max_rate_neg : _rate_setpoint;
+ }
- float ilimit_scaled = _integrator_max * scaler;
+ }
- if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+ return _rate_setpoint;
+}
- float id = _rate_error * k_i_rate * dt * scaler;
+float ECL_PitchController::control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
+{
+ /* 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_ff = 0;
+
+ /* 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;
+ }
+
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = cosf(roll) * _rate_setpoint + cosf(pitch) * sinf(roll) * yaw_rate_setpoint; //jacobian
+
+ /* Transform estimation to body angular rates */
+ float pitch_bodyrate = cosf(roll) * pitch_rate + cosf(pitch) * sinf(roll) * yaw_rate; //jacobian
+
+ _rate_error = _bodyrate_setpoint - pitch_bodyrate;
+
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase into the
- * wrong direction if actuator is at limit
+ * anti-windup: do not allow integrator to increase if actuator is at limit
*/
- if (_last_output < -_max_deflection_rad) {
+ if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
- } else if (_last_output > _max_deflection_rad) {
+ } else if (_last_output > 1.0f) {
/* only allow motion to center: decrease value */
id = math::min(id, 0.0f);
}
@@ -136,11 +170,14 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
}
/* 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);
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff +_rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
+// warnx("pitch: _integrator: %.4f, _integrator_max: %.4f, airspeed %.4f, _k_i %.4f, _k_p: %.4f", (double)_integrator, (double)_integrator_max, (double)airspeed, (double)_k_i, (double)_k_p);
+// warnx("roll: _last_output %.4f", (double)_last_output);
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_PitchController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
index 1e6cec6a1..2ca0490fd 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -36,6 +36,7 @@
* Definition of a simple orthogonal pitch PID controller.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Acknowledgements:
*
@@ -51,13 +52,18 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_PitchController
+class __EXPORT ECL_PitchController //XXX: create controller superclass
{
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));
+ float control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed);
+
+
+ float control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f), float scaler = 1.0f, bool lock_integrator = false);
void reset_integrator();
@@ -67,21 +73,30 @@ public:
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_k_ff(float k_ff) {
+ _k_ff = k_ff;
+ }
+
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;
}
@@ -94,6 +109,10 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
@@ -101,6 +120,7 @@ private:
float _k_p;
float _k_i;
float _k_d;
+ float _k_ff;
float _integrator_max;
float _max_rate_pos;
float _max_rate_neg;
@@ -109,7 +129,7 @@ private:
float _integrator;
float _rate_error;
float _rate_setpoint;
- float _max_deflection_rad;
+ float _bodyrate_setpoint;
};
#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
index 0b1ffa7a4..bd6c9da71 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -45,21 +45,47 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_RollController::ECL_RollController() :
_last_run(0),
_tc(0.1f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate(0.0f),
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
_rate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _bodyrate_setpoint(0.0f)
{
+}
+
+float ECL_RollController::control_attitude(float roll_setpoint, float roll)
+{
+
+ /* Calculate error */
+ float roll_error = roll_setpoint - roll;
+
+ /* Apply P controller */
+ _rate_setpoint = roll_error / _tc;
+
+ /* limit the rate */ //XXX: move to body angluar rates
+ 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;
+ }
+ return _rate_setpoint;
}
-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)
+float ECL_RollController::control_bodyrate(float pitch,
+ float roll_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
@@ -70,10 +96,11 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
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;
+// float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_ff = 0; //xxx: param
/* input conditioning */
+// warnx("airspeed pre %.4f", (double)airspeed);
if (!isfinite(airspeed)) {
/* airspeed is NaN, +- INF or not available, pick center of band */
airspeed = 0.5f * (airspeed_min + airspeed_max);
@@ -81,32 +108,27 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
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;
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = _rate_setpoint - sinf(pitch) * yaw_rate_setpoint; //jacobian
+ /* Transform estimation to body angular rates */
+ float roll_bodyrate = roll_rate - sinf(pitch) * yaw_rate; //jacobian
- float ilimit_scaled = _integrator_max * scaler;
+ /* Calculate body angular rate error */
+ _rate_error = _bodyrate_setpoint - roll_bodyrate; //body angular rate error
- if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
- float id = _rate_error * k_i_rate * dt * scaler;
+ float id = _rate_error * dt;
/*
- * anti-windup: do not allow integrator to increase into the
- * wrong direction if actuator is at limit
+ * anti-windup: do not allow integrator to increase if actuator is at limit
*/
- if (_last_output < -_max_deflection_rad) {
+ if (_last_output < -1.0f) {
/* only allow motion to center: increase value */
id = math::max(id, 0.0f);
- } else if (_last_output > _max_deflection_rad) {
+ } else if (_last_output > 1.0f) {
/* only allow motion to center: decrease value */
id = math::min(id, 0.0f);
}
@@ -115,11 +137,14 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
}
/* 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;
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+ //warnx("roll: _integrator: %.4f, _integrator_max: %.4f", (double)_integrator, (double)_integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff + _rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
- return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_RollController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
index 0d4ea9333..efc7b8944 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -36,6 +36,7 @@
* Definition of a simple orthogonal roll PID controller.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
* Acknowledgements:
*
@@ -51,13 +52,17 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_RollController
+class __EXPORT ECL_RollController //XXX: create controller superclass
{
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));
+ float control_attitude(float roll_setpoint, float roll);
+
+ float control_bodyrate(float pitch,
+ float roll_rate, float yaw_rate,
+ float yaw_rate_setpoint,
+ float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f), float scaler = 1.0f, bool lock_integrator = false);
void reset_integrator();
@@ -66,18 +71,27 @@ public:
_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_k_ff(float k_ff) {
+ _k_ff = k_ff;
+ }
+
void set_integrator_max(float max) {
_integrator_max = max;
}
+
void set_max_rate(float max_rate) {
_max_rate = max_rate;
}
@@ -90,19 +104,24 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
float _tc;
float _k_p;
float _k_i;
float _k_d;
+ float _k_ff;
float _integrator_max;
float _max_rate;
float _last_output;
float _integrator;
float _rate_error;
float _rate_setpoint;
- float _max_deflection_rad;
+ float _bodyrate_setpoint;
};
#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
index b786acf24..7c366aaf2 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -44,29 +44,127 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_YawController::ECL_YawController() :
_last_run(0),
- _last_error(0.0f),
+ _k_p(0.0f),
+ _k_i(0.0f),
+ _k_d(0.0f),
+ _k_ff(0.0f),
+ _integrator_max(0.0f),
+ _max_rate(0.0f),
+ _roll_ff(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)
+ _integrator(0.0f),
+ _rate_error(0.0f),
+ _rate_setpoint(0.0f),
+ _bodyrate_setpoint(0.0f),
+ _coordinated_min_speed(1.0f)
{
+}
+
+float ECL_YawController::control_attitude(float roll, float pitch,
+ float speed_body_u, float speed_body_v, float speed_body_w,
+ float roll_rate_setpoint, float pitch_rate_setpoint)
+{
+// static int counter = 0;
+ /* Calculate desired yaw rate from coordinated turn constraint / (no side forces) */
+ _rate_setpoint = 0.0f;
+ if (sqrtf(speed_body_u * speed_body_u + speed_body_v * speed_body_v + speed_body_w * speed_body_w) > _coordinated_min_speed) {
+ float denumerator = (speed_body_u * cosf(roll) * cosf(pitch) + speed_body_w * sinf(pitch));
+ if(denumerator != 0.0f) { //XXX: floating point comparison
+ _rate_setpoint = (speed_body_w * roll_rate_setpoint + 9.81f * sinf(roll) * cosf(pitch) + speed_body_u * pitch_rate_setpoint * sinf(roll)) / denumerator;
+// warnx("yaw: speed_body_u %.f speed_body_w %1.f roll %.1f pitch %.1f denumerator %.1f _rate_setpoint %.1f", speed_body_u, speed_body_w, denumerator, _rate_setpoint);
+ }
+
+// if(counter % 20 == 0) {
+// warnx("denumerator: %.4f, speed_body_u: %.4f, speed_body_w: %.4f, cosf(roll): %.4f, cosf(pitch): %.4f, sinf(pitch): %.4f", (double)denumerator, (double)speed_body_u, (double)speed_body_w, (double)cosf(roll), (double)cosf(pitch), (double)sinf(pitch));
+// }
+ }
+
+ /* limit the rate */ //XXX: move to body angluar rates
+ 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;
+ }
+
+// counter++;
+
+ if(!isfinite(_rate_setpoint)){
+ warnx("yaw rate sepoint not finite");
+ _rate_setpoint = 0.0f;
+ }
+
+ return _rate_setpoint;
}
-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)
+float ECL_YawController::control_bodyrate(float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float pitch_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator)
{
/* 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_ff = 0;
+
+
+ /* 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;
+ }
+
+
+ /* Transform setpoint to body angular rates */
+ _bodyrate_setpoint = -sinf(roll) * pitch_rate_setpoint + cosf(roll)*cosf(pitch) * _rate_setpoint; //jacobian
+
+ /* Transform estimation to body angular rates */
+ float yaw_bodyrate = -sinf(roll) * pitch_rate + cosf(roll)*cosf(pitch) * yaw_rate; //jacobian
+
+ /* Calculate body angular rate error */
+ _rate_error = _bodyrate_setpoint - yaw_bodyrate; //body angular rate error
+
+ if (!lock_integrator && _k_i > 0.0f && airspeed > 0.5f * airspeed_min) {
+
+ float id = _rate_error * dt;
+
+ /*
+ * anti-windup: do not allow integrator to increase if actuator is at limit
+ */
+ if (_last_output < -1.0f) {
+ /* only allow motion to center: increase value */
+ id = math::max(id, 0.0f);
+ } else if (_last_output > 1.0f) {
+ /* only allow motion to center: decrease value */
+ id = math::min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ //xxx: until start detection is available: integral part in control signal is limited here
+ float integrator_constrained = math::constrain(_integrator * _k_i, -_integrator_max, _integrator_max);
+
+ /* Apply PI rate controller and store non-limited output */
+ _last_output = (_bodyrate_setpoint * _k_ff + _rate_error * _k_p + integrator_constrained + _rate_setpoint * k_ff) * scaler * scaler; //scaler is proportional to 1/airspeed
+ //warnx("yaw:_last_output: %.4f, _integrator: %.4f, _integrator_max: %.4f, airspeed %.4f, _k_i %.4f, _k_p: %.4f", (double)_last_output, (double)_integrator, (double)_integrator_max, (double)airspeed, (double)_k_i, (double)_k_p);
- float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000;
- return 0.0f;
+ return math::constrain(_last_output, -1.0f, 1.0f);
}
void ECL_YawController::reset_integrator()
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
index 66b227918..f15645fcf 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -35,6 +35,15 @@
* @file ecl_yaw_controller.h
* Definition of a simple orthogonal coordinated turn yaw PID controller.
*
+ * @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
+ *
+ * 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_YAW_CONTROLLER_H
#define ECL_YAW_CONTROLLER_H
@@ -42,47 +51,82 @@
#include <stdbool.h>
#include <stdint.h>
-class __EXPORT ECL_YawController
+class __EXPORT ECL_YawController //XXX: create controller superclass
{
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));
+ float control_attitude(float roll, float pitch,
+ float speed_body_u, float speed_body_v, float speed_body_w,
+ float roll_rate_setpoint, float pitch_rate_setpoint);
+
+ float control_bodyrate( float roll, float pitch,
+ float pitch_rate, float yaw_rate,
+ float pitch_rate_setpoint,
+ float airspeed_min, float airspeed_max, float airspeed, float scaler, bool lock_integrator);
void reset_integrator();
- void set_k_side(float k_a) {
- _k_side = k_a;
+ 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_k_roll_ff(float k_roll_ff) {
- _k_roll_ff = k_roll_ff;
+
+ void set_k_ff(float k_ff) {
+ _k_ff = k_ff;
}
+
void set_integrator_max(float max) {
_integrator_max = max;
}
+ void set_max_rate(float max_rate) {
+ _max_rate = max_rate;
+ }
+
+ void set_k_roll_ff(float roll_ff) {
+ _roll_ff = roll_ff;
+ }
+
+ void set_coordinated_min_speed(float coordinated_min_speed) {
+ _coordinated_min_speed = coordinated_min_speed;
+ }
+
+
+ float get_rate_error() {
+ return _rate_error;
+ }
+
+ float get_desired_rate() {
+ return _rate_setpoint;
+ }
+
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
-
- float _k_side;
+ float _k_p;
float _k_i;
float _k_d;
- float _k_roll_ff;
+ float _k_ff;
float _integrator_max;
-
- float _last_error;
+ float _max_rate;
+ float _roll_ff;
float _last_output;
- float _last_rate_hp_out;
- float _last_rate_hp_in;
- float _k_d_last;
float _integrator;
+ float _rate_error;
+ float _rate_setpoint;
+ float _bodyrate_setpoint;
+ float _coordinated_min_speed;
};
diff --git a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
index 27d76f959..31d7cecb7 100644
--- a/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
+++ b/src/lib/ecl/l1/ecl_l1_pos_controller.cpp
@@ -70,7 +70,7 @@ float ECL_L1_Pos_Controller::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);
+ return math::min(wp_radius, _L1_distance);
}
bool ECL_L1_Pos_Controller::reached_loiter_target(void)
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index 864a9d24d..510b8ed9c 100644
--- a/src/lib/external_lgpl/tecs/tecs.cpp
+++ b/src/lib/external_lgpl/tecs/tecs.cpp
@@ -2,6 +2,7 @@
#include "tecs.h"
#include <ecl/ecl.h>
+#include <systemlib/err.h>
using namespace math;
@@ -199,33 +200,47 @@ void TECS::_update_speed_demand(void)
_TAS_dem_last = _TAS_dem;
}
-void TECS::_update_height_demand(float demand)
+void TECS::_update_height_demand(float demand, float state)
{
- // 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);
+// // 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);
+
+ _hgt_dem_adj = demand;//0.025f * demand + 0.975f * _hgt_dem_adj_last;
+ _hgt_dem_adj_last = _hgt_dem_adj;
+ _hgt_rate_dem = (_hgt_dem_adj-state)*_heightrate_p;
// Limit height rate of change
- if ((_hgt_dem - _hgt_dem_prev) > (_maxClimbRate * 0.1f)) {
- _hgt_dem = _hgt_dem_prev + _maxClimbRate * 0.1f;
+ if (_hgt_rate_dem > _maxClimbRate) {
+ _hgt_rate_dem = _maxClimbRate;
- } else if ((_hgt_dem - _hgt_dem_prev) < (-_maxSinkRate * 0.1f)) {
- _hgt_dem = _hgt_dem_prev - _maxSinkRate * 0.1f;
+ } else if (_hgt_rate_dem < -_maxSinkRate) {
+ _hgt_rate_dem = -_maxSinkRate;
}
- _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);
+ warnx("_hgt_rate_dem: %.4f, _hgt_dem_adj %.4f", _hgt_rate_dem, _hgt_dem_adj);
}
void TECS::_detect_underspeed(void)
@@ -299,7 +314,7 @@ void TECS::_update_throttle(float throttle_cruise, const math::Dcm &rotMat)
// Rate limit PD + FF throttle
// Calculate the throttle increment from the specified slew time
- if (fabsf(_throttle_slewrate) < 0.01f) {
+ if (fabsf(_throttle_slewrate) > 0.01f) {
float thrRateIncr = _DT * (_THRmaxf - _THRminf) * _throttle_slewrate;
_throttle_dem = constrain(_throttle_dem,
@@ -500,7 +515,7 @@ void TECS::update_pitch_throttle(const math::Dcm &rotMat, float pitch, float bar
_update_speed_demand();
// Calculate the height demand
- _update_height_demand(hgt_dem);
+ _update_height_demand(hgt_dem, baro_altitude);
// Detect underspeed condition
_detect_underspeed();
diff --git a/src/lib/external_lgpl/tecs/tecs.h b/src/lib/external_lgpl/tecs/tecs.h
index f8f832ed7..06e1c8ad3 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -180,6 +180,10 @@ public:
_indicated_airspeed_max = airspeed;
}
+ void set_heightrate_p(float heightrate_p) {
+ _heightrate_p = heightrate_p;
+ }
+
private:
// Last time update_50Hz was called
uint64_t _update_50hz_last_usec;
@@ -203,6 +207,7 @@ private:
float _vertAccLim;
float _rollComp;
float _spdWeight;
+ float _heightrate_p;
// throttle demand in the range from 0.0 to 1.0
float _throttle_dem;
@@ -329,7 +334,7 @@ private:
void _update_speed_demand(void);
// Update the demanded height
- void _update_height_demand(float demand);
+ void _update_height_demand(float demand, float state);
// Detect an underspeed condition
void _detect_underspeed(void);