2016-02-17 21:25:08 -04:00
|
|
|
#pragma once
|
2012-01-29 01:21:43 -04:00
|
|
|
|
|
|
|
/// @file AC_PID.h
|
|
|
|
/// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
|
|
|
|
|
2015-08-11 03:28:41 -03:00
|
|
|
#include <AP_Common/AP_Common.h>
|
|
|
|
#include <AP_Param/AP_Param.h>
|
2012-10-09 18:01:58 -03:00
|
|
|
#include <stdlib.h>
|
2016-03-31 18:43:36 -03:00
|
|
|
#include <cmath>
|
2020-09-24 00:28:24 -03:00
|
|
|
#include <Filter/SlewLimiter.h>
|
2023-07-27 10:58:50 -03:00
|
|
|
#include <Filter/NotchFilter.h>
|
2023-10-01 14:21:00 -03:00
|
|
|
#include <Filter/AP_Filter.h>
|
2012-01-29 01:21:43 -04:00
|
|
|
|
2019-06-27 06:33:15 -03:00
|
|
|
#define AC_PID_TFILT_HZ_DEFAULT 0.0f // default input filter frequency
|
|
|
|
#define AC_PID_EFILT_HZ_DEFAULT 0.0f // default input filter frequency
|
|
|
|
#define AC_PID_DFILT_HZ_DEFAULT 20.0f // default input filter frequency
|
2020-12-01 11:02:54 -04:00
|
|
|
#define AC_PID_RESET_TC 0.16f // Time constant for integrator reset decay to zero
|
2014-02-14 02:52:24 -04:00
|
|
|
|
2022-03-03 23:29:46 -04:00
|
|
|
#include "AP_PIDInfo.h"
|
|
|
|
|
2012-01-29 01:21:43 -04:00
|
|
|
/// @class AC_PID
|
2015-02-11 08:06:04 -04:00
|
|
|
/// @brief Copter PID control class
|
2012-01-29 01:21:43 -04:00
|
|
|
class AC_PID {
|
|
|
|
public:
|
|
|
|
|
2023-08-30 03:11:20 -03:00
|
|
|
struct Defaults {
|
|
|
|
float p;
|
|
|
|
float i;
|
|
|
|
float d;
|
|
|
|
float ff;
|
|
|
|
float imax;
|
|
|
|
float filt_T_hz;
|
|
|
|
float filt_E_hz;
|
|
|
|
float filt_D_hz;
|
|
|
|
float srmax;
|
|
|
|
float srtau;
|
2023-07-27 10:58:50 -03:00
|
|
|
float dff;
|
2023-08-30 03:11:20 -03:00
|
|
|
};
|
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// Constructor for PID
|
2020-09-24 00:28:24 -03:00
|
|
|
AC_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz,
|
2023-07-27 10:58:50 -03:00
|
|
|
float initial_srmax=0, float initial_srtau=1.0, float initial_dff=0);
|
2023-08-30 03:11:20 -03:00
|
|
|
AC_PID(const AC_PID::Defaults &defaults) :
|
|
|
|
AC_PID(
|
|
|
|
defaults.p,
|
|
|
|
defaults.i,
|
|
|
|
defaults.d,
|
|
|
|
defaults.ff,
|
|
|
|
defaults.imax,
|
|
|
|
defaults.filt_T_hz,
|
|
|
|
defaults.filt_E_hz,
|
|
|
|
defaults.filt_D_hz,
|
|
|
|
defaults.srmax,
|
2023-07-27 10:58:50 -03:00
|
|
|
defaults.srtau,
|
|
|
|
defaults.dff
|
2023-08-30 03:11:20 -03:00
|
|
|
)
|
|
|
|
{ }
|
2015-02-11 08:06:04 -04:00
|
|
|
|
2021-06-06 05:33:35 -03:00
|
|
|
CLASS_NO_COPY(AC_PID);
|
|
|
|
|
2019-06-27 06:33:15 -03:00
|
|
|
// 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
|
|
|
|
// the integral is then updated based on the setting of the limit flag
|
2022-05-28 12:58:25 -03:00
|
|
|
float update_all(float target, float measurement, float dt, bool limit = false, float boost = 1.0f);
|
2019-06-27 06:33:15 -03:00
|
|
|
|
|
|
|
// update_error - set error input to PID controller and calculate outputs
|
|
|
|
// target is set to zero and error is set and filtered
|
|
|
|
// the derivative then is calculated and filtered
|
|
|
|
// the integral is then updated based on the setting of the limit flag
|
|
|
|
// Target and Measured must be set manually for logging purposes.
|
|
|
|
// todo: remove function when it is no longer used.
|
2022-12-02 08:34:53 -04:00
|
|
|
float update_error(float error, float dt, bool limit = false);
|
2019-06-27 06:33:15 -03:00
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// get_pid - get results from pid controller
|
2019-06-27 06:33:15 -03:00
|
|
|
float get_p() const;
|
|
|
|
float get_i() const;
|
|
|
|
float get_d() const;
|
2023-12-10 16:03:38 -04:00
|
|
|
float get_ff() const;
|
2019-06-27 06:33:15 -03:00
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// reset_I - reset the integrator
|
2019-06-27 06:33:15 -03:00
|
|
|
void reset_I();
|
2012-08-17 02:37:26 -03:00
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// reset_filter - input filter will be reset to the next value provided to set_input()
|
2019-06-27 06:33:15 -03:00
|
|
|
void reset_filter() {
|
|
|
|
_flags._reset_filter = true;
|
|
|
|
}
|
2015-02-11 08:06:04 -04:00
|
|
|
|
|
|
|
// load gain from eeprom
|
2019-06-27 06:33:15 -03:00
|
|
|
void load_gains();
|
2012-08-17 02:37:26 -03:00
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// save gain to eeprom
|
2019-06-27 06:33:15 -03:00
|
|
|
void save_gains();
|
2015-02-11 08:06:04 -04:00
|
|
|
|
|
|
|
/// operator function call for easy initialisation
|
2023-07-27 10:58:50 -03:00
|
|
|
void operator()(float p_val, float i_val, float d_val, float ff_val, float imax_val, float input_filt_T_hz, float input_filt_E_hz, float input_filt_D_hz, float dff_val=0);
|
2015-02-11 08:06:04 -04:00
|
|
|
|
|
|
|
// get accessors
|
2023-08-28 21:02:22 -03:00
|
|
|
const AP_Float &kP() const { return _kp; }
|
2019-06-27 06:33:15 -03:00
|
|
|
AP_Float &kP() { return _kp; }
|
|
|
|
AP_Float &kI() { return _ki; }
|
|
|
|
AP_Float &kD() { return _kd; }
|
2020-09-19 07:18:44 -03:00
|
|
|
AP_Float &kIMAX() { return _kimax; }
|
2023-09-18 22:46:00 -03:00
|
|
|
AP_Float &kPDMAX() { return _kpdmax; }
|
2019-06-27 06:33:15 -03:00
|
|
|
AP_Float &ff() { return _kff;}
|
|
|
|
AP_Float &filt_T_hz() { return _filt_T_hz; }
|
|
|
|
AP_Float &filt_E_hz() { return _filt_E_hz; }
|
|
|
|
AP_Float &filt_D_hz() { return _filt_D_hz; }
|
2021-04-04 06:49:31 -03:00
|
|
|
AP_Float &slew_limit() { return _slew_rate_max; }
|
2023-12-10 16:03:38 -04:00
|
|
|
AP_Float &kDff() { return _kdff; }
|
2021-04-04 06:49:31 -03:00
|
|
|
|
2019-06-27 06:33:15 -03:00
|
|
|
float imax() const { return _kimax.get(); }
|
2023-09-18 22:46:00 -03:00
|
|
|
float pdmax() const { return _kpdmax.get(); }
|
2023-12-10 16:03:38 -04:00
|
|
|
|
2022-12-02 08:34:53 -04:00
|
|
|
float get_filt_T_alpha(float dt) const;
|
|
|
|
float get_filt_E_alpha(float dt) const;
|
|
|
|
float get_filt_D_alpha(float dt) const;
|
2015-02-11 08:06:04 -04:00
|
|
|
|
|
|
|
// set accessors
|
2019-06-27 06:33:15 -03:00
|
|
|
void kP(const float v) { _kp.set(v); }
|
|
|
|
void kI(const float v) { _ki.set(v); }
|
|
|
|
void kD(const float v) { _kd.set(v); }
|
|
|
|
void ff(const float v) { _kff.set(v); }
|
|
|
|
void imax(const float v) { _kimax.set(fabsf(v)); }
|
2023-09-18 22:46:00 -03:00
|
|
|
void pdmax(const float v) { _kpdmax.set(fabsf(v)); }
|
2019-06-27 06:33:15 -03:00
|
|
|
void filt_T_hz(const float v);
|
|
|
|
void filt_E_hz(const float v);
|
|
|
|
void filt_D_hz(const float v);
|
2021-11-05 17:52:42 -03:00
|
|
|
void slew_limit(const float v);
|
2023-12-10 16:03:38 -04:00
|
|
|
void kDff(const float v) { _kdff.set(v); }
|
2012-08-17 02:37:26 -03:00
|
|
|
|
2018-08-08 01:11:59 -03:00
|
|
|
// set the desired and actual rates (for logging purposes)
|
2019-06-27 06:33:15 -03:00
|
|
|
void set_target_rate(float target) { _pid_info.target = target; }
|
|
|
|
void set_actual_rate(float actual) { _pid_info.actual = actual; }
|
|
|
|
|
|
|
|
// integrator setting functions
|
2019-10-16 05:10:28 -03:00
|
|
|
void set_integrator(float i);
|
2022-12-02 08:34:53 -04:00
|
|
|
void relax_integrator(float integrator, float dt, float time_constant);
|
2015-05-24 02:51:44 -03:00
|
|
|
|
2021-03-31 21:12:11 -03:00
|
|
|
// set slew limiter scale factor
|
|
|
|
void set_slew_limit_scale(int8_t scale) { _slew_limit_scale = scale; }
|
|
|
|
|
2021-04-04 06:49:31 -03:00
|
|
|
// return current slew rate of slew limiter. Will return 0 if SMAX is zero
|
|
|
|
float get_slew_rate(void) const { return _slew_limiter.get_slew_rate(); }
|
|
|
|
|
2022-03-03 23:29:46 -04:00
|
|
|
const AP_PIDInfo& get_pid_info(void) const { return _pid_info; }
|
2015-05-21 22:43:43 -03:00
|
|
|
|
2023-07-27 10:58:50 -03:00
|
|
|
void set_notch_sample_rate(float);
|
2023-12-10 16:03:38 -04:00
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// parameter var table
|
2019-06-27 06:33:15 -03:00
|
|
|
static const struct AP_Param::GroupInfo var_info[];
|
2012-02-12 07:25:50 -04:00
|
|
|
|
2014-05-02 18:17:32 -03:00
|
|
|
protected:
|
2015-02-11 08:06:04 -04:00
|
|
|
|
2023-12-10 16:03:38 -04:00
|
|
|
// update_i - update the integral
|
|
|
|
// if the limit flag is set the integral is only allowed to shrink
|
|
|
|
void update_i(float dt, bool limit);
|
|
|
|
|
2015-02-11 08:06:04 -04:00
|
|
|
// parameters
|
2019-06-27 06:33:15 -03:00
|
|
|
AP_Float _kp;
|
|
|
|
AP_Float _ki;
|
|
|
|
AP_Float _kd;
|
|
|
|
AP_Float _kff;
|
|
|
|
AP_Float _kimax;
|
2023-09-18 22:46:00 -03:00
|
|
|
AP_Float _kpdmax;
|
2019-06-27 06:33:15 -03:00
|
|
|
AP_Float _filt_T_hz; // PID target filter frequency in Hz
|
|
|
|
AP_Float _filt_E_hz; // PID error filter frequency in Hz
|
|
|
|
AP_Float _filt_D_hz; // PID derivative filter frequency in Hz
|
2020-09-24 00:28:24 -03:00
|
|
|
AP_Float _slew_rate_max;
|
2023-07-27 10:58:50 -03:00
|
|
|
AP_Float _kdff;
|
2023-10-01 14:21:00 -03:00
|
|
|
#if AP_FILTER_ENABLED
|
|
|
|
AP_Int8 _notch_T_filter;
|
|
|
|
AP_Int8 _notch_E_filter;
|
2023-07-27 10:58:50 -03:00
|
|
|
#endif
|
2023-12-10 16:03:38 -04:00
|
|
|
|
|
|
|
// the time constant tau is not currently configurable, but is set
|
|
|
|
// as an AP_Float to make it easy to make it configurable for a
|
|
|
|
// single user of AC_PID by adding the parameter in the param
|
|
|
|
// table of the parent class. It is made public for this reason
|
|
|
|
AP_Float _slew_rate_tau;
|
|
|
|
|
2020-09-24 00:28:24 -03:00
|
|
|
SlewLimiter _slew_limiter{_slew_rate_max, _slew_rate_tau};
|
2015-02-11 08:06:04 -04:00
|
|
|
|
|
|
|
// flags
|
|
|
|
struct ac_pid_flags {
|
2019-06-27 06:33:15 -03:00
|
|
|
bool _reset_filter :1; // true when input filter should be reset during next call to set_input
|
2023-12-11 14:44:30 -04:00
|
|
|
bool _I_set :1; // true if if the I terms has been set externally including zeroing
|
2015-02-11 08:06:04 -04:00
|
|
|
} _flags;
|
|
|
|
|
|
|
|
// internal variables
|
2019-06-27 06:33:15 -03:00
|
|
|
float _integrator; // integrator value
|
|
|
|
float _target; // target value to enable filtering
|
|
|
|
float _error; // error value to enable filtering
|
|
|
|
float _derivative; // derivative value to enable filtering
|
2021-03-31 21:12:11 -03:00
|
|
|
int8_t _slew_limit_scale;
|
2023-07-27 10:58:50 -03:00
|
|
|
float _target_derivative; // target derivative value to enable dff
|
2023-10-01 14:21:00 -03:00
|
|
|
#if AP_FILTER_ENABLED
|
|
|
|
NotchFilterFloat* _target_notch;
|
|
|
|
NotchFilterFloat* _error_notch;
|
2023-07-27 10:58:50 -03:00
|
|
|
#endif
|
2015-05-21 22:43:43 -03:00
|
|
|
|
2022-03-03 23:29:46 -04:00
|
|
|
AP_PIDInfo _pid_info;
|
2022-12-29 22:20:32 -04:00
|
|
|
|
|
|
|
private:
|
|
|
|
const float default_kp;
|
|
|
|
const float default_ki;
|
|
|
|
const float default_kd;
|
|
|
|
const float default_kff;
|
2023-07-27 10:58:50 -03:00
|
|
|
const float default_kdff;
|
2022-12-29 22:20:32 -04:00
|
|
|
const float default_kimax;
|
|
|
|
const float default_filt_T_hz;
|
|
|
|
const float default_filt_E_hz;
|
|
|
|
const float default_filt_D_hz;
|
|
|
|
const float default_slew_rate_max;
|
2012-01-29 01:21:43 -04:00
|
|
|
};
|