ardupilot/libraries/AC_PID/AC_PID_2D.h

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

117 lines
4.1 KiB
C
Raw Permalink Normal View History

2017-11-17 10:10:04 -04:00
#pragma once
/// @file AC_PID_2D.h
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
#include <AP_Common/AP_Common.h>
#include <AP_Param/AP_Param.h>
#include <stdlib.h>
#include <cmath>
#include <AC_PID/AP_PIDInfo.h>
#include <Filter/SlewCalculator2D.h>
2017-11-17 10:10:04 -04:00
/// @class AC_PID_2D
/// @brief Copter PID control class
class AC_PID_2D {
public:
// Constructor for PID
2022-12-02 08:34:53 -04:00
AC_PID_2D(float initial_kP, float initial_kI, float initial_kD, float initial_kFF, float initial_imax, float initial_filt_hz, float initial_filt_d_hz);
2017-11-17 10:10:04 -04:00
2021-06-06 05:33:35 -03:00
CLASS_NO_COPY(AC_PID_2D);
// update_all - set target and measured inputs to PID controller and calculate outputs
// target and error are filtered
// the derivative is then calculated and filtered
2022-01-06 20:43:23 -04:00
// the integral is then updated if it does not increase in the direction of the limit vector
2022-12-02 08:34:53 -04:00
Vector2f update_all(const Vector2f &target, const Vector2f &measurement, float dt, const Vector2f &limit);
Vector2f update_all(const Vector3f &target, const Vector3f &measurement, float dt, const Vector3f &limit);
2017-11-17 10:10:04 -04:00
// update the integral
// if the limit flag is set the integral is only allowed to shrink
2022-12-02 08:34:53 -04:00
void update_i(float dt, const Vector2f &limit);
2017-11-17 10:10:04 -04:00
// get results from pid controller
Vector2f get_p() const;
2021-05-20 07:42:20 -03:00
const Vector2f& get_i() const;
Vector2f get_d() const;
Vector2f get_ff();
const Vector2f& get_error() const { return _error; }
2017-11-17 10:10:04 -04:00
// reset the integrator
void reset_I();
2017-11-17 10:10:04 -04:00
// reset_filter - input and D term filter will be reset to the next value provided to set_input()
void reset_filter() { _reset_filter = true; }
2017-11-17 10:10:04 -04:00
// save gain to eeprom
void save_gains();
2017-11-17 10:10:04 -04:00
// get accessors
AP_Float &kP() { return _kp; }
AP_Float &kI() { return _ki; }
AP_Float &kD() { return _kd; }
AP_Float &ff() { return _kff;}
AP_Float &filt_E_hz() { return _filt_E_hz; }
AP_Float &filt_D_hz() { return _filt_D_hz; }
float imax() const { return _kimax.get(); }
2022-12-02 08:34:53 -04:00
float get_filt_E_alpha(float dt) const;
float get_filt_D_alpha(float dt) const;
2017-11-17 10:10:04 -04:00
// set accessors
void set_kP(float v) { _kp.set(v); }
void set_kI(float v) { _ki.set(v); }
void set_kD(float v) { _kd.set(v); }
void set_ff(float v) { _kff.set(v); }
void set_imax(float v) { _kimax.set(fabsf(v)); }
void set_filt_E_hz(float hz) { _filt_E_hz.set(fabsf(hz)); }
void set_filt_D_hz(float hz) { _filt_D_hz.set(fabsf(hz)); }
// integrator setting functions
void set_integrator(const Vector2f& target, const Vector2f& measurement, const Vector2f& i);
void set_integrator(const Vector2f& error, const Vector2f& i);
2021-05-12 00:51:35 -03:00
void set_integrator(const Vector3f& i) { set_integrator(Vector2f{i.x, i.y}); }
void set_integrator(const Vector2f& i);
// return current slew rate of slew limiter. Will return 0 if SMAX is zero
float get_slew_rate(void) const { return _slew_calc.get_slew_rate(); }
const AP_PIDInfo& get_pid_info_x(void) const { return _pid_info_x; }
const AP_PIDInfo& get_pid_info_y(void) const { return _pid_info_y; }
2017-11-17 10:10:04 -04:00
// parameter var table
static const struct AP_Param::GroupInfo var_info[];
protected:
// parameters
AP_Float _kp;
AP_Float _ki;
AP_Float _kd;
AP_Float _kff;
AP_Float _kimax;
AP_Float _filt_E_hz; // PID error filter frequency in Hz
AP_Float _filt_D_hz; // PID derivative filter frequency in Hz
2017-11-17 10:10:04 -04:00
// internal variables
Vector2f _target; // target value to enable filtering
Vector2f _error; // error value to enable filtering
Vector2f _derivative; // last derivative from low-pass filter
Vector2f _integrator; // integrator value
bool _reset_filter; // true when input filter should be reset during next call to update_all
AP_PIDInfo _pid_info_x;
AP_PIDInfo _pid_info_y;
2023-01-03 13:22:36 -04:00
SlewCalculator2D _slew_calc; // 2D slew rate calculator
2023-01-03 13:22:36 -04:00
private:
const float default_kp;
const float default_ki;
const float default_kd;
const float default_kff;
const float default_kimax;
const float default_filt_E_hz;
const float default_filt_D_hz;
2017-11-17 10:10:04 -04:00
};