39 ROS node for controling a Robotiq 2F gripper using the Modbus RTU protocol. 41 The script takes as an argument the IP address of the gripper. It initializes a baseRobotiq2FGripper 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 'Robotiq2FGripperRobotInput' topic using the 'Robotiq2FGripper_robot_input' msg type. The node subscribes to the 'Robotiq2FGripperRobotOutput' topic for new commands using the 'Robotiq2FGripper_robot_output' msg type. Examples are provided to control the gripper (Robotiq2FGripperSimpleController.py) and interpreting its status (Robotiq2FGripperStatusListener.py). 44 import roslib; roslib.load_manifest(
'robotiq_2f_gripper_control')
45 roslib.load_manifest(
'robotiq_modbus_rtu')
48 import robotiq_modbus_rtu.comModbusRtu
50 from robotiq_2f_gripper_control.msg
import _Robotiq2FGripper_robot_input
as inputMsg
51 from robotiq_2f_gripper_control.msg
import _Robotiq2FGripper_robot_output
as outputMsg
57 gripper.client = robotiq_modbus_rtu.comModbusRtu.communication()
60 gripper.client.connectToDevice(device)
62 rospy.init_node(
'robotiq2FGripper')
65 pub = rospy.Publisher(
'Robotiq2FGripperRobotInput', inputMsg.Robotiq2FGripper_robot_input)
68 rospy.Subscriber(
'Robotiq2FGripperRobotOutput', outputMsg.Robotiq2FGripper_robot_output, gripper.refreshCommand)
72 while not rospy.is_shutdown():
75 status = gripper.getStatus()
87 if __name__ ==
'__main__':
90 except rospy.ROSInterruptException:
pass