sub_topic = rospy.get_param('~sub_topic', 'output') pub_topic = rospy.get_param('~pub_topic', 'input') address_read_start = int(rospy.get_param('~address_read_start', 0)) address_write_start = int(rospy.get_param('~address_write_start', 0)) num_registers = int(rospy.get_param('~num_registers', 20)) rospy.loginfo('Modbus server: {}:{}'.format(host, port)) rospy.loginfo('Modbus id: {}'.format(str(unit))) rospy.loginfo('address_read_start: {}'.format(address_read_start)) rospy.loginfo('address_write_start: {}'.format(address_write_start)) rospy.loginfo('num_registers: {}'.format(num_registers)) nh = ModbusWrapperClient( host, port=port, unit=unit, reset_registers=False, sub_topic=sub_topic, pub_topic=pub_topic ) nh.setReadingRegisters(address_read_start, num_registers) nh.setWritingRegisters(address_write_start, num_registers) rospy.loginfo('Setup complete') # start listening to modbus and publish changes to the rostopic nh.startListening() rospy.loginfo('Listener started') rospy.spin() # modclient.stopListening()
"For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.199\"'", host) if rospy.has_param("~port"): port = rospy.get_param("~port") else: rospy.loginfo( "For not using the default port %d, add an arg e.g.: '_port:=1234'", port) # setup modbus client modclient = ModbusWrapperClient(host, port=port, rate=50, reset_registers=False, sub_topic="modbus_wrapper/output", pub_topic="modbus_wrapper/input") modclient.setReadingRegisters(ADDRESS_READ_START, NUM_REGISTERS) modclient.setWritingRegisters(ADDRESS_WRITE_START, NUM_REGISTERS) rospy.loginfo("Setup complete") # start listening to modbus and publish changes to the rostopic modclient.startListening() rospy.loginfo("Listener started") ################# # Example 1 # Sets an individual register using the python interface, which can automatically be reset, if a timeout is given. register = 40020 value = 1 timeout = 0.5 modclient.setOutput(register, value, timeout) rospy.loginfo("Set and individual output")
To see sent something to the modbus use a publisher on the topic /modbus_wrapper/output This file contains a sample publisher. """) host = "192.168.0.123" port = 502 if rospy.has_param("~ip"): host = rospy.get_param("~ip") else: rospy.loginfo("For not using the default IP %s, add an arg e.g.: '_ip:=\"192.168.0.199\"'",host) if rospy.has_param("~port"): port = rospy.get_param("~port") else: rospy.loginfo("For not using the default port %d, add an arg e.g.: '_port:=1234'",port) # setup modbus client modclient = ModbusWrapperClient(host,port=port,rate=50,reset_registers=False,sub_topic="modbus_wrapper/output",pub_topic="modbus_wrapper/input") modclient.setReadingRegisters(ADDRESS_READ_START,NUM_REGISTERS) modclient.setWritingRegisters(ADDRESS_WRITE_START,NUM_REGISTERS) rospy.loginfo("Setup complete") # start listening to modbus and publish changes to the rostopic modclient.startListening() rospy.loginfo("Listener started") ################# # Example 1 # Sets an individual register using the python interface, which can automatically be reset, if a timeout is given. register = 40020 value = 1 timeout = 0.5 modclient.setOutput(register,value,timeout) rospy.loginfo("Set and individual output")