AC_PI_2D.h 3.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293
  1. #pragma once
  2. /// @file AC_PI_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. #define AC_PI_2D_FILT_HZ_DEFAULT 20.0f // default input filter frequency
  9. #define AC_PI_2D_FILT_HZ_MIN 0.01f // minimum input filter frequency
  10. /// @class AC_PI_2D
  11. /// @brief Copter PID control class
  12. class AC_PI_2D {
  13. public:
  14. // Constructor for PID
  15. AC_PI_2D(float initial_p, float initial_i, float initial_imax, float initial_filt_hz, float dt);
  16. // set_dt - set time step in seconds
  17. void set_dt(float dt);
  18. // set_input - set input to PID controller
  19. // input is filtered before the PID controllers are run
  20. // this should be called before any other calls to get_p, get_i or get_d
  21. void set_input(const Vector2f &input);
  22. void set_input(const Vector3f &input) { set_input(Vector2f(input.x, input.y)); }
  23. // get_pi - get results from pid controller
  24. Vector2f get_pi();
  25. Vector2f get_p() const;
  26. Vector2f get_i();
  27. Vector2f get_i_shrink(); // get_i but do not allow integrator to grow (it may shrink)
  28. // reset_I - reset the integrator
  29. void reset_I();
  30. // reset_filter - input filter will be reset to the next value provided to set_input()
  31. void reset_filter();
  32. // load gain from eeprom
  33. void load_gains();
  34. // save gain to eeprom
  35. void save_gains();
  36. /// operator function call for easy initialisation
  37. void operator() (float p, float i, float imaxval, float input_filt_hz, float dt);
  38. // get accessors
  39. AP_Float &kP() { return _kp; }
  40. AP_Float &kI() { return _ki; }
  41. float imax() const { return _imax.get(); }
  42. float filt_hz() const { return _filt_hz.get(); }
  43. float get_filt_alpha() const { return _filt_alpha; }
  44. // set accessors
  45. void kP(const float v) { _kp.set(v); }
  46. void kI(const float v) { _ki.set(v); }
  47. void imax(const float v) { _imax.set(fabsf(v)); }
  48. void filt_hz(const float v);
  49. Vector2f get_integrator() const { return _integrator; }
  50. void set_integrator(const Vector2f &i) { _integrator = i; }
  51. void set_integrator(const Vector3f &i) { _integrator.x = i.x; _integrator.y = i.y; }
  52. // parameter var table
  53. static const struct AP_Param::GroupInfo var_info[];
  54. protected:
  55. // calc_filt_alpha - recalculate the input filter alpha
  56. void calc_filt_alpha();
  57. // parameters
  58. AP_Float _kp;
  59. AP_Float _ki;
  60. AP_Float _imax;
  61. AP_Float _filt_hz; // PID Input filter frequency in Hz
  62. // flags
  63. struct ac_pid_flags {
  64. bool _reset_filter : 1; // true when input filter should be reset during next call to set_input
  65. } _flags;
  66. // internal variables
  67. float _dt; // timestep in seconds
  68. Vector2f _integrator; // integrator value
  69. Vector2f _input; // last input for derivative
  70. float _filt_alpha; // input filter alpha
  71. };