AP_RollController.h 1.9 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869
  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_AutoTune.h"
  6. #include <AP_Logger/AP_Logger.h>
  7. #include <AP_Math/AP_Math.h>
  8. class AP_RollController {
  9. public:
  10. AP_RollController(AP_AHRS &ahrs, const AP_Vehicle::FixedWing &parms)
  11. : aparm(parms)
  12. , autotune(gains, AP_AutoTune::AUTOTUNE_ROLL, parms)
  13. , _ahrs(ahrs)
  14. {
  15. AP_Param::setup_object_defaults(this, var_info);
  16. }
  17. /* Do not allow copies */
  18. AP_RollController(const AP_RollController &other) = delete;
  19. AP_RollController &operator=(const AP_RollController&) = delete;
  20. int32_t get_rate_out(float desired_rate, float scaler);
  21. int32_t get_servo_out(int32_t angle_err, 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. void autotune_start(void) { autotune.start(); }
  31. void autotune_restore(void) { autotune.stop(); }
  32. const AP_Logger::PID_Info& get_pid_info(void) const { return _pid_info; }
  33. static const struct AP_Param::GroupInfo var_info[];
  34. // tuning accessors
  35. void kP(float v) { gains.P.set(v); }
  36. void kI(float v) { gains.I.set(v); }
  37. void kD(float v) { gains.D.set(v); }
  38. void kFF(float v) { gains.FF.set(v); }
  39. AP_Float &kP(void) { return gains.P; }
  40. AP_Float &kI(void) { return gains.I; }
  41. AP_Float &kD(void) { return gains.D; }
  42. AP_Float &kFF(void) { return gains.FF; }
  43. private:
  44. const AP_Vehicle::FixedWing &aparm;
  45. AP_AutoTune::ATGains gains;
  46. AP_AutoTune autotune;
  47. uint32_t _last_t;
  48. float _last_out;
  49. AP_Logger::PID_Info _pid_info;
  50. int32_t _get_rate_out(float desired_rate, float scaler, bool disable_integrator);
  51. AP_AHRS &_ahrs;
  52. };