aboutsummaryrefslogtreecommitdiff
path: root/src/lib
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-08 21:50:14 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-08 21:50:14 +0200
commit8bd018c5611dddd914fd108965526945b31d5944 (patch)
treeedb065e1a3c64075bbfcb03c5810da72f307748b /src/lib
parent11e4fbc3745193a61f6f56619318dc1bc0b60307 (diff)
parentd3ac8c9ff31ac609d555613e552b38782a2b2490 (diff)
downloadpx4-firmware-8bd018c5611dddd914fd108965526945b31d5944.tar.gz
px4-firmware-8bd018c5611dddd914fd108965526945b31d5944.tar.bz2
px4-firmware-8bd018c5611dddd914fd108965526945b31d5944.zip
Merge branch 'fixedwing_l1' of github.com:PX4/Firmware into fixedwing_l1
Diffstat (limited to 'src/lib')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp73
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h7
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp58
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h7
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp11
5 files changed, 144 insertions, 12 deletions
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index 0faba287d..77ec15c53 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -38,20 +38,87 @@
*/
#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),
- _desired_rate(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 aspeed)
+ bool lock_integrator, float airspeed_min, float airspeed_max, float airspeed)
{
- return 0.0f;
+ /* get the usual dt estimate */
+ uint64_t dt_micros = ecl_elapsed_time(&_last_run);
+ _last_run = ecl_absolute_time();
+
+ float dt = dt_micros / 1000000;
+
+ /* 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;
+ }
+
+ /* calculate the offset in the rate resulting from rolling */
+ float turn_offset = fabsf((CONSTANTS_ONE_G / airspeed) *
+ tanf(roll) * sinf(roll)) * _roll_ff;
+
+ 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 = 0.0f;
+
+ 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()
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
index 391f90b9d..02ca62dad 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.h
@@ -49,7 +49,7 @@ 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 aspeed = (0.0f / 0.0f));
+ bool lock_integrator = false, float airspeed_min = 0.0f, float airspeed_max = 0.0f, float airspeed = (0.0f / 0.0f));
void reset_integrator();
@@ -83,7 +83,7 @@ public:
}
float get_desired_rate() {
- return _desired_rate;
+ return _rate_setpoint;
}
private:
@@ -100,7 +100,8 @@ private:
float _last_output;
float _integrator;
float _rate_error;
- float _desired_rate;
+ 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
index b28ecdabe..6de30fc33 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -39,6 +39,11 @@
#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),
@@ -46,13 +51,14 @@ ECL_RollController::ECL_RollController() :
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
- _desired_rate(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 aspeed)
+ 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);
@@ -60,10 +66,56 @@ float ECL_RollController::control(float roll_setpoint, float roll, float roll_ra
float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000;
+ 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;
- return 0.0f;
+ /* 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 = 0.0f;
+
+ 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()
diff --git a/src/lib/ecl/attitude_fw/ecl_roll_controller.h b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
index bba9ae163..7fbcdf4b8 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.h
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.h
@@ -49,7 +49,7 @@ 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 aspeed = (0.0f / 0.0f));
+ 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();
@@ -79,7 +79,7 @@ public:
}
float get_desired_rate() {
- return _desired_rate;
+ return _rate_setpoint;
}
private:
@@ -93,7 +93,8 @@ private:
float _last_output;
float _integrator;
float _rate_error;
- float _desired_rate;
+ 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
index 0d8a0513f..a0f901e71 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -38,6 +38,11 @@
*/
#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),
@@ -54,6 +59,12 @@ ECL_YawController::ECL_YawController() :
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;
}