Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Real-time collaboration for Jupyter Notebooks, Linux Terminals, LaTeX, VS Code, R IDE, and more,
all in one place. Commercial Alternative to JupyterHub.
Path: blob/master/libraries/AC_PID/AC_PID_Basic.cpp
Views: 1798
/// @file AC_PID_Basic.cpp1/// @brief Generic PID algorithm23#include <AP_Math/AP_Math.h>4#include <AP_InternalError/AP_InternalError.h>5#include "AC_PID_Basic.h"67#define AC_PID_Basic_FILT_E_HZ_MIN 0.01f // minimum input filter frequency8#define AC_PID_Basic_FILT_D_HZ_MIN 0.005f // minimum input filter frequency910const AP_Param::GroupInfo AC_PID_Basic::var_info[] = {11// @Param: P12// @DisplayName: PID Proportional Gain13// @Description: P Gain which produces an output value that is proportional to the current error value14AP_GROUPINFO_FLAGS_DEFAULT_POINTER("P", 0, AC_PID_Basic, _kp, default_kp),1516// @Param: I17// @DisplayName: PID Integral Gain18// @Description: I Gain which produces an output that is proportional to both the magnitude and the duration of the error19AP_GROUPINFO_FLAGS_DEFAULT_POINTER("I", 1, AC_PID_Basic, _ki, default_ki),2021// @Param: IMAX22// @DisplayName: PID Integral Maximum23// @Description: The maximum/minimum value that the I term can output24AP_GROUPINFO_FLAGS_DEFAULT_POINTER("IMAX", 2, AC_PID_Basic, _kimax, default_kimax),2526// @Param: FLTE27// @DisplayName: PID Error filter frequency in Hz28// @Description: Error filter frequency in Hz29// @Units: Hz30AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTE", 3, AC_PID_Basic, _filt_E_hz, default_filt_E_hz),3132// @Param: D33// @DisplayName: PID Derivative Gain34// @Description: D Gain which produces an output that is proportional to the rate of change of the error35AP_GROUPINFO_FLAGS_DEFAULT_POINTER("D", 4, AC_PID_Basic, _kd, default_kd),3637// @Param: FLTD38// @DisplayName: D term filter frequency in Hz39// @Description: D term filter frequency in Hz40// @Units: Hz41AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FLTD", 5, AC_PID_Basic, _filt_D_hz, default_filt_D_hz),4243// @Param: FF44// @DisplayName: PID Feed Forward Gain45// @Description: FF Gain which produces an output that is proportional to the magnitude of the target46AP_GROUPINFO_FLAGS_DEFAULT_POINTER("FF", 6, AC_PID_Basic, _kff, default_kff),4748AP_GROUPEND49};5051// Constructor52AC_PID_Basic::AC_PID_Basic(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_E_hz, float initial_filt_D_hz) :53default_kp(initial_p),54default_ki(initial_i),55default_kd(initial_d),56default_kff(initial_ff),57default_kimax(initial_imax),58default_filt_E_hz(initial_filt_E_hz),59default_filt_D_hz(initial_filt_D_hz)60{61// load parameter values from eeprom62AP_Param::setup_object_defaults(this, var_info);6364// reset input filter to first value received65_reset_filter = true;66}6768float AC_PID_Basic::update_all(float target, float measurement, float dt, bool limit)69{70return update_all(target, measurement, dt, (limit && is_negative(_integrator)), (limit && is_positive(_integrator)));71}7273// update_all - set target and measured inputs to PID controller and calculate outputs74// target and error are filtered75// the derivative is then calculated and filtered76// the integral is then updated based on the setting of the limit flag77float AC_PID_Basic::update_all(float target, float measurement, float dt, bool limit_neg, bool limit_pos)78{79// don't process inf or NaN80if (!isfinite(target) || isnan(target) ||81!isfinite(measurement) || isnan(measurement)) {82INTERNAL_ERROR(AP_InternalError::error_t::invalid_arg_or_result);83return 0.0f;84}8586_target = target;8788// reset input filter to value received89if (_reset_filter) {90_reset_filter = false;91_error = _target - measurement;92_derivative = 0.0f;93} else {94float error_last = _error;95_error += get_filt_E_alpha(dt) * ((_target - measurement) - _error);9697// calculate and filter derivative98if (is_positive(dt)) {99float derivative = (_error - error_last) / dt;100_derivative += get_filt_D_alpha(dt) * (derivative - _derivative);101}102}103104// update I term105update_i(dt, limit_neg, limit_pos);106107const float P_out = _error * _kp;108const float D_out = _derivative * _kd;109110_pid_info.target = _target;111_pid_info.actual = measurement;112_pid_info.error = _error;113_pid_info.P = _error * _kp;114_pid_info.I = _integrator;115_pid_info.D = _derivative * _kd;116_pid_info.FF = _target * _kff;117118return P_out + _integrator + D_out + _target * _kff;119}120121// update_i - update the integral122// if limit_neg is true, the integral can only increase123// if limit_pos is true, the integral can only decrease124void AC_PID_Basic::update_i(float dt, bool limit_neg, bool limit_pos)125{126if (!is_zero(_ki)) {127// Ensure that integrator can only be reduced if the output is saturated128if (!((limit_neg && is_negative(_error)) || (limit_pos && is_positive(_error)))) {129_integrator += ((float)_error * _ki) * dt;130_integrator = constrain_float(_integrator, -_kimax, _kimax);131}132} else {133_integrator = 0.0f;134}135}136137void AC_PID_Basic::reset_I()138{139_integrator = 0.0;140}141142// save_gains - save gains to eeprom143void AC_PID_Basic::save_gains()144{145_kp.save();146_ki.save();147_kd.save();148_kff.save();149_kimax.save();150_filt_E_hz.save();151_filt_D_hz.save();152}153154// get_filt_T_alpha - get the target filter alpha155float AC_PID_Basic::get_filt_E_alpha(float dt) const156{157return calc_lowpass_alpha_dt(dt, _filt_E_hz);158}159160// get_filt_D_alpha - get the derivative filter alpha161float AC_PID_Basic::get_filt_D_alpha(float dt) const162{163return calc_lowpass_alpha_dt(dt, _filt_D_hz);164}165166void AC_PID_Basic::set_integrator(float target, float measurement, float i)167{168set_integrator(target - measurement, i);169}170171void AC_PID_Basic::set_integrator(float error, float i)172{173set_integrator(i - error * _kp);174}175176void AC_PID_Basic::set_integrator(float i)177{178_integrator = constrain_float(i, -_kimax, _kimax);179}180181182