6 roslib.load_manifest(
'robotiq_2f_gripper_control')
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
15 self.
status_sub = rospy.Subscriber(
'Robotiq2FGripperRobotInput', inputMsg,
17 self.
cmd_pub = rospy.Publisher(
'Robotiq2FGripperRobotOutput', outputMsg)
25 start_time = rospy.get_time()
26 while not rospy.is_shutdown():
27 if (timeout >= 0.
and rospy.get_time() - start_time > timeout):
35 return self.cur_status.gSTA == 3
and self.cur_status.gACT == 1
38 return self.cur_status.gSTA == 0
or self.cur_status.gACT == 0
41 return self.cur_status.gGTO == 1
and self.cur_status.gOBJ == 0
44 return self.cur_status.gOBJ != 0
47 return self.cur_status.gOBJ == 1
or self.cur_status.gOBJ == 2
50 return self.cur_status.gFLT
53 po = self.cur_status.gPO
54 return np.clip(0.087/(13.-230.)*(po-230.), 0, 0.087)
57 pr = self.cur_status.gPR
58 return np.clip(0.087/(13.-230.)*(pr-230.), 0, 0.087)
61 return self.cur_status.gPO >= 230
64 return self.cur_status.gPO <= 13
68 return self.cur_status.gCU * 0.1
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():
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():
96 self.cmd_pub.publish(cmd)
105 self.cmd_pub.publish(cmd)
107 start_time = rospy.get_time()
108 while not rospy.is_shutdown():
109 if timeout >= 0.
and rospy.get_time() - start_time > timeout:
120 self.cmd_pub.publish(cmd)
127 def goto(self, pos, vel, force, block=False, timeout=-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)
142 def stop(self, block=False, timeout=-1):
146 self.cmd_pub.publish(cmd)
152 def open(self, vel=0.1, force=100, block=False, timeout=-1):
155 return self.
goto(1.0, vel, force, block=block, timeout=timeout)
157 def close(self, vel=0.1, force=100, block=False, timeout=-1):
160 return self.
goto(-1.0, vel, force, block=block, timeout=timeout)
163 rospy.init_node(
"robotiq_2f_gripper_ctrl_test")
165 gripper.wait_for_connection()
166 if gripper.is_reset():
169 print gripper.close(block=
True)
170 while not rospy.is_shutdown():
171 print gripper.open(block=
False)
174 print gripper.close(block=
False)
178 if __name__ ==
'__main__':
def wait_until_moving(self, timeout=-1)
def wait_until_stopped(self, timeout=-1)
def open(self, vel=0.1, force=100, block=False, timeout=-1)
def activate(self, timeout=-1)
def close(self, vel=0.1, force=100, block=False, timeout=-1)
def get_fault_status(self)
def object_detected(self)
def wait_for_connection(self, timeout=-1)
def stop(self, block=False, timeout=-1)
def _status_cb(self, msg)
def goto(self, pos, vel, force, block=False, timeout=-1)
Goto position with desired force and velocity.