ardupilot/libraries/AC_PID/AC_PI_2D.cpp

Ignoring revisions in .git-blame-ignore-revs. Click here to bypass and see the normal blame view.

178 lines
4.7 KiB
C++
Raw Permalink Normal View History

2015-01-29 02:49:30 -04:00
/// @file AC_PI_2D.cpp
/// @brief 2-axis PI controller
2015-01-29 02:49:30 -04:00
#include <AP_Math/AP_Math.h>
2015-01-29 02:49:30 -04:00
#include "AC_PI_2D.h"
const AP_Param::GroupInfo AC_PI_2D::var_info[] = {
2015-01-29 02:49:30 -04:00
// @Param: P
// @DisplayName: PI Proportional Gain
2015-01-29 02:49:30 -04:00
// @Description: P Gain which produces an output value that is proportional to the current error value
2023-01-03 13:22:36 -04:00
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, AC_PI_2D, _kp, default_kp),
2015-01-29 02:49:30 -04:00
// @Param: I
// @DisplayName: PI Integral Gain
2015-01-29 02:49:30 -04:00
// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error
2023-01-03 13:22:36 -04:00
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, AC_PI_2D, _ki, default_ki),
2015-01-29 02:49:30 -04:00
// @Param: IMAX
// @DisplayName: PI Integral Maximum
2015-01-29 02:49:30 -04:00
// @Description: The maximum/minimum value that the I term can output
2023-01-03 13:22:36 -04:00
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 2, AC_PI_2D, _imax, default_imax),
2015-01-29 02:49:30 -04:00
// @Param: FILT_HZ
// @DisplayName: PI Input filter frequency in Hz
2015-01-29 02:49:30 -04:00
// @Description: Input filter frequency in Hz
2016-02-17 22:11:13 -04:00
// @Units: Hz
2023-01-03 13:22:36 -04:00
AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FILT_HZ", 3, AC_PI_2D, _filt_hz, default_filt_hz),
2015-01-29 02:49:30 -04:00
AP_GROUPEND
};
// Constructor
AC_PI_2D::AC_PI_2D(float initial_p, float initial_i, float initial_imax, float initial_filt_hz, float dt) :
2023-01-03 13:22:36 -04:00
_dt(dt),
default_kp(initial_p),
default_ki(initial_i),
default_imax(initial_imax),
default_filt_hz(initial_filt_hz)
2015-01-29 02:49:30 -04:00
{
// load parameter values from eeprom
AP_Param::setup_object_defaults(this, var_info);
filt_hz(initial_filt_hz);
2015-01-29 02:49:30 -04:00
// reset input filter to first value received
_flags._reset_filter = true;
}
// set_dt - set time step in seconds
void AC_PI_2D::set_dt(float dt)
{
// set dt and calculate the input filter alpha
_dt = dt;
calc_filt_alpha();
}
// filt_hz - set input filter hz
void AC_PI_2D::filt_hz(float hz)
2015-01-29 02:49:30 -04:00
{
2015-05-08 15:42:13 -03:00
_filt_hz.set(fabsf(hz));
// sanity check _filt_hz
2022-07-05 00:08:55 -03:00
_filt_hz.set(MAX(_filt_hz, AC_PI_2D_FILT_HZ_MIN));
2015-01-29 02:49:30 -04:00
// calculate the input filter alpha
calc_filt_alpha();
}
// set_input - set input to PID controller
// input is filtered before the PID controllers are run
// this should be called before any other calls to get_p, get_i or get_d
void AC_PI_2D::set_input(const Vector2f &input)
{
// don't process inf or NaN
if (!isfinite(input.x) || !isfinite(input.y)) {
return;
}
2015-01-29 02:49:30 -04:00
// reset input filter to value received
if (_flags._reset_filter) {
_flags._reset_filter = false;
_input = input;
}
// update filter and calculate derivative
Vector2f input_filt_change = (input - _input) * _filt_alpha;
_input = _input + input_filt_change;
}
Vector2f AC_PI_2D::get_p() const
{
return (_input * _kp);
}
Vector2f AC_PI_2D::get_i()
{
if (!is_zero(_ki) && !is_zero(_dt)) {
2015-01-29 02:49:30 -04:00
_integrator += (_input * _ki) * _dt;
const float integrator_length = _integrator.length();
if ((integrator_length > _imax) && (is_positive(integrator_length))) {
2015-01-29 02:49:30 -04:00
_integrator *= (_imax / integrator_length);
}
return _integrator;
}
return Vector2f{};
2015-01-29 02:49:30 -04:00
}
// get_i_shrink - get_i but do not allow integrator to grow in length (it may shrink)
Vector2f AC_PI_2D::get_i_shrink()
{
2015-05-04 23:34:48 -03:00
if (!is_zero(_ki) && !is_zero(_dt)) {
const float integrator_length_orig = MIN(_integrator.length(),_imax);
2015-01-29 02:49:30 -04:00
_integrator += (_input * _ki) * _dt;
const float integrator_length_new = _integrator.length();
if ((integrator_length_new > integrator_length_orig) && is_positive(integrator_length_new)) {
2015-01-29 02:49:30 -04:00
_integrator *= (integrator_length_orig / integrator_length_new);
}
return _integrator;
}
return Vector2f{};
2015-01-29 02:49:30 -04:00
}
Vector2f AC_PI_2D::get_pi()
{
return get_p() + get_i();
}
void AC_PI_2D::reset_I()
{
_integrator.zero();
}
void AC_PI_2D::load_gains()
{
_kp.load();
_ki.load();
_imax.load();
2022-07-05 00:08:55 -03:00
_imax.set(fabsf(_imax));
2015-01-29 02:49:30 -04:00
_filt_hz.load();
// calculate the input filter alpha
calc_filt_alpha();
}
// save_gains - save gains to eeprom
void AC_PI_2D::save_gains()
{
_kp.save();
_ki.save();
_imax.save();
_filt_hz.save();
}
/// Overload the function call operator to permit easy initialisation
void AC_PI_2D::operator() (float p, float i, float imaxval, float input_filt_hz, float dt)
{
2022-07-05 00:08:55 -03:00
_kp.set(p);
_ki.set(i);
_imax.set(fabsf(imaxval));
_filt_hz.set(input_filt_hz);
2015-01-29 02:49:30 -04:00
_dt = dt;
// calculate the input filter alpha
calc_filt_alpha();
}
// calc_filt_alpha - recalculate the input filter alpha
void AC_PI_2D::calc_filt_alpha()
{
2015-05-04 23:34:48 -03:00
if (is_zero(_filt_hz)) {
_filt_alpha = 1.0f;
return;
}
2015-01-29 02:49:30 -04:00
// calculate alpha
const float rc = 1/(M_2PI*_filt_hz);
2015-01-29 02:49:30 -04:00
_filt_alpha = _dt / (_dt + rc);
}