AC_HELI_PID.h 1.0 KB

12345678910111213141516171819202122232425262728293031
  1. #pragma once
  2. /// @file AC_HELI_PID.h
  3. /// @brief Helicopter Specific Rate 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. #include "AC_PID.h"
  9. static const float AC_PID_LEAK_MIN = 0.1f; // Default I-term Leak Minimum
  10. /// @class AC_HELI_PID
  11. /// @brief Heli PID control class
  12. class AC_HELI_PID : public AC_PID {
  13. public:
  14. /// Constructor for PID
  15. AC_HELI_PID(float initial_p, float initial_i, float initial_d, float initial_ff, float initial_imax, float initial_filt_T_hz, float initial_filt_E_hz, float initial_filt_D_hz, float dt);
  16. /// update_leaky_i - replacement for get_i but output is leaded at leak_rate
  17. void update_leaky_i(float leak_rate);
  18. static const struct AP_Param::GroupInfo var_info[];
  19. private:
  20. AP_Float _leak_min;
  21. float _last_requested_rate; // Requested rate from last iteration, used to calculate rate change of requested rate
  22. };