aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorThomas Gubler <thomasgubler@gmail.com>2013-10-19 14:14:44 +0200
committerThomas Gubler <thomasgubler@gmail.com>2013-10-24 17:47:22 +0200
commit8f74aab468d565101eaa1e0f104b0297343fe2ed (patch)
treec0b376656cd1e147c0572db3def03429f0b10703 /src/lib
parentb9ef3636f5210588d0aa219a163d3ef5edd6a204 (diff)
downloadpx4-firmware-8f74aab468d565101eaa1e0f104b0297343fe2ed.tar.gz
px4-firmware-8f74aab468d565101eaa1e0f104b0297343fe2ed.tar.bz2
px4-firmware-8f74aab468d565101eaa1e0f104b0297343fe2ed.zip
fw att control: bugfixes for integrator
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp11
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp13
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp30
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h4
4 files changed, 35 insertions, 23 deletions
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index e1f4d3eef..5fe55163f 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -116,8 +116,7 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
/* get the usual dt estimate */
uint64_t dt_micros = ecl_elapsed_time(&_last_run);
_last_run = ecl_absolute_time();
-
- float dt = dt_micros / 1000000;
+ float dt = (dt_micros > 500000) ? 0.0f : (float)dt_micros * 1e-6f;
/* lock integral for long intervals */
if (dt_micros > 500000)
@@ -142,11 +141,9 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
_rate_error = _bodyrate_setpoint - pitch_bodyrate;
- float ilimit_scaled = 0.0f;
-
if (!lock_integrator && k_i_rate > 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
@@ -164,9 +161,9 @@ float ECL_PitchController::control_bodyrate(float roll, float pitch,
}
/* integrator limit */
- _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
+ _integrator = math::constrain(_integrator, -_integrator_max, _integrator_max);
/* store non-limited output */
- _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_roll_ff)) * scaler;
+ _last_output = ((_rate_error * _k_d * scaler) + _integrator * k_i_rate * scaler + (_rate_setpoint * k_roll_ff)) * scaler;
return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
}
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
index 3afda3176..1aac82792 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -45,6 +45,7 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_RollController::ECL_RollController() :
_last_run(0),
@@ -85,7 +86,7 @@ float ECL_RollController::control_bodyrate(float pitch,
/* 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;
+ float dt = (dt_micros > 500000) ? 0.0f : (float)dt_micros * 1e-6f;
float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
float k_i_rate = _k_i * _tc;
@@ -108,11 +109,9 @@ float ECL_RollController::control_bodyrate(float pitch,
/* Calculate body angular rate error */
_rate_error = _bodyrate_setpoint - roll_bodyrate; //body angular rate error
- float ilimit_scaled = 0.0f;
-
if (!lock_integrator && k_i_rate > 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
@@ -130,9 +129,11 @@ float ECL_RollController::control_bodyrate(float pitch,
}
/* integrator limit */
- _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
+ _integrator = math::constrain(_integrator, -_integrator_max, _integrator_max);
+ //warnx("roll: _integrator: %.4f, _integrator_max: %.4f", (double)_integrator, (double)_integrator_max);
+
/* store non-limited output */
- _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_ff)) * scaler;
+ _last_output = ((_rate_error * _k_d * scaler) + _integrator * k_i_rate * scaler + (_rate_setpoint * k_ff)) * scaler;
return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
}
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
index d2cd9cf04..7dfed3379 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -44,6 +44,7 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_YawController::ECL_YawController() :
_last_run(0),
@@ -53,7 +54,8 @@ ECL_YawController::ECL_YawController() :
_rate_error(0.0f),
_rate_setpoint(0.0f),
_bodyrate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _max_deflection_rad(math::radians(45.0f)),
+ _coordinated(1.0f)
{
@@ -63,11 +65,18 @@ float ECL_YawController::control_attitude(float roll, float pitch,
float speed_body_u, 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;
- 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;
+ if (_coordinated > 0.1) {
+ 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;
+ }
+
+// 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
@@ -76,6 +85,9 @@ float ECL_YawController::control_attitude(float roll, float pitch,
_rate_setpoint = (_rate_setpoint < -_max_rate) ? -_max_rate : _rate_setpoint;
}
+
+// counter++;
+
return _rate_setpoint;
}
@@ -87,7 +99,7 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
/* 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;
+ float dt = (dt_micros > 500000) ? 0.0f : (float)dt_micros * 1e-6f;
float k_ff = math::max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
float k_i_rate = _k_i * _tc;
@@ -110,11 +122,9 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
/* Calculate body angular rate error */
_rate_error = _bodyrate_setpoint - yaw_bodyrate; //body angular rate error
- float ilimit_scaled = 0.0f;
-
if (!lock_integrator && k_i_rate > 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
@@ -132,9 +142,9 @@ float ECL_YawController::control_bodyrate(float roll, float pitch,
}
/* integrator limit */
- _integrator = math::constrain(_integrator, -ilimit_scaled, ilimit_scaled);
+ _integrator = math::constrain(_integrator, -_integrator_max, _integrator_max);
/* store non-limited output */
- _last_output = ((_rate_error * _k_d * scaler) + _integrator + (_rate_setpoint * k_ff)) * scaler;
+ _last_output = ((_rate_error * _k_d * scaler) + _integrator * k_i_rate * scaler + (_rate_setpoint * k_ff)) * scaler;
return math::constrain(_last_output, -_max_deflection_rad, _max_deflection_rad);
}
diff --git a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
index d5aaa617f..0250fcb35 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.h
@@ -85,6 +85,9 @@ public:
void set_k_roll_ff(float roll_ff) {
_roll_ff = roll_ff;
}
+ void set_coordinated(float coordinated) {
+ _coordinated = coordinated;
+ }
float get_rate_error() {
@@ -115,6 +118,7 @@ private:
float _rate_setpoint;
float _bodyrate_setpoint;
float _max_deflection_rad;
+ float _coordinated;
};