robotiq_2f_gripper_ctrl.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 
3 import numpy as np
4 
5 import roslib
6 roslib.load_manifest('robotiq_2f_gripper_control')
7 
8 import rospy
9 from robotiq_2f_gripper_control.msg import Robotiq2FGripper_robot_output as outputMsg
10 from robotiq_2f_gripper_control.msg import Robotiq2FGripper_robot_input as inputMsg
11 
12 class RobotiqCGripper(object):
13  def __init__(self):
14  self.cur_status = None
15  self.status_sub = rospy.Subscriber('Robotiq2FGripperRobotInput', inputMsg,
16  self._status_cb)
17  self.cmd_pub = rospy.Publisher('Robotiq2FGripperRobotOutput', outputMsg)
18 
19  def _status_cb(self, msg):
20  self.cur_status = msg
21 
22  def wait_for_connection(self, timeout=-1):
23  rospy.sleep(0.1)
24  r = rospy.Rate(30)
25  start_time = rospy.get_time()
26  while not rospy.is_shutdown():
27  if (timeout >= 0. and rospy.get_time() - start_time > timeout):
28  return False
29  if self.cur_status is not None:
30  return True
31  r.sleep()
32  return False
33 
34  def is_ready(self):
35  return self.cur_status.gSTA == 3 and self.cur_status.gACT == 1
36 
37  def is_reset(self):
38  return self.cur_status.gSTA == 0 or self.cur_status.gACT == 0
39 
40  def is_moving(self):
41  return self.cur_status.gGTO == 1 and self.cur_status.gOBJ == 0
42 
43  def is_stopped(self):
44  return self.cur_status.gOBJ != 0
45 
46  def object_detected(self):
47  return self.cur_status.gOBJ == 1 or self.cur_status.gOBJ == 2
48 
49  def get_fault_status(self):
50  return self.cur_status.gFLT
51 
52  def get_pos(self):
53  po = self.cur_status.gPO
54  return np.clip(0.087/(13.-230.)*(po-230.), 0, 0.087)
55 
56  def get_req_pos(self):
57  pr = self.cur_status.gPR
58  return np.clip(0.087/(13.-230.)*(pr-230.), 0, 0.087)
59 
60  def is_closed(self):
61  return self.cur_status.gPO >= 230
62 
63  def is_opened(self):
64  return self.cur_status.gPO <= 13
65 
66  # in mA
67  def get_current(self):
68  return self.cur_status.gCU * 0.1
69 
70  # if timeout is negative, wait forever
71  def wait_until_stopped(self, timeout=-1):
72  r = rospy.Rate(30)
73  start_time = rospy.get_time()
74  while not rospy.is_shutdown():
75  if (timeout >= 0. and rospy.get_time() - start_time > timeout) or self.is_reset():
76  return False
77  if self.is_stopped():
78  return True
79  r.sleep()
80  return False
81 
82  def wait_until_moving(self, timeout=-1):
83  r = rospy.Rate(30)
84  start_time = rospy.get_time()
85  while not rospy.is_shutdown():
86  if (timeout >= 0. and rospy.get_time() - start_time > timeout) or self.is_reset():
87  return False
88  if not self.is_stopped():
89  return True
90  r.sleep()
91  return False
92 
93  def reset(self):
94  cmd = outputMsg()
95  cmd.rACT = 0
96  self.cmd_pub.publish(cmd)
97 
98  def activate(self, timeout=-1):
99  cmd = outputMsg()
100  cmd.rACT = 1
101  cmd.rGTO = 1
102  cmd.rPR = 0
103  cmd.rSP = 255
104  cmd.rFR = 150
105  self.cmd_pub.publish(cmd)
106  r = rospy.Rate(30)
107  start_time = rospy.get_time()
108  while not rospy.is_shutdown():
109  if timeout >= 0. and rospy.get_time() - start_time > timeout:
110  return False
111  if self.is_ready():
112  return True
113  r.sleep()
114  return False
115 
116  def auto_release(self):
117  cmd = outputMsg()
118  cmd.rACT = 1
119  cmd.rATR = 1
120  self.cmd_pub.publish(cmd)
121 
122 
127  def goto(self, pos, vel, force, block=False, timeout=-1):
128  cmd = outputMsg()
129  cmd.rACT = 1
130  cmd.rGTO = 1
131  cmd.rPR = int(np.clip((13.-230.)/0.087 * pos + 230., 0, 255))
132  cmd.rSP = int(np.clip(255./(0.1-0.013) * (vel-0.013), 0, 255))
133  cmd.rFR = int(np.clip(255./(100.-30.) * (force-30.), 0, 255))
134  self.cmd_pub.publish(cmd)
135  rospy.sleep(0.1)
136  if block:
137  if not self.wait_until_moving(timeout):
138  return False
139  return self.wait_until_stopped(timeout)
140  return True
141 
142  def stop(self, block=False, timeout=-1):
143  cmd = outputMsg()
144  cmd.rACT = 1
145  cmd.rGTO = 0
146  self.cmd_pub.publish(cmd)
147  rospy.sleep(0.1)
148  if block:
149  return self.wait_until_stopped(timeout)
150  return True
151 
152  def open(self, vel=0.1, force=100, block=False, timeout=-1):
153  if self.is_opened():
154  return True
155  return self.goto(1.0, vel, force, block=block, timeout=timeout)
156 
157  def close(self, vel=0.1, force=100, block=False, timeout=-1):
158  if self.is_closed():
159  return True
160  return self.goto(-1.0, vel, force, block=block, timeout=timeout)
161 
162 def main():
163  rospy.init_node("robotiq_2f_gripper_ctrl_test")
164  gripper = RobotiqCGripper()
165  gripper.wait_for_connection()
166  if gripper.is_reset():
167  gripper.reset()
168  gripper.activate()
169  print gripper.close(block=True)
170  while not rospy.is_shutdown():
171  print gripper.open(block=False)
172  rospy.sleep(0.11)
173  gripper.stop()
174  print gripper.close(block=False)
175  rospy.sleep(0.1)
176  gripper.stop()
177 
178 if __name__ == '__main__':
179  main()
def open(self, vel=0.1, force=100, block=False, timeout=-1)
def close(self, vel=0.1, force=100, block=False, timeout=-1)
def goto(self, pos, vel, force, block=False, timeout=-1)
Goto position with desired force and velocity.


robotiq_2f_gripper_control
Author(s): Nicolas Lauzier (Robotiq inc.)
autogenerated on Tue Jun 1 2021 02:29:54