aboutsummaryrefslogtreecommitdiff
path: root/src
diff options
context:
space:
mode:
Diffstat (limited to 'src')
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp102
-rw-r--r--src/lib/ecl/attitude_fw/ecl_pitch_controller.h18
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.cpp75
-rw-r--r--src/lib/ecl/attitude_fw/ecl_roll_controller.h17
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp106
-rw-r--r--src/lib/ecl/attitude_fw/ecl_yaw_controller.h67
-rw-r--r--src/lib/external_lgpl/tecs/tecs.cpp59
-rw-r--r--src/lib/external_lgpl/tecs/tecs.h7
-rw-r--r--src/modules/fw_att_control/fw_att_control_main.cpp159
-rw-r--r--src/modules/fw_att_control/fw_att_control_params.c36
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp8
-rw-r--r--src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c2
12 files changed, 470 insertions, 186 deletions
diff --git a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
index d876f1a39..4e27de45c 100644
--- a/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_pitch_controller.cpp
@@ -45,40 +45,20 @@
#include <geo/geo.h>
#include <ecl/ecl.h>
#include <mathlib/mathlib.h>
+#include <systemlib/err.h>
ECL_PitchController::ECL_PitchController() :
_last_run(0),
_last_output(0.0f),
_integrator(0.0f),
_rate_error(0.0f),
- _rate_setpoint(0.0f),
- _max_deflection_rad(math::radians(45.0f))
+ _rate_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 = 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;
- }
/* flying inverted (wings upside down) ? */
bool inverted = false;
@@ -106,29 +86,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;
+ }
+
+ }
+
+ return _rate_setpoint;
+}
+
+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;
- float ilimit_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;
+ }
+
+ /* 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
- if (!lock_integrator && k_i_rate > 0.0f && airspeed > 0.5f * airspeed_min) {
+ _rate_error = _bodyrate_setpoint - pitch_bodyrate;
- float id = _rate_error * k_i_rate * dt * scaler;
+ 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);
}
@@ -137,11 +160,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 = (_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..ba8ed3e6f 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();
@@ -94,6 +100,10 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
@@ -109,7 +119,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 b9a73fc02..0772f88bc 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),
@@ -53,24 +54,48 @@ ECL_RollController::ECL_RollController() :
_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(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_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_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);
_last_run = ecl_absolute_time();
+ float dt = (float)dt_micros * 1e-6f;
- float dt = (dt_micros > 500000) ? 0.0f : dt_micros / 1000000;
+ /* 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_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);
@@ -78,32 +103,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 = 0.0f;
+ /* 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);
}
@@ -112,11 +132,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 = (_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..dd7d1bf53 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();
@@ -90,6 +95,10 @@ public:
return _rate_setpoint;
}
+ float get_desired_bodyrate() {
+ return _bodyrate_setpoint;
+ }
+
private:
uint64_t _last_run;
float _tc;
@@ -102,7 +111,7 @@ private:
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..0de0eb439 100644
--- a/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
+++ b/src/lib/ecl/attitude_fw/ecl_yaw_controller.cpp
@@ -44,29 +44,117 @@
#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),
+ _tc(0.1f),
_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(1.0f)
+
+{
+
+}
+
+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;
+ 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
+ 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++;
+
+ 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 = (_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..5c00fa873 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,73 @@
#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_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_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(float coordinated) {
+ _coordinated = coordinated;
+ }
+
+
+ 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 _tc;
+ float _k_p;
float _k_i;
float _k_d;
- float _k_roll_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;
};
diff --git a/src/lib/external_lgpl/tecs/tecs.cpp b/src/lib/external_lgpl/tecs/tecs.cpp
index 864a9d24d..a94a06dda 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)
@@ -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 4a98c8e97..d07bd00dd 100644
--- a/src/lib/external_lgpl/tecs/tecs.h
+++ b/src/lib/external_lgpl/tecs/tecs.h
@@ -178,6 +178,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;
@@ -201,6 +205,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;
@@ -327,7 +332,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);
diff --git a/src/modules/fw_att_control/fw_att_control_main.cpp b/src/modules/fw_att_control/fw_att_control_main.cpp
index eb67874db..78952cb8d 100644
--- a/src/modules/fw_att_control/fw_att_control_main.cpp
+++ b/src/modules/fw_att_control/fw_att_control_main.cpp
@@ -37,6 +37,7 @@
* Implementation of a generic attitude controller based on classic orthogonal PIDs.
*
* @author Lorenz Meier <lm@inf.ethz.ch>
+ * @author Thomas Gubler <thomasgubler@gmail.com>
*
*/
@@ -62,6 +63,7 @@
#include <uORB/topics/vehicle_attitude.h>
#include <uORB/topics/vehicle_control_mode.h>
#include <uORB/topics/parameter_update.h>
+#include <uORB/topics/vehicle_global_position.h>
#include <systemlib/param/param.h>
#include <systemlib/err.h>
#include <systemlib/pid/pid.h>
@@ -106,26 +108,28 @@ private:
bool _task_should_exit; /**< if true, sensor task should exit */
int _control_task; /**< task handle for sensor task */
- int _att_sub; /**< vehicle attitude subscription */
- int _accel_sub; /**< accelerometer subscription */
+ int _att_sub; /**< vehicle attitude subscription */
+ int _accel_sub; /**< accelerometer subscription */
int _att_sp_sub; /**< vehicle attitude setpoint */
int _attitude_sub; /**< raw rc channels data subscription */
int _airspeed_sub; /**< airspeed subscription */
- int _vcontrol_mode_sub; /**< vehicle status subscription */
- int _params_sub; /**< notification of parameter updates */
- int _manual_sub; /**< notification of manual control updates */
+ int _vcontrol_mode_sub; /**< vehicle status subscription */
+ int _params_sub; /**< notification of parameter updates */
+ int _manual_sub; /**< notification of manual control updates */
+ int _global_pos_sub; /**< global position subscription */
orb_advert_t _rate_sp_pub; /**< rate setpoint publication */
orb_advert_t _attitude_sp_pub; /**< attitude setpoint point */
orb_advert_t _actuators_0_pub; /**< actuator control group 0 setpoint */
- struct vehicle_attitude_s _att; /**< vehicle attitude */
- struct accel_report _accel; /**< body frame accelerations */
+ struct vehicle_attitude_s _att; /**< vehicle attitude */
+ struct accel_report _accel; /**< body frame accelerations */
struct vehicle_attitude_setpoint_s _att_sp; /**< vehicle attitude setpoint */
struct manual_control_setpoint_s _manual; /**< r/c channel data */
- struct airspeed_s _airspeed; /**< airspeed */
- struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
- struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct airspeed_s _airspeed; /**< airspeed */
+ struct vehicle_control_mode_s _vcontrol_mode; /**< vehicle control mode */
+ struct actuator_controls_s _actuators; /**< actuator control inputs */
+ struct vehicle_global_position_s _global_pos; /**< global position */
perf_counter_t _loop_perf; /**< loop performance counter */
@@ -151,6 +155,8 @@ private:
float y_d;
float y_roll_feedforward;
float y_integrator_max;
+ float y_coordinated;
+ float y_rmax;
float airspeed_min;
float airspeed_trim;
@@ -177,6 +183,8 @@ private:
param_t y_d;
param_t y_roll_feedforward;
param_t y_integrator_max;
+ param_t y_coordinated;
+ param_t y_rmax;
param_t airspeed_min;
param_t airspeed_trim;
@@ -227,6 +235,11 @@ private:
void vehicle_setpoint_poll();
/**
+ * Check for global position updates.
+ */
+ void global_pos_poll();
+
+ /**
* Shim for calling task_main from task_create.
*/
static void task_main_trampoline(int argc, char *argv[]);
@@ -261,6 +274,7 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_vcontrol_mode_sub(-1),
_params_sub(-1),
_manual_sub(-1),
+ _global_pos_sub(-1),
/* publications */
_rate_sp_pub(-1),
@@ -274,30 +288,33 @@ FixedwingAttitudeControl::FixedwingAttitudeControl() :
_airspeed_valid(false)
{
_parameter_handles.tconst = param_find("FW_ATT_TC");
- _parameter_handles.p_p = param_find("FW_P_P");
- _parameter_handles.p_d = param_find("FW_P_D");
- _parameter_handles.p_i = param_find("FW_P_I");
+ _parameter_handles.p_p = param_find("FW_PR_P");
+ _parameter_handles.p_d = param_find("FW_PR_D");
+ _parameter_handles.p_i = param_find("FW_PR_I");
_parameter_handles.p_rmax_pos = param_find("FW_P_RMAX_POS");
_parameter_handles.p_rmax_neg = param_find("FW_P_RMAX_NEG");
- _parameter_handles.p_integrator_max = param_find("FW_P_integrator_max");
+ _parameter_handles.p_integrator_max = param_find("FW_PR_IMAX");
_parameter_handles.p_roll_feedforward = param_find("FW_P_ROLLFF");
- _parameter_handles.r_p = param_find("FW_R_P");
- _parameter_handles.r_d = param_find("FW_R_D");
- _parameter_handles.r_i = param_find("FW_R_I");
- _parameter_handles.r_integrator_max = param_find("FW_R_integrator_max");
+ _parameter_handles.r_p = param_find("FW_RR_P");
+ _parameter_handles.r_d = param_find("FW_RR_D");
+ _parameter_handles.r_i = param_find("FW_RR_I");
+ _parameter_handles.r_integrator_max = param_find("FW_RR_IMAX");
_parameter_handles.r_rmax = param_find("FW_R_RMAX");
- _parameter_handles.y_p = param_find("FW_Y_P");
- _parameter_handles.y_i = param_find("FW_Y_I");
- _parameter_handles.y_d = param_find("FW_Y_D");
+ _parameter_handles.y_p = param_find("FW_YR_P");
+ _parameter_handles.y_i = param_find("FW_YR_I");
+ _parameter_handles.y_d = param_find("FW_YR_D");
_parameter_handles.y_roll_feedforward = param_find("FW_Y_ROLLFF");
- _parameter_handles.y_integrator_max = param_find("FW_Y_integrator_max");
+ _parameter_handles.y_integrator_max = param_find("FW_YR_IMAX");
+ _parameter_handles.y_rmax = param_find("FW_Y_RMAX");
_parameter_handles.airspeed_min = param_find("FW_AIRSPD_MIN");
_parameter_handles.airspeed_trim = param_find("FW_AIRSPD_TRIM");
_parameter_handles.airspeed_max = param_find("FW_AIRSPD_MAX");
+ _parameter_handles.y_coordinated = param_find("FW_Y_COORD");
+
/* fetch initial parameter values */
parameters_update();
}
@@ -351,6 +368,8 @@ FixedwingAttitudeControl::parameters_update()
param_get(_parameter_handles.y_d, &(_parameters.y_d));
param_get(_parameter_handles.y_roll_feedforward, &(_parameters.y_roll_feedforward));
param_get(_parameter_handles.y_integrator_max, &(_parameters.y_integrator_max));
+ param_get(_parameter_handles.y_coordinated, &(_parameters.y_coordinated));
+ param_get(_parameter_handles.y_rmax, &(_parameters.y_rmax));
param_get(_parameter_handles.airspeed_min, &(_parameters.airspeed_min));
param_get(_parameter_handles.airspeed_trim, &(_parameters.airspeed_trim));
@@ -358,28 +377,30 @@ FixedwingAttitudeControl::parameters_update()
/* pitch control parameters */
_pitch_ctrl.set_time_constant(_parameters.tconst);
- _pitch_ctrl.set_k_p(math::radians(_parameters.p_p));
- _pitch_ctrl.set_k_i(math::radians(_parameters.p_i));
- _pitch_ctrl.set_k_d(math::radians(_parameters.p_d));
- _pitch_ctrl.set_integrator_max(math::radians(_parameters.p_integrator_max));
+ _pitch_ctrl.set_k_p(_parameters.p_p);
+ _pitch_ctrl.set_k_i(_parameters.p_i);
+ _pitch_ctrl.set_k_d(_parameters.p_d);
+ _pitch_ctrl.set_integrator_max(_parameters.p_integrator_max);
_pitch_ctrl.set_max_rate_pos(math::radians(_parameters.p_rmax_pos));
_pitch_ctrl.set_max_rate_neg(math::radians(_parameters.p_rmax_neg));
- _pitch_ctrl.set_roll_ff(math::radians(_parameters.p_roll_feedforward));
+ _pitch_ctrl.set_roll_ff(_parameters.p_roll_feedforward);
/* roll control parameters */
_roll_ctrl.set_time_constant(_parameters.tconst);
- _roll_ctrl.set_k_p(math::radians(_parameters.r_p));
- _roll_ctrl.set_k_i(math::radians(_parameters.r_i));
- _roll_ctrl.set_k_d(math::radians(_parameters.r_d));
- _roll_ctrl.set_integrator_max(math::radians(_parameters.r_integrator_max));
+ _roll_ctrl.set_k_p(_parameters.r_p);
+ _roll_ctrl.set_k_i(_parameters.r_i);
+ _roll_ctrl.set_k_d(_parameters.r_d);
+ _roll_ctrl.set_integrator_max(_parameters.r_integrator_max);
_roll_ctrl.set_max_rate(math::radians(_parameters.r_rmax));
/* yaw control parameters */
- _yaw_ctrl.set_k_side(math::radians(_parameters.y_p));
- _yaw_ctrl.set_k_i(math::radians(_parameters.y_i));
- _yaw_ctrl.set_k_d(math::radians(_parameters.y_d));
- _yaw_ctrl.set_k_roll_ff(math::radians(_parameters.y_roll_feedforward));
- _yaw_ctrl.set_integrator_max(math::radians(_parameters.y_integrator_max));
+ _yaw_ctrl.set_k_p(_parameters.y_p);
+ _yaw_ctrl.set_k_i(_parameters.y_i);
+ _yaw_ctrl.set_k_d(_parameters.y_d);
+ _yaw_ctrl.set_k_roll_ff(_parameters.y_roll_feedforward);
+ _yaw_ctrl.set_integrator_max(_parameters.y_integrator_max);
+ _yaw_ctrl.set_coordinated(_parameters.y_coordinated);
+ _yaw_ctrl.set_max_rate(math::radians(_parameters.y_rmax));
return OK;
}
@@ -421,6 +442,7 @@ FixedwingAttitudeControl::vehicle_airspeed_poll()
if (airspeed_updated) {
orb_copy(ORB_ID(airspeed), _airspeed_sub, &_airspeed);
+// warnx("airspeed poll: ind: %.4f, true: %.4f", _airspeed.indicated_airspeed_m_s, _airspeed.true_airspeed_m_s);
return true;
}
@@ -453,6 +475,18 @@ FixedwingAttitudeControl::vehicle_setpoint_poll()
}
void
+FixedwingAttitudeControl::global_pos_poll()
+{
+ /* check if there is a new global position */
+ bool global_pos_updated;
+ orb_check(_global_pos_sub, &global_pos_updated);
+
+ if (global_pos_updated) {
+ orb_copy(ORB_ID(vehicle_global_position), _global_pos_sub, &_global_pos);
+ }
+}
+
+void
FixedwingAttitudeControl::task_main_trampoline(int argc, char *argv[])
{
att_control::g_control->task_main();
@@ -476,6 +510,7 @@ FixedwingAttitudeControl::task_main()
_vcontrol_mode_sub = orb_subscribe(ORB_ID(vehicle_control_mode));
_params_sub = orb_subscribe(ORB_ID(parameter_update));
_manual_sub = orb_subscribe(ORB_ID(manual_control_setpoint));
+ _global_pos_sub = orb_subscribe(ORB_ID(vehicle_global_position));
/* rate limit vehicle status updates to 5Hz */
orb_set_interval(_vcontrol_mode_sub, 200);
@@ -551,6 +586,8 @@ FixedwingAttitudeControl::task_main()
vehicle_manual_poll();
+ global_pos_poll();
+
/* lock integrator until control is started */
bool lock_integrator;
@@ -565,9 +602,6 @@ FixedwingAttitudeControl::task_main()
if (_vcontrol_mode.flag_control_attitude_enabled) {
- /* scale from radians to normalized -1 .. 1 range */
- const float actuator_scaling = 1.0f / (M_PI_F / 4.0f);
-
/* scale around tuning airspeed */
float airspeed;
@@ -635,17 +669,42 @@ FixedwingAttitudeControl::task_main()
}
}
- float roll_rad = _roll_ctrl.control(roll_sp, _att.roll, _att.rollspeed,
- airspeed_scaling, lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[0] = (isfinite(roll_rad)) ? roll_rad * actuator_scaling : 0.0f;
-
- float pitch_rad = _pitch_ctrl.control(pitch_sp, _att.pitch, _att.pitchspeed, _att.roll, airspeed_scaling,
- lock_integrator, _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[1] = (isfinite(pitch_rad)) ? pitch_rad * actuator_scaling : 0.0f;
+ /* Prepare speed_body_u and speed_body_w */
+ float speed_body_u = 0.0f;
+ float speed_body_w = 0.0f;
+ if(_att.R_valid) {
+ speed_body_u = _att.R[0][0] * _global_pos.vx + _att.R[1][0] * _global_pos.vy + _att.R[2][0] * _global_pos.vz;
+// speed_body_v = _att.R[0][1] * _global_pos.vx + _att.R[1][1] * _global_pos.vy + _att.R[2][1] * _global_pos.vz;
+ speed_body_w = _att.R[0][2] * _global_pos.vx + _att.R[1][2] * _global_pos.vy + _att.R[2][2] * _global_pos.vz;
+ } else {
+ warnx("Did not get a valid R\n");
+ }
- float yaw_rad = _yaw_ctrl.control(_att.roll, _att.yawspeed, _accel.y, airspeed_scaling, lock_integrator,
- _parameters.airspeed_min, _parameters.airspeed_max, airspeed);
- _actuators.control[2] = (isfinite(yaw_rad)) ? yaw_rad * actuator_scaling : 0.0f;
+ /* Run attitude controllers */
+ _roll_ctrl.control_attitude(roll_sp, _att.roll);
+ _pitch_ctrl.control_attitude(pitch_sp, _att.roll, _att.pitch, airspeed);
+ _yaw_ctrl.control_attitude(_att.roll, _att.pitch,
+ speed_body_u,speed_body_w,
+ _roll_ctrl.get_desired_rate(), _pitch_ctrl.get_desired_rate()); //runs last, because is depending on output of roll and pitch attitude
+
+ /* Run attitude RATE controllers which need the desired attitudes from above */
+ float roll_u = _roll_ctrl.control_bodyrate(_att.pitch,
+ _att.rollspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[0] = (isfinite(roll_u)) ? roll_u : 0.0f;
+
+ float pitch_u = _pitch_ctrl.control_bodyrate(_att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _yaw_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[1] = (isfinite(pitch_u)) ? pitch_u : 0.0f;
+
+ float yaw_u = _yaw_ctrl.control_bodyrate( _att.roll, _att.pitch,
+ _att.pitchspeed, _att.yawspeed,
+ _pitch_ctrl.get_desired_rate(),
+ _parameters.airspeed_min, _parameters.airspeed_max, airspeed, airspeed_scaling, lock_integrator);
+ _actuators.control[2] = (isfinite(yaw_u)) ? yaw_u : 0.0f;
/* throttle passed through */
_actuators.control[3] = (isfinite(throttle_sp)) ? throttle_sp : 0.0f;
@@ -661,7 +720,7 @@ FixedwingAttitudeControl::task_main()
vehicle_rates_setpoint_s rates_sp;
rates_sp.roll = _roll_ctrl.get_desired_rate();
rates_sp.pitch = _pitch_ctrl.get_desired_rate();
- rates_sp.yaw = 0.0f; // XXX not yet implemented
+ rates_sp.yaw = _yaw_ctrl.get_desired_rate();
rates_sp.timestamp = hrt_absolute_time();
diff --git a/src/modules/fw_att_control/fw_att_control_params.c b/src/modules/fw_att_control/fw_att_control_params.c
index 97aa275de..41e37e61f 100644
--- a/src/modules/fw_att_control/fw_att_control_params.c
+++ b/src/modules/fw_att_control/fw_att_control_params.c
@@ -44,11 +44,13 @@
#include <systemlib/param/param.h>
+//XXX resolve unclear naming of paramters: FW_P_P --> FW_PR_P
+
/*
* Controller parameters, accessible via MAVLink
*
*/
-
+//xxx: update descriptions
// @DisplayName Attitude Time Constant
// @Description This defines the latency between a step input and the achieved setpoint. Half a second is a good start value and fits for most average systems. Smaller systems may require smaller values, but as this will wear out servos faster, the value should only be decreased as needed.
// @Range 0.4 to 1.0 seconds, in tens of seconds
@@ -57,33 +59,33 @@ PARAM_DEFINE_FLOAT(FW_ATT_TC, 0.5f);
// @DisplayName Proportional gain.
// @Description This defines how much the elevator input will be commanded dependend on the current pitch error.
// @Range 10 to 200, 1 increments
-PARAM_DEFINE_FLOAT(FW_P_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_PR_P, 0.3f);
// @DisplayName Damping gain.
// @Description This gain damps the airframe pitch rate. In particular relevant for flying wings.
// @Range 0.0 to 10.0, 0.1 increments
-PARAM_DEFINE_FLOAT(FW_P_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_PR_D, 0.0f); //xxx: remove
// @DisplayName Integrator gain.
// @Description This gain defines how much control response will result out of a steady state error. It trims any constant error.
// @Range 0 to 50.0
-PARAM_DEFINE_FLOAT(FW_P_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_PR_I, 0.05f);
// @DisplayName Maximum positive / up pitch rate.
// @Description This limits the maximum pitch up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
// @Range 0 to 90.0 degrees per seconds, in 1 increments
-PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_POS, 60.0f);
// @DisplayName Maximum negative / down pitch rate.
// @Description This limits the maximum pitch down up angular rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
// @Range 0 to 90.0 degrees per seconds, in 1 increments
-PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 0.0f);
+PARAM_DEFINE_FLOAT(FW_P_RMAX_NEG, 60.0f);
// @DisplayName Pitch Integrator Anti-Windup
// @Description This limits the range in degrees the integrator can wind up to.
// @Range 0.0 to 45.0
// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_P_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_PR_IMAX, 0.2f);
// @DisplayName Roll feedforward gain.
// @Description This compensates during turns and ensures the nose stays level.
@@ -97,27 +99,27 @@ PARAM_DEFINE_FLOAT(FW_P_ROLLFF, 1.0f);
// @Range 10.0 200.0
// @Increment 10.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_P, 40.0f);
+PARAM_DEFINE_FLOAT(FW_RR_P, 0.5f);
// @DisplayName Damping Gain
// @Description Controls the roll rate to roll actuator output. It helps to reduce motions in turbulence.
// @Range 0.0 10.0
// @Increment 1.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_D, 0.0f);
+PARAM_DEFINE_FLOAT(FW_RR_D, 0.0f); //xxx: remove
// @DisplayName Integrator Gain
// @Description This gain controls the contribution of the integral to roll actuator outputs. It trims out steady state errors.
// @Range 0.0 100.0
// @Increment 5.0
// @User User
-PARAM_DEFINE_FLOAT(FW_R_I, 0.0f);
+PARAM_DEFINE_FLOAT(FW_RR_I, 0.05f);
// @DisplayName Roll Integrator Anti-Windup
// @Description This limits the range in degrees the integrator can wind up to.
// @Range 0.0 to 45.0
// @Increment 1.0
-PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
+PARAM_DEFINE_FLOAT(FW_RR_IMAX, 0.2f);
// @DisplayName Maximum Roll Rate
// @Description This limits the maximum roll rate the controller will output (in degrees per second). Setting a value of zero disables the limit.
@@ -126,11 +128,13 @@ PARAM_DEFINE_FLOAT(FW_R_IMAX, 15.0f);
PARAM_DEFINE_FLOAT(FW_R_RMAX, 60);
-PARAM_DEFINE_FLOAT(FW_Y_P, 0);
-PARAM_DEFINE_FLOAT(FW_Y_I, 0);
-PARAM_DEFINE_FLOAT(FW_Y_IMAX, 15.0f);
-PARAM_DEFINE_FLOAT(FW_Y_D, 0);
-PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 1);
+PARAM_DEFINE_FLOAT(FW_YR_P, 0.5);
+PARAM_DEFINE_FLOAT(FW_YR_I, 0.05);
+PARAM_DEFINE_FLOAT(FW_YR_IMAX, 0.2f);
+PARAM_DEFINE_FLOAT(FW_YR_D, 0); //xxx: remove
+PARAM_DEFINE_FLOAT(FW_Y_ROLLFF, 0);
PARAM_DEFINE_FLOAT(FW_AIRSPD_MIN, 9.0f);
PARAM_DEFINE_FLOAT(FW_AIRSPD_TRIM, 12.0f);
PARAM_DEFINE_FLOAT(FW_AIRSPD_MAX, 18.0f);
+PARAM_DEFINE_FLOAT(FW_Y_RMAX, 60);
+PARAM_DEFINE_FLOAT(FW_Y_COORD, 1.0f);
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
index a90899528..97140f01c 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_main.cpp
@@ -206,6 +206,8 @@ private:
float throttle_land_max;
float loiter_hold_radius;
+
+ float heightrate_p;
} _parameters; /**< local copies of interesting parameters */
struct {
@@ -240,6 +242,8 @@ private:
param_t throttle_land_max;
param_t loiter_hold_radius;
+
+ param_t heightrate_p;
} _parameter_handles; /**< handles for interesting parameters */
@@ -375,6 +379,7 @@ FixedwingPositionControl::FixedwingPositionControl() :
_parameter_handles.roll_throttle_compensation = param_find("FW_T_RLL2THR");
_parameter_handles.speed_weight = param_find("FW_T_SPDWEIGHT");
_parameter_handles.pitch_damping = param_find("FW_T_PTCH_DAMP");
+ _parameter_handles.heightrate_p = param_find("FW_T_HRATE_P");
/* fetch initial parameter values */
parameters_update();
@@ -440,6 +445,8 @@ FixedwingPositionControl::parameters_update()
param_get(_parameter_handles.pitch_damping, &(_parameters.pitch_damping));
param_get(_parameter_handles.max_climb_rate, &(_parameters.max_climb_rate));
+ param_get(_parameter_handles.heightrate_p, &(_parameters.heightrate_p));
+
_l1_control.set_l1_damping(_parameters.l1_damping);
_l1_control.set_l1_period(_parameters.l1_period);
_l1_control.set_l1_roll_limit(math::radians(_parameters.roll_limit));
@@ -458,6 +465,7 @@ FixedwingPositionControl::parameters_update()
_tecs.set_indicated_airspeed_min(_parameters.airspeed_min);
_tecs.set_indicated_airspeed_max(_parameters.airspeed_min);
_tecs.set_max_climb_rate(_parameters.max_climb_rate);
+ _tecs.set_heightrate_p(_parameters.heightrate_p);
/* sanity check parameters */
if (_parameters.airspeed_max < _parameters.airspeed_min ||
diff --git a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
index 3bb872405..a6aa45258 100644
--- a/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
+++ b/src/modules/fw_pos_control_l1/fw_pos_control_l1_params.c
@@ -111,3 +111,5 @@ PARAM_DEFINE_FLOAT(FW_T_PTCH_DAMP, 0.0f);
PARAM_DEFINE_FLOAT(FW_T_SINK_MAX, 5.0f);
+
+PARAM_DEFINE_FLOAT(FW_T_HRATE_P, 0.05f);