class ModbusWrapperClient(): """ Wrapper that integrates python modbus into standardized ros msgs. The wrapper is able to read from and write to a standard modbus tcp/ip server. """ def __init__(self, host, port=502, rate=50, reset_registers=True, sub_topic="modbus_wrapper/output", pub_topic="modbus_wrapper/input"): """ Use subscribers and publisher to communicate with the modbus server. Check the scripts for example code. :param host: Contains the IP adress of the modbus server :type host: string :param port: The port number, where the modbus server is runnning :type port: integer :param rate: How often the registers on the modbusserver should be read per second :type rate: float :param reset_registers: Defines if the holding registers should be reset to 0 after they have been read. Only possible if they are writeable :type reset_registers: bool """ try: self.client = ModbusTcpClient(host, port) except Exception, e: rospy.logwarn( "Could not get a modbus connection to the host modbus. %s", str(e)) raise e return self.__rate = rate self.__reading_delay = 1 / rate self.post = Post(self) self.__reset_registers = reset_registers self.__reading_register_start = 0 self.__num_reading_registers = 20 # self.input_size = 16 self.__input = HoldingRegister() self.__input.data = [0 for i in xrange(self.__num_reading_registers)] self.__writing_registers_start = ADDRESS_WRITE_START self.__num_writing_registers = 20 # self.output_size = 16 self.__output = [None for i in range(self.__num_writing_registers)] self.__last_output_time = rospy.get_time() self.__mutex = Lock() self.__sub = rospy.Subscriber(sub_topic, HoldingRegister, self.__updateModbusOutput, queue_size=500) self.__pub = rospy.Publisher(pub_topic, HoldingRegister, queue_size=500, latch=True) rospy.on_shutdown(self.closeConnection)
def setValues(self, address, value): """ Sets the requested values to the holding registers and publishes they new values on a rostopic :param address: The starting address :type address: int :param values: The new values to be set :type values: list[int] """ ModbusSequentialDataBlock.setValues(self, address, value) if address >= self.reading_start: msg = HoldingRegister() msg.data = value self.pub.publish(msg)
rospy.loginfo("Modbus server registers have been updated: %s", str(msg.data)) sub = rospy.Subscriber("modbus_wrapper/input", HoldingRegister, showUpdatedRegisters, queue_size=500) ################# ################# # Example 3 # writing to modbus registers using a standard ros publisher pub = rospy.Publisher("modbus_wrapper/output", HoldingRegister, queue_size=500) output = HoldingRegister() output.data = xrange(20, 40) output2 = HoldingRegister() output2.data = xrange(40, 20, -1) rospy.loginfo("Sending arrays to the modbus server") while not rospy.is_shutdown(): rospy.sleep(1) pub.publish(output) rospy.sleep(1) pub.publish(output2) ################# # Stops the listener on the modbus modclient.stopListening()
rospy.loginfo("Modbus register have been written: %s", str(msg.data)) rospy.sleep(2) sub = rospy.Subscriber("modbus_server/read_from_registers", HoldingRegister, callback, queue_size=500) ############### ############### # Example 4 # Publisher to write first 20 modbus registers from any node pub = rospy.Publisher("modbus_server/write_to_registers", HoldingRegister, queue_size=500) rospy.sleep(1) msg = HoldingRegister() msg.data = range(20) msg2 = HoldingRegister() msg2.data = range(20, 0, -1) while not rospy.is_shutdown(): pub.publish(msg) rospy.sleep(1) pub.publish(msg2) rospy.sleep(1) ################ rospy.spin() mws.stopServer()