AP_Gripper_EPM.cpp 4.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141
  1. /*
  2. * AP_Gripper_EPM.cpp
  3. *
  4. * Created on: DEC 6, 2013
  5. * Author: Andreas Jochum
  6. * Pavel Kirienko <pavel.kirienko@zubax.com> - UAVCAN support
  7. * Peter Barker - moved into AP_Gripper_EPM
  8. */
  9. #include "AP_Gripper_EPM.h"
  10. #include <AP_HAL/AP_HAL.h>
  11. #include <AP_BoardConfig/AP_BoardConfig.h>
  12. #include <GCS_MAVLink/GCS.h>
  13. #ifdef UAVCAN_NODE_FILE
  14. #include <fcntl.h>
  15. #include <stdio.h>
  16. #endif
  17. extern const AP_HAL::HAL& hal;
  18. AP_Gripper_EPM::AP_Gripper_EPM(struct AP_Gripper::Backend_Config &_config) :
  19. AP_Gripper_Backend(_config) { }
  20. void AP_Gripper_EPM::init_gripper()
  21. {
  22. #ifdef UAVCAN_NODE_FILE
  23. _uavcan_fd = ::open(UAVCAN_NODE_FILE, O_CLOEXEC);
  24. // http://ardupilot.org/dev/docs/learning-ardupilot-uarts-and-the-console.html
  25. ::printf("EPM: UAVCAN fd %d\n", _uavcan_fd);
  26. #endif
  27. // initialise the EPM to the neutral position
  28. neutral();
  29. }
  30. // Refer to http://uavcan.org/Specification/7._List_of_standard_data_types/#uavcanequipmenthardpoint
  31. struct UAVCANCommand {
  32. uint8_t hardpoint_id = 0;
  33. uint16_t command = 0;
  34. };
  35. // grab - move the epm pwm output to the grab position
  36. void AP_Gripper_EPM::grab()
  37. {
  38. // flag we are active and grabbing cargo
  39. config.state = AP_Gripper::STATE_GRABBING;
  40. // capture time
  41. _last_grab_or_release = AP_HAL::millis();
  42. #ifdef UAVCAN_IOCS_HARDPOINT_SET
  43. if (should_use_uavcan()) {
  44. const UAVCANCommand cmd = make_uavcan_command(1);
  45. (void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
  46. }
  47. else
  48. #endif
  49. {
  50. // move the servo output to the grab position
  51. SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.grab_pwm);
  52. }
  53. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load grabbing");
  54. }
  55. // release - move epm pwm output to the release position
  56. void AP_Gripper_EPM::release()
  57. {
  58. // flag we are releasing cargo
  59. config.state = AP_Gripper::STATE_RELEASING;
  60. // capture time
  61. _last_grab_or_release = AP_HAL::millis();
  62. #ifdef UAVCAN_IOCS_HARDPOINT_SET
  63. if (should_use_uavcan()) {
  64. const UAVCANCommand cmd = make_uavcan_command(0);
  65. (void)ioctl(_uavcan_fd, UAVCAN_IOCS_HARDPOINT_SET, reinterpret_cast<unsigned long>(&cmd));
  66. }
  67. else
  68. #endif
  69. {
  70. // move the servo to the release position
  71. SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.release_pwm);
  72. }
  73. gcs().send_text(MAV_SEVERITY_INFO, "Gripper load releasing");
  74. }
  75. // neutral - return the epm pwm output to the neutral position
  76. void AP_Gripper_EPM::neutral()
  77. {
  78. if (!should_use_uavcan()) {
  79. // move the servo to the off position
  80. SRV_Channels::set_output_pwm(SRV_Channel::k_gripper, config.neutral_pwm);
  81. }
  82. }
  83. // update - moves the pwm back to neutral after the timeout has passed
  84. // should be called at at least 10hz
  85. void AP_Gripper_EPM::update_gripper()
  86. {
  87. // move EPM PWM output back to neutral after the last grab or release
  88. if (AP_HAL::millis() - _last_grab_or_release > EPM_RETURN_TO_NEUTRAL_MS) {
  89. if (config.state == AP_Gripper::STATE_GRABBING) {
  90. neutral();
  91. config.state = AP_Gripper::STATE_GRABBED;
  92. } else if (config.state == AP_Gripper::STATE_RELEASING) {
  93. neutral();
  94. config.state = AP_Gripper::STATE_RELEASED;
  95. }
  96. }
  97. // re-grab the cargo intermittently
  98. if (config.state == AP_Gripper::STATE_GRABBED &&
  99. (config.regrab_interval > 0) &&
  100. (AP_HAL::millis() - _last_grab_or_release > ((uint32_t)config.regrab_interval * 1000))) {
  101. grab();
  102. }
  103. }
  104. UAVCANCommand AP_Gripper_EPM::make_uavcan_command(uint16_t command) const
  105. {
  106. UAVCANCommand cmd;
  107. cmd.hardpoint_id = config.uavcan_hardpoint_id;
  108. cmd.command = command;
  109. return cmd;
  110. }
  111. bool AP_Gripper_EPM::released() const
  112. {
  113. // we assume instanteous releasing ATM:
  114. return (config.state == AP_Gripper::STATE_GRABBED ||
  115. config.state == AP_Gripper::STATE_GRABBING);
  116. }
  117. bool AP_Gripper_EPM::grabbed() const
  118. {
  119. // we assume instanteous grabbing ATM:
  120. return (config.state == AP_Gripper::STATE_GRABBED ||
  121. config.state == AP_Gripper::STATE_GRABBING);
  122. }