39 ROS node for controling a Robotiq 3F gripper gripper using the Modbus TCP protocol. 41 The script takes as an argument the IP address of the gripper. It initializes a baseRobotiq3FGripper object and adds a comModbusTcp client to it. It then loops forever, reading the gripper status and updating its command. The gripper status is published on the 'Robotiq3FGripperRobotInput' topic using the 'Robotiq3FGripper_robot_input' msg type. The node subscribes to the 'Robotiq3FGripperRobotOutput' topic for new commands using the 'Robotiq3FGripper_robot_output' msg type. Examples are provided to control the gripper (Robotiq3FGripperSimpleController.py) and interpreting its status (Robotiq3FGripperStatusListener.py). 46 roslib.load_manifest(
'robotiq_3f_gripper_control')
47 roslib.load_manifest(
'robotiq_modbus_tcp')
50 import robotiq_modbus_tcp.comModbusTcp
52 from robotiq_3f_gripper_articulated_msgs.msg
import Robotiq3FGripperRobotInput
53 from robotiq_3f_gripper_articulated_msgs.msg
import Robotiq3FGripperRobotOutput
59 gripper.client = robotiq_modbus_tcp.comModbusTcp.communication()
62 gripper.client.connectToDevice(address)
64 rospy.init_node(
'robotiq3FGripper')
67 pub = rospy.Publisher(
'Robotiq3FGripperRobotInput', Robotiq3FGripperRobotInput, queue_size=1)
70 rospy.Subscriber(
'Robotiq3FGripperRobotOutput', Robotiq3FGripperRobotOutput, gripper.refreshCommand)
73 while not rospy.is_shutdown():
75 status = gripper.getStatus()
88 if __name__ ==
'__main__':
92 except rospy.ROSInterruptException: