APM:Libraries
AP_Gripper_EPM.h
Go to the documentation of this file.
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 
14 #pragma once
15 
16 #include "AP_Gripper.h"
17 #include "AP_Gripper_Backend.h"
18 
20 
21 #define EPM_RETURN_TO_NEUTRAL_MS 500 // EPM PWM returns to neutral position this many milliseconds after grab or release
22 
26 public:
28 
29  // initialise the EPM
30  void init_gripper() override;
31 
32  // grab - move the EPM pwm output to the grab position
33  void grab() override;
34 
35  // release - move the EPM pwm output to the release position
36  void release() override;
37 
38  // grabbed - returns true if gripper in grabbed state
39  bool grabbed() const override;
40 
41  // released - returns true if gripper in released state
42  bool released() const override;
43 
44  // update - moves the pwm back to neutral after the timeout has passed
45  // should be called at at least 10hz
46  void update_gripper() override;
47 
48 private:
49 
50  // neutral - return the EPM pwm output to the neutral position
51  void neutral();
52 
53  bool should_use_uavcan() const { return _uavcan_fd >= 0; }
54 
55  struct UAVCANCommand make_uavcan_command(uint16_t command) const;
56 
57  // UAVCAN driver fd
58  int _uavcan_fd = -1;
59 
60  // internal variables
62 };
bool grabbed() const override
void update_gripper() override
uint32_t _last_grab_or_release
void grab() override
Class to manage the EPM_CargoGripper.
bool released() const override
void release() override
AP_Gripper_EPM(struct AP_Gripper::Backend_Config &_config)
bool should_use_uavcan() const
void init_gripper() override