AP_WheelRateControl.h 3.2 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #include <AP_Common/AP_Common.h>
  15. #include <AP_Math/AP_Math.h>
  16. #include <AP_Param/AP_Param.h>
  17. #include <AC_PID/AC_PID.h>
  18. #include <AP_WheelEncoder/AP_WheelEncoder.h>
  19. // wheel rate control defaults
  20. #define AP_WHEEL_RATE_MAX_DEFAULT 12.0f // maximum wheel rotation rate in rad/sec (about 115rpm, 687deg/sec)
  21. #define AP_WHEEL_RATE_CONTROL_FF 8.00f
  22. #define AP_WHEEL_RATE_CONTROL_P 2.00f
  23. #define AP_WHEEL_RATE_CONTROL_I 2.00f
  24. #define AP_WHEEL_RATE_CONTROL_IMAX 1.00f
  25. #define AP_WHEEL_RATE_CONTROL_D 0.01f
  26. #define AP_WHEEL_RATE_CONTROL_FILT 0.00f
  27. #define AP_WHEEL_RATE_CONTROL_DT 0.02f
  28. #define AP_WHEEL_RATE_CONTROL_TIMEOUT_MS 200
  29. class AP_WheelRateControl {
  30. public:
  31. AP_WheelRateControl(const AP_WheelEncoder &wheel_encoder_ref);
  32. // returns true if a wheel encoder and rate control PID are available for this instance
  33. bool enabled(uint8_t instance);
  34. // get throttle output in the range -100 to +100 given a desired rate expressed as a percentage of the rate_max (-100 to +100)
  35. // instance can be 0 or 1
  36. float get_rate_controlled_throttle(uint8_t instance, float desired_rate_pct, float dt);
  37. // get rate maximum in radians/sec
  38. float get_rate_max_rads() const { return MAX(_rate_max, 0.0f); }
  39. // get pid objects for reporting
  40. AC_PID& get_pid(uint8_t instance);
  41. static const struct AP_Param::GroupInfo var_info[];
  42. private:
  43. // parameters
  44. AP_Int8 _enabled; // top level enable/disable control
  45. AP_Float _rate_max; // wheel maximum rotation rate in rad/s
  46. AC_PID _rate_pid0 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT);
  47. AC_PID _rate_pid1 = AC_PID(AP_WHEEL_RATE_CONTROL_P, AP_WHEEL_RATE_CONTROL_I, AP_WHEEL_RATE_CONTROL_D, AP_WHEEL_RATE_CONTROL_FF, AP_WHEEL_RATE_CONTROL_IMAX, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_FILT, AP_WHEEL_RATE_CONTROL_DT);
  48. // limit flags
  49. struct AP_MotorsUGV_limit {
  50. bool lower; // reached this instance's lower limit on last iteration
  51. bool upper; // reached this instance's upper limit on last iteration
  52. } _limit[2];
  53. // internal variables
  54. const AP_WheelEncoder& _wheel_encoder; // pointer to accompanying wheel encoder
  55. uint32_t _last_update_ms; // system time of last call to get_rate_controlled_throttle
  56. };