AP_Gripper.cpp 4.4 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161
  1. #include "AP_Gripper.h"
  2. #include "AP_Gripper_Servo.h"
  3. #include "AP_Gripper_EPM.h"
  4. extern const AP_HAL::HAL& hal;
  5. #define GRIPPER_GRAB_PWM_DEFAULT 1900
  6. #define GRIPPER_RELEASE_PWM_DEFAULT 1100
  7. // EPM PWM definitions
  8. #define GRIPPER_NEUTRAL_PWM_DEFAULT 1500
  9. #define GRIPPER_REGRAB_DEFAULT 0 // default re-grab interval (in seconds) to ensure cargo is securely held
  10. const AP_Param::GroupInfo AP_Gripper::var_info[] = {
  11. // @Param: ENABLE
  12. // @DisplayName: Gripper Enable/Disable
  13. // @Description: Gripper enable/disable
  14. // @User: Standard
  15. // @Values: 0:Disabled, 1:Enabled
  16. AP_GROUPINFO_FLAGS("ENABLE", 0, AP_Gripper, _enabled, 0, AP_PARAM_FLAG_ENABLE),
  17. // @Param: TYPE
  18. // @DisplayName: Gripper Type
  19. // @Description: Gripper enable/disable
  20. // @User: Standard
  21. // @Values: 0:None,1:Servo,2:EPM
  22. AP_GROUPINFO("TYPE", 1, AP_Gripper, config.type, 0),
  23. // @Param: GRAB
  24. // @DisplayName: Gripper Grab PWM
  25. // @Description: PWM value in microseconds sent to Gripper to initiate grabbing the cargo
  26. // @User: Advanced
  27. // @Range: 1000 2000
  28. // @Units: PWM
  29. AP_GROUPINFO("GRAB", 2, AP_Gripper, config.grab_pwm, GRIPPER_GRAB_PWM_DEFAULT),
  30. // @Param: RELEASE
  31. // @DisplayName: Gripper Release PWM
  32. // @Description: PWM value in microseconds sent to Gripper to release the cargo
  33. // @User: Advanced
  34. // @Range: 1000 2000
  35. // @Units: PWM
  36. AP_GROUPINFO("RELEASE", 3, AP_Gripper, config.release_pwm, GRIPPER_RELEASE_PWM_DEFAULT),
  37. // @Param: NEUTRAL
  38. // @DisplayName: Neutral PWM
  39. // @Description: PWM value in microseconds sent to grabber when not grabbing or releasing
  40. // @User: Advanced
  41. // @Range: 1000 2000
  42. // @Units: PWM
  43. AP_GROUPINFO("NEUTRAL", 4, AP_Gripper, config.neutral_pwm, GRIPPER_NEUTRAL_PWM_DEFAULT),
  44. // @Param: REGRAB
  45. // @DisplayName: Gripper Regrab interval
  46. // @Description: Time in seconds that gripper will regrab the cargo to ensure grip has not weakened; 0 to disable
  47. // @User: Advanced
  48. // @Range: 0 255
  49. // @Units: s
  50. AP_GROUPINFO("REGRAB", 5, AP_Gripper, config.regrab_interval, GRIPPER_REGRAB_DEFAULT),
  51. // @Param: UAVCAN_ID
  52. // @DisplayName: EPM UAVCAN Hardpoint ID
  53. // @Description: Refer to https://docs.zubax.com/opengrab_epm_v3#UAVCAN_interface
  54. // @User: Standard
  55. // @Range: 0 255
  56. AP_GROUPINFO("UAVCAN_ID", 6, AP_Gripper, config.uavcan_hardpoint_id, 0),
  57. AP_GROUPEND
  58. };
  59. AP_Gripper::AP_Gripper()
  60. {
  61. if (_singleton) {
  62. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  63. AP_HAL::panic("Too many grippers");
  64. #endif
  65. return;
  66. }
  67. _singleton = this;
  68. AP_Param::setup_object_defaults(this, var_info);
  69. }
  70. /*
  71. * Get the AP_Gripper singleton
  72. */
  73. AP_Gripper *AP_Gripper::_singleton = nullptr;
  74. AP_Gripper *AP_Gripper::get_singleton()
  75. {
  76. return _singleton;
  77. }
  78. void AP_Gripper::init()
  79. {
  80. // return immediately if not enabled
  81. if (!_enabled.get()) {
  82. return;
  83. }
  84. switch(config.type.get()) {
  85. case 0:
  86. break;
  87. case 1:
  88. backend = new AP_Gripper_Servo(config);
  89. break;
  90. case 2:
  91. backend = new AP_Gripper_EPM(config);
  92. break;
  93. default:
  94. break;
  95. }
  96. if (backend != nullptr) {
  97. backend->init();
  98. }
  99. }
  100. // update - should be called at at least 10hz
  101. #define PASS_TO_BACKEND(function_name) \
  102. void AP_Gripper::function_name() \
  103. { \
  104. if (!enabled()) { \
  105. return; \
  106. } \
  107. if (backend != nullptr) { \
  108. backend->function_name(); \
  109. } \
  110. }
  111. PASS_TO_BACKEND(grab)
  112. PASS_TO_BACKEND(release)
  113. PASS_TO_BACKEND(update)
  114. #undef PASS_TO_BACKEND
  115. #define PASS_TO_BACKEND(function_name) \
  116. bool AP_Gripper::function_name() const \
  117. { \
  118. if (!enabled()) { \
  119. return false; \
  120. } \
  121. if (backend != nullptr) { \
  122. return backend->function_name(); \
  123. } \
  124. return false; \
  125. }
  126. PASS_TO_BACKEND(valid)
  127. PASS_TO_BACKEND(released)
  128. PASS_TO_BACKEND(grabbed)
  129. #undef PASS_TO_BACKEND
  130. namespace AP {
  131. AP_Gripper *gripper()
  132. {
  133. return AP_Gripper::get_singleton();
  134. }
  135. };