AP_YawController.h 1.3 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859
  1. #pragma once
  2. #include <AP_AHRS/AP_AHRS.h>
  3. #include <AP_Common/AP_Common.h>
  4. #include <AP_Vehicle/AP_Vehicle.h>
  5. #include <AP_Logger/AP_Logger.h>
  6. #include <cmath>
  7. class AP_YawController {
  8. public:
  9. AP_YawController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
  10. : aparm(parms)
  11. , _ahrs(ahrs)
  12. {
  13. AP_Param::setup_object_defaults(this, var_info);
  14. _pid_info.target = 0;
  15. _pid_info.FF = 0;
  16. _pid_info.P = 0;
  17. }
  18. /* Do not allow copies */
  19. AP_YawController(const AP_YawController &other) = delete;
  20. AP_YawController &operator=(const AP_YawController&) = delete;
  21. int32_t get_servo_out(float scaler, bool disable_integrator);
  22. void reset_I();
  23. /*
  24. reduce the integrator, used when we have a low scale factor in a quadplane hover
  25. */
  26. void decay_I() {
  27. // this reduces integrator by 95% over 2s
  28. _pid_info.I *= 0.995f;
  29. }
  30. const AP_Logger::PID_Info& get_pid_info(void) const {return _pid_info; }
  31. static const struct AP_Param::GroupInfo var_info[];
  32. private:
  33. const AP_Vehicle::FixedWing &aparm;
  34. AP_Float _K_A;
  35. AP_Float _K_I;
  36. AP_Float _K_D;
  37. AP_Float _K_FF;
  38. AP_Int16 _imax;
  39. uint32_t _last_t;
  40. float _last_out;
  41. float _last_rate_hp_out;
  42. float _last_rate_hp_in;
  43. float _K_D_last;
  44. float _integrator;
  45. AP_Logger::PID_Info _pid_info;
  46. AP_AHRS &_ahrs;
  47. };