AP_Winch.cpp 4.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. #include "AP_Winch.h"
  2. #include "AP_Winch_Servo.h"
  3. extern const AP_HAL::HAL& hal;
  4. const AP_Param::GroupInfo AP_Winch::var_info[] = {
  5. // @Param: ENABLE
  6. // @DisplayName: Winch enable/disable
  7. // @Description: Winch enable/disable
  8. // @User: Standard
  9. // @Values: 0:Disabled, 1:Enabled
  10. AP_GROUPINFO_FLAGS("_ENABLE", 0, AP_Winch, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  11. // @Param: TYPE
  12. // @DisplayName: Winch Type
  13. // @Description: Winch Type
  14. // @User: Standard
  15. // @Values: 1:Servo with encoder
  16. AP_GROUPINFO("_TYPE", 1, AP_Winch, config.type, 1),
  17. // @Param: _RATE_MAX
  18. // @DisplayName: Winch deploy or retract rate maximum
  19. // @Description: Winch deploy or retract rate maximum. Set to maximum rate with no load.
  20. // @User: Standard
  21. // @Range: 0 10
  22. // @Units: m/s
  23. AP_GROUPINFO("_RATE_MAX", 2, AP_Winch, config.rate_max, 1.0f),
  24. // @Param: _POS_P
  25. // @DisplayName: Winch control position error P gain
  26. // @Description: Winch control position error P gain
  27. // @Range: 0.01 10.0
  28. // @User: Standard
  29. AP_GROUPINFO("_POS_P", 3, AP_Winch, config.pos_p, AP_WINCH_POS_P),
  30. // @Param: _RATE_P
  31. // @DisplayName: Winch control rate P gain
  32. // @Description: Winch control rate P gain. Converts rate error (in radians/sec) to pwm output (in the range -1 to +1)
  33. // @Range: 0.100 2.000
  34. // @User: Standard
  35. // @Param: _RATE_I
  36. // @DisplayName: Winch control I gain
  37. // @Description: Winch control I gain. Corrects long term error between the desired rate (in rad/s) and actual
  38. // @Range: 0.000 2.000
  39. // @User: Standard
  40. // @Param: _RATE_IMAX
  41. // @DisplayName: Winch control I gain maximum
  42. // @Description: Winch control I gain maximum. Constrains the output (range -1 to +1) that the I term will generate
  43. // @Range: 0.000 1.000
  44. // @User: Standard
  45. // @Param: _RATE_D
  46. // @DisplayName: Winch control D gain
  47. // @Description: Winch control D gain. Compensates for short-term change in desired rate vs actual
  48. // @Range: 0.000 0.400
  49. // @User: Standard
  50. // @Param: _RATE_FILT
  51. // @DisplayName: Winch control filter frequency
  52. // @Description: Winch control input filter. Lower values reduce noise but add delay.
  53. // @Range: 1.000 100.000
  54. // @Units: Hz
  55. // @User: Standard
  56. AP_SUBGROUPINFO(config.rate_pid, "_RATE_", 4, AP_Winch, AC_PID),
  57. AP_GROUPEND
  58. };
  59. AP_Winch::AP_Winch()
  60. {
  61. AP_Param::setup_object_defaults(this, var_info);
  62. }
  63. // indicate whether this module is enabled
  64. bool AP_Winch::enabled() const
  65. {
  66. if (!_enabled) {
  67. return false;
  68. }
  69. return ((config.type > 0) && (backend != nullptr));
  70. }
  71. void AP_Winch::init(const AP_WheelEncoder *wheel_encoder)
  72. {
  73. // return immediately if not enabled
  74. if (!_enabled.get()) {
  75. return;
  76. }
  77. switch(config.type.get()) {
  78. case 0:
  79. break;
  80. case 1:
  81. backend = new AP_Winch_Servo(config);
  82. break;
  83. default:
  84. break;
  85. }
  86. if (backend != nullptr) {
  87. backend->init(wheel_encoder);
  88. }
  89. }
  90. // release specified length of cable (in meters) at the specified rate
  91. // if rate is zero, the RATE_MAX parameter value will be used
  92. void AP_Winch::release_length(float length, float rate)
  93. {
  94. config.length_desired = config.length_curr + length;
  95. config.state = STATE_POSITION;
  96. if (is_zero(rate)) {
  97. config.rate_desired = config.rate_max;
  98. } else {
  99. config.rate_desired = constrain_float(fabsf(rate), -get_rate_max(), get_rate_max());
  100. }
  101. }
  102. // deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops)
  103. void AP_Winch::set_desired_rate(float rate)
  104. {
  105. config.rate_desired = constrain_float(rate, -get_rate_max(), get_rate_max());
  106. config.state = STATE_RATE;
  107. }
  108. // update - should be called at at least 10hz
  109. #define PASS_TO_BACKEND(function_name) \
  110. void AP_Winch::function_name() \
  111. { \
  112. if (!enabled()) { \
  113. return; \
  114. } \
  115. if (backend != nullptr) { \
  116. backend->function_name(); \
  117. } \
  118. }
  119. PASS_TO_BACKEND(update)
  120. #undef PASS_TO_BACKEND