1
2
3
4
5
6
7
8
9
10
11
12
13
14
15 import rospy
16 import intera_dataflow
17 from intera_io import IODeviceInterface
18 from intera_core_msgs.msg import IONodeConfiguration
19
20
22 """
23 Interface class for a gripper on the Intera Research Robot.
24 """
25 MAX_POSITION = 0.041667
26 MIN_POSITION = 0.0
27 MAX_FORCE = 10.0
28 MIN_FORCE = 0.0
29 MAX_VELOCITY = 3.0
30 MIN_VELOCITY = 0.15
31
32 - def __init__(self, side="right", calibrate=True):
33 """
34 Constructor.
35
36 @type side: str
37 @param side: robot gripper name
38 @type calibrate: bool
39 @param calibrate: Attempts to calibrate the gripper when initializing class (defaults True)
40 """
41 self.devices = None
42 self.name = '_'.join([side, 'gripper'])
43 self.ee_config_sub = rospy.Subscriber('/io/end_effector/config', IONodeConfiguration, self._config_callback)
44
45 intera_dataflow.wait_for(
46 lambda: not self.devices is None, timeout=5.0,
47 timeout_msg=("Failed to get gripper. No gripper attached on the robot.")
48 )
49
50 self.gripper_io = IODeviceInterface("end_effector", self.name)
51 if self.has_error():
52 self.reboot()
53 calibrate = True
54 if calibrate and not self.is_calibrated():
55 self.calibrate()
56
58 """
59 config topic callback
60 """
61 if msg.devices != []:
62 if str(msg.devices[0].name) == self.name:
63 self.devices = msg
64
66 """
67 Power cycle the gripper, removing calibration information.
68
69 Basic call to the gripper reboot command. Waits for gripper to return
70 ready state but does not clear errors that could occur during boot.
71
72 @rtype: bool
73 @return: True if successfully Rebooted, False otherwise
74 """
75 return self.gripper_io.set_signal_value("reboot", True)
76
78 """
79 Set the gripper to stop executing command at the current
80 position, apply holding force.
81
82 @rtype: bool
83 @return: True if successfully Stopped, False otherwise
84 """
85 return self.gripper_io.set_signal_value("go", False)
86
88 """
89 Set the gripper to start executing command at the current
90 position, apply holding force.
91
92 @rtype: bool
93 @return: True if successfully Started, False otherwise
94 """
95 return self.gripper_io.set_signal_value("go", True)
96
98 """
99 Set the gripper position to open by providing opening position.
100 @type: float
101 @param: the postion of gripper in meters
102
103 @rtype: bool
104 @return: True if successfully set Position, False otherwise
105 """
106 return self.gripper_io.set_signal_value("position_m", position)
107
109 """
110 Set the gripper position to close by providing closing position.
111 @type: float
112 @param: the postion of gripper in meters
113
114 @rtype: bool
115 @return: True if successfully set Position, False otherwise
116 """
117 return self.gripper_io.set_signal_value("position_m", position)
118
120 """
121 Returns a bool describing whether the gripper is in an error state.
122 (True: Error detected, False: No errors)
123
124 @rtype: bool
125 @return: True if in error state, False otherwise
126 """
127 return self.gripper_io.get_signal_value("has_error")
128
130 """
131 Returns bool describing if the gripper ready, i.e. is
132 calibrated, not busy (as in resetting or rebooting), and
133 not moving.
134
135 @rtype: bool
136 @return: True if in ready state, False otherwise
137 """
138 return (self.is_calibrated() and not self.has_error()
139 and not self.is_moving())
140
142 """
143 Returns bool describing if the gripper is moving.
144
145 @rtype: bool
146 @return: True if in moving state, False otherwise
147 """
148 return self.gripper_io.get_signal_value("is_moving")
149
151 """
152 Returns bool describing if the gripper is gripping.
153
154 @rtype: bool
155 @return: True if in gripping state, False otherwise
156 """
157 return self.gripper_io.get_signal_value("is_gripping")
158
160 """
161 Returns bool describing if the gripper is calibrated.
162
163 @rtype: bool
164 @return: True if successfully calibrated, False otherwise
165 """
166 return self.gripper_io.get_signal_value("is_calibrated")
167
169 """
170 Calibrate the gripper in order to set maximum and
171 minimum travel distance.
172
173 @rtype: bool
174 @return: True if successfully calibrating, False otherwise
175 """
176 return self.gripper_io.set_signal_value("calibrate", True)
177
179 """
180 Returns float describing the gripper position in meters.
181
182 @rtype: float
183 @return: Current Position value in Meters (m)
184 """
185 return self.gripper_io.get_signal_value("position_response_m")
186
188 """
189 Set the position of gripper.
190 @type: float
191 @param: the postion of gripper in meters
192
193 @rtype: bool
194 @return: True if successfully set value, False otherwise
195 """
196 return self.gripper_io.set_signal_value("position_m", position)
197
199 """
200 Set the velocity at which the gripper position movement will execute.
201 @type: float
202 @param: the velocity of gripper in meters per second
203
204 @rtype: float
205 @return: Current Velocity value in Meters / second (m/s)
206 """
207 return self.gripper_io.set_signal_value("speed_mps", speed)
208
210 """
211 Returns the force sensed by the gripper in estimated Newtons.
212
213 @rtype: float
214 @return: Current Force value in Newton-Meters (N-m)
215 """
216 return self.gripper_io.get_signal_value("force_response_n")
217
219 """
220 Set holding force of successful gripper grasp.
221
222 Set the force at which the gripper will continue applying after a
223 position command has completed either from successfully achieving the
224 commanded position, or by exceeding the moving force threshold.
225
226 @type: float
227 @param: the holding force of gripper in newton
228
229 @rtype: bool
230 @return: True if successfully set value, False otherwise
231 """
232 return self.gripper_io.set_signal_value("holding_force_n", holding_force)
233
235 """
236 Set the weight of the object in kilograms.
237 @type: float
238 @param: the object weight in newton
239
240 @rtype: bool
241 @return: True if successfully set value, False otherwise
242 """
243 return self.gripper_io.set_signal_value("object_kg", object_weight)
244
246 """
247 Set the gripper dead zone describing the position error threshold
248 where a move will be considered successful.
249
250 @type: float
251 @param: the dead zone of gripper in meters
252
253 @rtype: bool
254 @return: True if successfully set value, False otherwise
255 """
256 return self.gripper_io.set_signal_value("dead_zone_m", dead_zone)
257