AC_P.h 1.7 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566
  1. #pragma once
  2. /// @file AC_PD.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_P
  9. /// @brief Object managing one P controller
  10. class AC_P {
  11. public:
  12. /// Constructor for P that saves its settings to EEPROM
  13. ///
  14. /// @note PIs must be named to avoid either multiple parameters with the
  15. /// same name, or an overly complex constructor.
  16. ///
  17. /// @param initial_p Initial value for the P term.
  18. ///
  19. AC_P(const float &initial_p = 0.0f)
  20. {
  21. AP_Param::setup_object_defaults(this, var_info);
  22. _kp = initial_p;
  23. }
  24. /// Iterate the P controller, return the new control value
  25. ///
  26. /// Positive error produces positive output.
  27. ///
  28. /// @param error The measured error value
  29. /// @param dt The time delta in milliseconds (note
  30. /// that update interval cannot be more
  31. /// than 65.535 seconds due to limited range
  32. /// of the data type).
  33. ///
  34. /// @returns The updated control output.
  35. ///
  36. float get_p(float error) const;
  37. /// Load gain properties
  38. ///
  39. void load_gains();
  40. /// Save gain properties
  41. ///
  42. void save_gains();
  43. /// @name parameter accessors
  44. //@{
  45. /// Overload the function call operator to permit relatively easy initialisation
  46. void operator() (const float p) { _kp = p; }
  47. // accessors
  48. AP_Float &kP() { return _kp; }
  49. const AP_Float &kP() const { return _kp; }
  50. void kP(const float v) { _kp.set(v); }
  51. static const struct AP_Param::GroupInfo var_info[];
  52. private:
  53. AP_Float _kp;
  54. };