AP_Gripper_Servo.cpp 2.5 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697
  1. #include <AP_Gripper/AP_Gripper_Servo.h>
  2. #include <GCS_MAVLink/GCS.h>
  3. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  4. #include <SITL/SITL.h>
  5. #endif
  6. extern const AP_HAL::HAL& hal;
  7. void AP_Gripper_Servo::init_gripper()
  8. {
  9. // move the servo to the release position
  10. release();
  11. }
  12. void AP_Gripper_Servo::grab()
  13. {
  14. // move the servo to the grab position
  15. SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
  16. action_timestamp = AP_HAL::millis();
  17. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  18. is_releasing = false;
  19. is_released = true;
  20. #endif
  21. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing");
  22. }
  23. void AP_Gripper_Servo::release()
  24. {
  25. // move the servo to the release position
  26. SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
  27. action_timestamp = AP_HAL::millis();
  28. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  29. is_releasing = true;
  30. is_released = false;
  31. #endif
  32. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing");
  33. }
  34. bool AP_Gripper_Servo::has_state_pwm(const uint16_t pwm) const
  35. {
  36. // return true if servo is in position represented by pwm
  37. uint16_t current_pwm;
  38. if (!SRV_Channels::get_output_pwm(SRV_Channel::k_gripper, current_pwm)) {
  39. // function not assigned to a channel, perhaps?
  40. return false;
  41. }
  42. if (current_pwm != pwm) {
  43. // last action did not set pwm to the current value
  44. // (e.g. last action was a grab not a release)
  45. return false;
  46. }
  47. if (AP_HAL::millis() - action_timestamp < action_time) {
  48. // servo still moving....
  49. return false;
  50. }
  51. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  52. if (is_releasing) {
  53. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load released");
  54. } else {
  55. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbed");
  56. }
  57. #endif
  58. return true;
  59. }
  60. bool AP_Gripper_Servo::released() const
  61. {
  62. return has_state_pwm(config.release_pwm);
  63. }
  64. bool AP_Gripper_Servo::grabbed() const
  65. {
  66. return has_state_pwm(config.grab_pwm);
  67. }
  68. // type-specific periodic updates:
  69. void AP_Gripper_Servo::update_gripper() {
  70. #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
  71. if (is_releasing && !is_released) {
  72. is_released = released();
  73. } else if (!is_releasing && is_released) {
  74. is_released = !grabbed();
  75. }
  76. #endif
  77. };
  78. bool AP_Gripper_Servo::valid() const
  79. {
  80. if (!AP_Gripper_Backend::valid()) {
  81. return false;
  82. }
  83. if (!SRV_Channels::function_assigned(SRV_Channel::k_gripper)) {
  84. return false;
  85. }
  86. return true;
  87. }