AP_Gripper_EPM.h 1.7 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253545556575859606162
  1. /*
  2. * AP_EPM.h
  3. *
  4. * Created on: DEC 06, 2013
  5. * Author: Andreas Jochum
  6. * Pavel Kirienko <pavel.kirienko@zubax.com> - UAVCAN support
  7. *
  8. * Set-up Wiki: http://copter.ardupilot.org/wiki/common-electro-permanent-magnet-gripper/
  9. * EPM docs: https://docs.zubax.com/opengrab_epm_v3
  10. */
  11. /// @file AP_EPM.h
  12. /// @brief AP_EPM control class
  13. #pragma once
  14. #include "AP_Gripper.h"
  15. #include "AP_Gripper_Backend.h"
  16. #include <SRV_Channel/SRV_Channel.h>
  17. #define EPM_RETURN_TO_NEUTRAL_MS 500 // EPM PWM returns to neutral position this many milliseconds after grab or release
  18. /// @class AP_Gripper_EPM
  19. /// @brief Class to manage the EPM_CargoGripper
  20. class AP_Gripper_EPM : public AP_Gripper_Backend {
  21. public:
  22. AP_Gripper_EPM(struct AP_Gripper::Backend_Config &_config);
  23. // initialise the EPM
  24. void init_gripper() override;
  25. // grab - move the EPM pwm output to the grab position
  26. void grab() override;
  27. // release - move the EPM pwm output to the release position
  28. void release() override;
  29. // grabbed - returns true if gripper in grabbed state
  30. bool grabbed() const override;
  31. // released - returns true if gripper in released state
  32. bool released() const override;
  33. // update - moves the pwm back to neutral after the timeout has passed
  34. // should be called at at least 10hz
  35. void update_gripper() override;
  36. private:
  37. // neutral - return the EPM pwm output to the neutral position
  38. void neutral();
  39. bool should_use_uavcan() const { return _uavcan_fd >= 0; }
  40. struct UAVCANCommand make_uavcan_command(uint16_t command) const;
  41. // UAVCAN driver fd
  42. int _uavcan_fd = -1;
  43. // internal variables
  44. uint32_t _last_grab_or_release;
  45. };