AP_Winch.h 3.3 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293
  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. // winch rate control default gains
  20. #define AP_WINCH_POS_P 1.00f
  21. #define AP_WINCH_RATE_P 1.00f
  22. #define AP_WINCH_RATE_I 0.50f
  23. #define AP_WINCH_RATE_IMAX 1.00f
  24. #define AP_WINCH_RATE_D 0.00f
  25. #define AP_WINCH_RATE_FILT 5.00f
  26. #define AP_WINCH_RATE_DT 0.10f
  27. class AP_Winch_Backend;
  28. class AP_Winch {
  29. friend class AP_Winch_Backend;
  30. friend class AP_Winch_Servo;
  31. public:
  32. AP_Winch();
  33. // indicate whether this module is enabled
  34. bool enabled() const;
  35. // initialise the winch
  36. void init(const AP_WheelEncoder *wheel_encoder = nullptr);
  37. // update the winch
  38. void update();
  39. // relax the winch so it does not attempt to maintain length or rate
  40. void relax() { config.state = STATE_RELAXED; }
  41. // get current line length
  42. float get_line_length() const { return config.length_curr; }
  43. // release specified length of cable (in meters) at the specified rate
  44. // if rate is zero, the RATE_MAX parameter value will be used
  45. void release_length(float length, float rate = 0.0f);
  46. // deploy line at specified speed in m/s (+ve deploys line, -ve retracts line, 0 stops)
  47. void set_desired_rate(float rate);
  48. // get rate maximum in m/s
  49. float get_rate_max() const { return MAX(config.rate_max, 0.0f); }
  50. static const struct AP_Param::GroupInfo var_info[];
  51. private:
  52. // parameters
  53. AP_Int8 _enabled; // grabber enable/disable
  54. // winch states
  55. typedef enum {
  56. STATE_RELAXED = 0, // winch is not operating
  57. STATE_POSITION, // moving or maintaining a target length
  58. STATE_RATE, // deploying or retracting at a target rate
  59. } winch_state;
  60. struct Backend_Config {
  61. AP_Int8 type; // winch type
  62. AP_Float rate_max; // deploy or retract rate maximum (in m/s).
  63. AP_Float pos_p; // position error P gain
  64. AC_PID rate_pid = AC_PID(AP_WINCH_RATE_P, AP_WINCH_RATE_I, AP_WINCH_RATE_D, 0.0f, AP_WINCH_RATE_IMAX, 0.0f, AP_WINCH_RATE_FILT, 0.0f, AP_WINCH_RATE_DT); // rate control PID
  65. winch_state state; // state of winch control (using target position or target rate)
  66. float length_curr; // current length of the line (in meters) that has been deployed
  67. float length_desired; // target desired length (in meters)
  68. float rate_desired; // target deploy rate (in m/s, +ve = deploying, -ve = retracting)
  69. } config;
  70. AP_Winch_Backend *backend;
  71. };