aboutsummaryrefslogtreecommitdiff
path: root/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
diff options
context:
space:
mode:
Diffstat (limited to 'src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp123
1 files changed, 88 insertions, 35 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..46db788a6 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -45,38 +45,39 @@
#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_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),
+ _nonfinite_input_perf(perf_alloc(PC_COUNT, "fw att control pitch nonfinite input"))
{
}
-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)
+ECL_PitchController::~ECL_PitchController()
{
- /* 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;
+ perf_free(_nonfinite_input_perf);
+}
- /* 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 ECL_PitchController::control_attitude(float pitch_setpoint, float roll, float pitch, float airspeed)
+{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(pitch_setpoint) && isfinite(roll) && isfinite(pitch) && isfinite(airspeed))) {
+ perf_count(_nonfinite_input_perf);
+ warnx("not controlling pitch");
+ return _rate_setpoint;
}
/* flying inverted (wings upside down) ? */
@@ -100,34 +101,83 @@ float ECL_PitchController::control(float pitch_setpoint, float pitch, float pitc
}
/* calculate the offset in the rate resulting from rolling */
+ //xxx needs explanation and conversion to body angular rates or should be removed
float turn_offset = fabsf((CONSTANTS_ONE_G / airspeed) *
tanf(roll) * sinf(roll)) * _roll_ff;
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)
+{
+ /* Do not calculate control signal with bad inputs */
+ if (!(isfinite(roll) && isfinite(pitch) && isfinite(pitch_rate) && isfinite(yaw_rate) &&
+ isfinite(yaw_rate_setpoint) && isfinite(airspeed_min) &&
+ isfinite(airspeed_max) && isfinite(scaler))) {
+ perf_count(_nonfinite_input_perf);
+ return math::constrain(_last_output, -1.0f, 1.0f);
+ }
+
+ /* 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;
+
+ /* 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 +186,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) * 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()