aboutsummaryrefslogtreecommitdiff
path: root/src/lib/ecl/attitude_fw
diff options
context:
space:
mode:
authorLorenz Meier <lm@inf.ethz.ch>2013-09-07 13:50:38 +0200
committerLorenz Meier <lm@inf.ethz.ch>2013-09-07 13:50:38 +0200
commit056fe1c0b93094e86fa80de4102b12f2d406de5a (patch)
treebd93d3bf16fe93cd73deccc911a467f49cdf4969 /src/lib/ecl/attitude_fw
parent8398de7515671b52df19a032162ff2064d68772a (diff)
downloadpx4-firmware-056fe1c0b93094e86fa80de4102b12f2d406de5a.tar.gz
px4-firmware-056fe1c0b93094e86fa80de4102b12f2d406de5a.tar.bz2
px4-firmware-056fe1c0b93094e86fa80de4102b12f2d406de5a.zip
WIP
Diffstat (limited to 'src/lib/ecl/attitude_fw')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp63
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h5
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp55
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h5
4 files changed, 116 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 c1c2bc5af..0e1a0d7f6 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -44,20 +44,75 @@ ECL_PitchController::ECL_PitchController() :
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
- _desired_rate(0.0f)
+ _desired_rate(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)
{
/* 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 / 1000000;
- return 0.0f;
+ /* lock integral for long intervals */
+ if (dt_micros > 500000)
+ lock_integrator = true;
+
+ float k_roll_ff = 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;
+
+ 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.5 * 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 = max(id, 0.0f);
+ } else if (_last_output > _max_deflection_rad) {
+ /* only allow motion to center: decrease value */
+ id = min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ _integrator = 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 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..53134556d 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();
@@ -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 cdb221b26..1152b2964 100644
--- a/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_roll_controller.cpp
@@ -46,13 +46,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 +61,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 = max((_k_p - _k_i * _tc) * _tc - _k_d, 0.0f);
+ float k_i_rate = _k_i * _tc;
- float integrator_limit_scaled = 0.0f;
+ /* 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;
+ }
- return 0.0f;
+ 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 = 0.0f;
+
+ if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5 * 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 = max(id, 0.0f);
+ } else if (_last_output > _max_deflection_rad) {
+ /* only allow motion to center: decrease value */
+ id = min(id, 0.0f);
+ }
+
+ _integrator += id;
+ }
+
+ /* integrator limit */
+ _integrator = 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 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..011820765 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();
@@ -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