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
00039 import rospy
00040 from modbus.modbus_wrapper_client import ModbusWrapperClient
00041 from std_msgs.msg import Int32MultiArray as HoldingRegister
00042
00043 NUM_REGISTERS = 20
00044 ADDRESS_READ_START = 40000
00045 ADDRESS_WRITE_START = 40020
00046
00047 if __name__=="__main__":
00048 rospy.init_node("modbus_client")
00049 rospy.loginfo("""
00050 This file shows the usage of the Modbus Wrapper Client.
00051 To see the read registers of the modbus server use: rostopic echo /modbus_wrapper/input
00052 To see sent something to the modbus use a publisher on the topic /modbus_wrapper/output
00053 This file contains a sample publisher.
00054 """)
00055 host = "192.168.0.123"
00056 port = 502
00057 if rospy.has_param("~ip"):
00058 host = rospy.get_param("~ip")
00059 else:
00060 rospy.loginfo("For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.199\"'",host)
00061 if rospy.has_param("~port"):
00062 port = rospy.get_param("~port")
00063 else:
00064 rospy.loginfo("For not using the default port %d, add an arg e.g.: '_port:=1234'",port)
00065
00066 modclient = ModbusWrapperClient(host,port=port,rate=50,reset_registers=False,sub_topic="modbus_wrapper/output",pub_topic="modbus_wrapper/input")
00067 modclient.setReadingRegisters(ADDRESS_READ_START,NUM_REGISTERS)
00068 modclient.setWritingRegisters(ADDRESS_WRITE_START,NUM_REGISTERS)
00069 rospy.loginfo("Setup complete")
00070
00071
00072 modclient.startListening()
00073 rospy.loginfo("Listener started")
00074
00075
00076
00077
00078 register = 40020
00079 value = 1
00080 timeout = 0.5
00081 modclient.setOutput(register,value,timeout)
00082 rospy.loginfo("Set and individual output")
00083
00084
00085
00086
00087
00088
00089
00090 rospy.loginfo("All done. Listening to inputs... Terminate by Ctrl+c")
00091 def showUpdatedRegisters(msg):
00092 rospy.loginfo("Modbus server registers have been updated: %s",str(msg.data))
00093 sub = rospy.Subscriber("modbus_wrapper/input",HoldingRegister,showUpdatedRegisters,queue_size=500)
00094
00095
00096
00097
00098
00099 pub = rospy.Publisher("modbus_wrapper/output",HoldingRegister,queue_size=500)
00100 output = HoldingRegister()
00101 output.data = xrange(20,40)
00102 output2 = HoldingRegister()
00103 output2.data = xrange(40,20,-1)
00104
00105 rospy.loginfo("Sending arrays to the modbus server")
00106 while not rospy.is_shutdown():
00107 rospy.sleep(1)
00108 pub.publish(output)
00109 rospy.sleep(1)
00110 pub.publish(output2)
00111
00112
00113
00114 modclient.stopListening()
00115
00116
00117
00118
00119