modbus_client_s7_1200.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 ########################################################################### 
00003 # This software is graciously provided by HumaRobotics 
00004 # under the Simplified BSD License on
00005 # github: git@www.humarobotics.com:baxter_tasker
00006 # HumaRobotics is a trademark of Generation Robots.
00007 # www.humarobotics.com 
00008 
00009 # Copyright (c) 2013, Generation Robots.
00010 # All rights reserved.
00011 # www.generationrobots.com
00012 #   
00013 # Redistribution and use in source and binary forms, with or without 
00014 # modification, are permitted provided that the following conditions are met:
00015 # 
00016 # 1. Redistributions of source code must retain the above copyright notice,
00017 #  this list of conditions and the following disclaimer.
00018 # 
00019 # 2. Redistributions in binary form must reproduce the above copyright notice,
00020 #  this list of conditions and the following disclaimer in the documentation 
00021 #  and/or other materials provided with the distribution.
00022 # 
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00024 # AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, 
00025 # THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR 
00026 # PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS 
00027 # BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR 
00028 # CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF 
00029 # SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS 
00030 # INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN 
00031 # CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) 
00032 # ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF 
00033 # THE POSSIBILITY OF SUCH DAMAGE. 
00034 # 
00035 # The views and conclusions contained in the software and documentation are 
00036 # those of the authors and should not be interpreted as representing official 
00037 # policies, either expressed or implied, of the FreeBSD Project.
00038 
00039 import rospy
00040 from modbus_plc_siemens.s7_modbus_client import S7ModbusClient 
00041 from std_msgs.msg import Int32MultiArray as HoldingRegister
00042 
00043 if __name__=="__main__":
00044     rospy.init_node("modbus_client_s7_1200")
00045     rospy.loginfo("""
00046     This file shows the usage of the Modbus Wrapper Client.
00047     To see the read registers of the modbus server use: rostopic echo /modbus_wrapper/input
00048     To see sent something to the modbus use a publisher on the topic /modbus_wrapper/output
00049     This file contains a sample publisher.
00050     """)
00051     host = "192.168.0.198"
00052     port = 502
00053     if rospy.has_param("~ip"):
00054         host =  rospy.get_param("~ip")
00055     else:
00056         rospy.loginfo("For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.198\"'",host)
00057     if rospy.has_param("~port"):
00058         port =  rospy.get_param("~port")
00059     else:
00060         rospy.loginfo("For not using the default port %d, add an arg e.g.: '_port:=1234'",port)
00061     # setup modbus client for siemens s7 PLC  
00062     modclient = S7ModbusClient(host,port)
00063     rospy.loginfo("Setup complete")
00064         
00065     #################        
00066     # Example 1 
00067     # Set single registers using the python interface - yeah knight rider is coming!
00068     outputs = xrange(8,14)
00069     outputs2 = range(13,7,-1)
00070     #inputs = range(1,9) 
00071     
00072     # for i in xrange(5):
00073     #     for output in outputs:    
00074     #         modclient.setOutput(output,1,0.3)
00075     #         rospy.sleep(0.1)
00076     #     for output in outputs2:            
00077     #         modclient.setOutput(output,1,0.3)
00078     #         rospy.sleep(0.1)
00079     # rospy.sleep(0.3)
00080     #################
00081       
00082     #################
00083     # Example 2
00084     # Create a listener that show us a message if anything on the readable modbus registers change
00085     rospy.loginfo("All done. Listening to inputs... Terminate by Ctrl+c")
00086     def showUpdatedRegisters(msg):
00087         rospy.loginfo("Modbus server registers have been updated: %s",str(msg.data))
00088     sub = rospy.Subscriber("modbus_wrapper/input",HoldingRegister,showUpdatedRegisters,queue_size=500)
00089     rospy.spin()
00090     #################
00091     
00092      #################
00093     # Example 3
00094     # writing to modbus registers using a standard ros publisher
00095     
00096     pub = rospy.Publisher("modbus_wrapper/output",HoldingRegister,queue_size=500)
00097     output = HoldingRegister()
00098     output.data = [1 for x in xrange(0,6)]
00099     output2 = HoldingRegister()
00100     output2.data = [0 for x in xrange(0,6)]
00101      
00102     rospy.loginfo("Sending arrays to the modbus server")
00103     for i in xrange(5):
00104         rospy.sleep(1)
00105         pub.publish(output)
00106         rospy.sleep(1)
00107         pub.publish(output2)
00108     #################
00109     
00110     rospy.loginfo("Outputs tests all done, just listening to inputs. Stop listening by pressing Ctrl+c")
00111     # Stops the listener on the modbus
00112     modclient.stopListening()
00113     


modbus_plc_siemens
Author(s): Sven Bock
autogenerated on Thu Jun 6 2019 17:39:38