AC_PID_2D.h 3.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104
  1. #pragma once
  2. /// @file AC_PID_2D.h
  3. /// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Param/AP_Param.h>
  6. #include <stdlib.h>
  7. #include <cmath>
  8. /// @class AC_PID_2D
  9. /// @brief Copter PID control class
  10. class AC_PID_2D {
  11. public:
  12. // Constructor for PID
  13. AC_PID_2D(float initial_p, float initial_i, float initial_d, float initial_imax, float initial_filt_hz, float initial_filt_d_hz, float dt);
  14. // set_dt - set time step in seconds
  15. void set_dt(float dt);
  16. // set_input - set input to PID controller
  17. // input is filtered before the PID controllers are run
  18. // this should be called before any other calls to get_p, get_i or get_d
  19. void set_input(const Vector2f &input);
  20. void set_input(const Vector3f &input) { set_input(Vector2f(input.x, input.y)); }
  21. // get_pi - get results from pid controller
  22. Vector2f get_pid();
  23. Vector2f get_p() const;
  24. Vector2f get_i();
  25. Vector2f get_i_shrink(); // get_i but do not allow integrator to grow (it may shrink)
  26. Vector2f get_d();
  27. // reset_I - reset the integrator
  28. void reset_I();
  29. // reset_filter - input and D term filter will be reset to the next value provided to set_input()
  30. void reset_filter();
  31. // load gain from eeprom
  32. void load_gains();
  33. // save gain to eeprom
  34. void save_gains();
  35. // get accessors
  36. AP_Float &kP() { return _kp; }
  37. AP_Float &kI() { return _ki; }
  38. float imax() const { return _imax.get(); }
  39. float filt_hz() const { return _filt_hz.get(); }
  40. float get_filt_alpha() const { return _filt_alpha; }
  41. float filt_d_hz() const { return _filt_d_hz.get(); }
  42. float get_filt_alpha_D() const { return _filt_alpha_d; }
  43. // set accessors
  44. void kP(const float v) { _kp.set(v); }
  45. void kI(const float v) { _ki.set(v); }
  46. void kD(const float v) { _kd.set(v); }
  47. void imax(const float v) { _imax.set(fabsf(v)); }
  48. void filt_hz(const float v);
  49. void filt_d_hz(const float v);
  50. Vector2f get_integrator() const { return _integrator; }
  51. void set_integrator(const Vector2f &i) { _integrator = i; }
  52. void set_integrator(const Vector3f &i) { _integrator.x = i.x; _integrator.y = i.y; }
  53. // parameter var table
  54. static const struct AP_Param::GroupInfo var_info[];
  55. protected:
  56. // set_input_filter_d - set input to PID controller
  57. // only input to the D portion of the controller is filtered
  58. // this should be called before any other calls to get_p, get_i or get_d
  59. void set_input_filter_d(const Vector2f& input_delta);
  60. // calc_filt_alpha - recalculate the input filter alpha
  61. void calc_filt_alpha();
  62. // calc_filt_alpha - recalculate the input filter alpha
  63. void calc_filt_alpha_d();
  64. // parameters
  65. AP_Float _kp;
  66. AP_Float _ki;
  67. AP_Float _kd;
  68. AP_Float _imax;
  69. AP_Float _filt_hz; // PID Input filter frequency in Hz
  70. AP_Float _filt_d_hz; // D term filter frequency in Hz
  71. // flags
  72. struct ac_pid_flags {
  73. bool _reset_filter : 1; // true when input filter should be reset during next call to set_input
  74. } _flags;
  75. // internal variables
  76. float _dt; // timestep in seconds
  77. float _filt_alpha; // input filter alpha
  78. float _filt_alpha_d; // input filter alpha
  79. Vector2f _integrator; // integrator value
  80. Vector2f _input; // last input for derivative
  81. Vector2f _derivative; // last derivative for low-pass filter
  82. };