PID.h 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124
  1. /// @file PID.h
  2. /// @brief Generic PID algorithm, with EEPROM-backed storage of constants.
  3. #pragma once
  4. #include <AP_Common/AP_Common.h>
  5. #include <AP_Param/AP_Param.h>
  6. #include <AP_Logger/AP_Logger.h>
  7. #include <stdlib.h>
  8. #include <cmath>
  9. /// @class PID
  10. /// @brief Object managing one PID control
  11. class PID {
  12. public:
  13. PID(const float & initial_p = 0.0f,
  14. const float & initial_i = 0.0f,
  15. const float & initial_d = 0.0f,
  16. const int16_t & initial_imax = 0)
  17. {
  18. AP_Param::setup_object_defaults(this, var_info);
  19. _kp = initial_p;
  20. _ki = initial_i;
  21. _kd = initial_d;
  22. _imax = initial_imax;
  23. // set _last_derivative as invalid when we startup
  24. _last_derivative = NAN;
  25. }
  26. /// Iterate the PID, return the new control value
  27. ///
  28. /// Positive error produces positive output.
  29. ///
  30. /// @param error The measured error value
  31. /// @param scaler An arbitrary scale factor
  32. ///
  33. /// @returns The updated control output.
  34. ///
  35. float get_pid(float error, float scaler = 1.0);
  36. /// Reset the whole PID state
  37. //
  38. void reset();
  39. /// Reset the PID integrator
  40. ///
  41. void reset_I();
  42. /// Load gain properties
  43. ///
  44. void load_gains();
  45. /// Save gain properties
  46. ///
  47. void save_gains();
  48. /// @name parameter accessors
  49. //@{
  50. /// Overload the function call operator to permit relatively easy initialisation
  51. void operator () (const float p,
  52. const float i,
  53. const float d,
  54. const int16_t imaxval) {
  55. _kp = p; _ki = i; _kd = d; _imax = imaxval;
  56. }
  57. float kP() const {
  58. return _kp.get();
  59. }
  60. float kI() const {
  61. return _ki.get();
  62. }
  63. float kD() const {
  64. return _kd.get();
  65. }
  66. int16_t imax() const {
  67. return _imax.get();
  68. }
  69. void kP(const float v) {
  70. _kp.set(v);
  71. }
  72. void kI(const float v) {
  73. _ki.set(v);
  74. }
  75. void kD(const float v) {
  76. _kd.set(v);
  77. }
  78. void imax(const int16_t v) {
  79. _imax.set(abs(v));
  80. }
  81. float get_integrator() const {
  82. return _integrator;
  83. }
  84. static const struct AP_Param::GroupInfo var_info[];
  85. const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; }
  86. private:
  87. AP_Float _kp;
  88. AP_Float _ki;
  89. AP_Float _kd;
  90. AP_Int16 _imax;
  91. float _integrator;///< integrator value
  92. float _last_error;///< last error for derivative
  93. float _last_derivative;///< last derivative for low-pass filter
  94. uint32_t _last_t;///< last time get_pid() was called in millis
  95. float _get_pid(float error, uint16_t dt, float scaler);
  96. AP_Logger::PID_Info _pid_info {};
  97. /// Low pass filter cut frequency for derivative calculation.
  98. ///
  99. /// 20 Hz because anything over that is probably noise, see
  100. /// http://en.wikipedia.org/wiki/Low-pass_filter.
  101. ///
  102. static const uint8_t _fCut = 20;
  103. };