AP_WheelRateControl.cpp 5.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166
  1. #include <AP_WheelEncoder/AP_WheelRateControl.h>
  2. extern const AP_HAL::HAL& hal;
  3. const AP_Param::GroupInfo AP_WheelRateControl::var_info[] = {
  4. // @Param: _ENABLE
  5. // @DisplayName: Wheel rate control enable/disable
  6. // @Description: Enable or disable wheel rate control
  7. // @Values: 0:Disabled,1:Enabled
  8. // @User: Standard
  9. AP_GROUPINFO_FLAGS("_ENABLE", 1, AP_WheelRateControl, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  10. // @Param: _RATE_MAX
  11. // @DisplayName: Wheel max rotation rate
  12. // @Description: Wheel max rotation rate
  13. // @Units: rad/s
  14. // @Range: 0 200
  15. // @User: Standard
  16. AP_GROUPINFO("_RATE_MAX", 2, AP_WheelRateControl, _rate_max, AP_WHEEL_RATE_MAX_DEFAULT),
  17. // @Param: _RATE_FF
  18. // @DisplayName: Wheel rate control feed forward gain
  19. // @Description: Wheel rate control feed forward gain. Desired rate (in radians/sec) is multiplied by this constant and output to output (in the range -1 to +1)
  20. // @Range: 0.100 2.000
  21. // @User: Standard
  22. // @Param: _RATE_P
  23. // @DisplayName: Wheel rate control P gain
  24. // @Description: Wheel rate control P gain. Converts rate error (in radians/sec) to output (in the range -1 to +1)
  25. // @Range: 0.100 2.000
  26. // @User: Standard
  27. // @Param: _RATE_I
  28. // @DisplayName: Wheel rate control I gain
  29. // @Description: Wheel rate control I gain. Corrects long term error between the desired rate (in rad/s) and actual
  30. // @Range: 0.000 2.000
  31. // @User: Standard
  32. // @Param: _RATE_IMAX
  33. // @DisplayName: Wheel rate control I gain maximum
  34. // @Description: Wheel rate control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate
  35. // @Range: 0.000 1.000
  36. // @User: Standard
  37. // @Param: _RATE_D
  38. // @DisplayName: Wheel rate control D gain
  39. // @Description: Wheel rate control D gain. Compensates for short-term change in desired rate vs actual
  40. // @Range: 0.000 0.400
  41. // @User: Standard
  42. // @Param: _RATE_FILT
  43. // @DisplayName: Wheel rate control filter frequency
  44. // @Description: Wheel rate control input filter. Lower values reduce noise but add delay.
  45. // @Range: 1.000 100.000
  46. // @Units: Hz
  47. // @User: Standard
  48. AP_SUBGROUPINFO(_rate_pid0, "_RATE_", 3, AP_WheelRateControl, AC_PID),
  49. // @Param: 2_RATE_FF
  50. // @DisplayName: Wheel rate control feed forward gain
  51. // @Description: Wheel rate control feed forward gain. Desired rate (in radians/sec) is multiplied by this constant and output to output (in the range -1 to +1)
  52. // @Range: 0.100 2.000
  53. // @User: Standard
  54. // @Param: 2_RATE_P
  55. // @DisplayName: Wheel rate control P gain
  56. // @Description: Wheel rate control P gain. Converts rate error (in radians/sec) to output (in the range -1 to +1)
  57. // @Range: 0.100 2.000
  58. // @User: Standard
  59. // @Param: 2_RATE_I
  60. // @DisplayName: Wheel rate control I gain
  61. // @Description: Wheel rate control I gain. Corrects long term error between the desired rate (in rad/s) and actual
  62. // @Range: 0.000 2.000
  63. // @User: Standard
  64. // @Param: 2_RATE_IMAX
  65. // @DisplayName: Wheel rate control I gain maximum
  66. // @Description: Wheel rate control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate
  67. // @Range: 0.000 1.000
  68. // @User: Standard
  69. // @Param: 2_RATE_D
  70. // @DisplayName: Wheel rate control D gain
  71. // @Description: Wheel rate control D gain. Compensates for short-term change in desired rate vs actual
  72. // @Range: 0.000 0.400
  73. // @User: Standard
  74. // @Param: 2_RATE_FILT
  75. // @DisplayName: Wheel rate control filter frequency
  76. // @Description: Wheel rate control input filter. Lower values reduce noise but add delay.
  77. // @Range: 1.000 100.000
  78. // @Units: Hz
  79. // @User: Standard
  80. AP_SUBGROUPINFO(_rate_pid1, "2_RATE_", 4, AP_WheelRateControl, AC_PID),
  81. AP_GROUPEND
  82. };
  83. AP_WheelRateControl::AP_WheelRateControl(const AP_WheelEncoder &wheel_encoder_ref) :
  84. _wheel_encoder(wheel_encoder_ref)
  85. {
  86. AP_Param::setup_object_defaults(this, var_info);
  87. }
  88. // returns true if a wheel encoder and rate control PID are available for this instance
  89. bool AP_WheelRateControl::enabled(uint8_t instance)
  90. {
  91. // sanity check instance
  92. if ((instance > 1) || (_enabled == 0)) {
  93. return false;
  94. }
  95. // wheel encoder enabled
  96. return _wheel_encoder.enabled(instance);
  97. }
  98. // get throttle output in the range -100 to +100 given a desired rate expressed as a percentage of the rate_max (-100 to +100)
  99. // instance can be 0 or 1
  100. float AP_WheelRateControl::get_rate_controlled_throttle(uint8_t instance, float desired_rate_pct, float dt)
  101. {
  102. if (!enabled(instance)) {
  103. return 0;
  104. }
  105. // determine which PID instance to use
  106. AC_PID& rate_pid = (instance == 0) ? _rate_pid0 : _rate_pid1;
  107. // set PID's dt
  108. rate_pid.set_dt(dt);
  109. // check for timeout
  110. uint32_t now = AP_HAL::millis();
  111. if (now - _last_update_ms > AP_WHEEL_RATE_CONTROL_TIMEOUT_MS) {
  112. rate_pid.reset_filter();
  113. rate_pid.reset_I();
  114. _limit[instance].lower = false;
  115. _limit[instance].upper = false;
  116. }
  117. _last_update_ms = now;
  118. // convert desired rate as a percentage to radians/sec
  119. float desired_rate = desired_rate_pct / 100.0f * get_rate_max_rads();
  120. // get actual rate from wheeel encoder
  121. float actual_rate = _wheel_encoder.get_rate(instance);
  122. // constrain and set limit flags
  123. float output = rate_pid.update_all(desired_rate, actual_rate, (_limit[instance].lower || _limit[instance].upper));
  124. output += rate_pid.get_ff();
  125. // set limits for next iteration
  126. _limit[instance].upper = output >= 100.0f;
  127. _limit[instance].lower = output <= -100.0f;
  128. return output;
  129. }
  130. // get pid objects for reporting
  131. AC_PID& AP_WheelRateControl::get_pid(uint8_t instance)
  132. {
  133. if (instance == 0) {
  134. return _rate_pid0;
  135. } else {
  136. return _rate_pid1;
  137. }
  138. }