Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038 """@package docstring
00039 ROS node for controling a Robotiq S-Model gripper using the Modbus TCP protocol.
00040
00041 The script takes as an argument the IP address of the gripper. It initializes a baseSModel 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 'SModelRobotInput' topic using the 'SModel_robot_input' msg type. The node subscribes to the 'SModelRobotOutput' topic for new commands using the 'SModel_robot_output' msg type. Examples are provided to control the gripper (SModelSimpleController.py) and interpreting its status (SModelStatusListener.py).
00042 """
00043
00044 import roslib; roslib.load_manifest('robotiq_s_model_control')
00045 roslib.load_manifest('robotiq_modbus_tcp')
00046 import rospy
00047 import robotiq_s_model_control.baseSModel
00048 import robotiq_modbus_tcp.comModbusTcp
00049 import os, sys
00050 from robotiq_s_model_control.msg import _SModel_robot_input as inputMsg
00051 from robotiq_s_model_control.msg import _SModel_robot_output as outputMsg
00052
00053 def mainLoop(address):
00054
00055
00056 gripper = robotiq_s_model_control.baseSModel.robotiqBaseSModel()
00057 gripper.client = robotiq_modbus_tcp.comModbusTcp.communication()
00058
00059
00060 gripper.client.connectToDevice(address)
00061
00062 rospy.init_node('robotiqSModel')
00063
00064
00065 pub = rospy.Publisher('SModelRobotInput', inputMsg.SModel_robot_input)
00066
00067
00068 rospy.Subscriber('SModelRobotOutput', outputMsg.SModel_robot_output, gripper.refreshCommand)
00069
00070
00071
00072 while not rospy.is_shutdown():
00073
00074
00075 status = gripper.getStatus()
00076 pub.publish(status)
00077
00078
00079 rospy.sleep(0.05)
00080
00081
00082 gripper.sendCommand()
00083
00084
00085 rospy.sleep(0.05)
00086
00087 if __name__ == '__main__':
00088 try:
00089
00090 mainLoop(sys.argv[1])
00091 except rospy.ROSInterruptException: pass