39 Module comModbusTcp: defines a class which communicates with Robotiq Grippers using the Modbus TCP protocol. 41 The module depends on pymodbus (http://code.google.com/p/pymodbus/) for the Modbus TCP client. 44 from pymodbus.client.sync
import ModbusTcpClient
45 from pymodbus.register_read_message
import ReadInputRegistersResponse
54 self.
lock = threading.Lock()
57 """Connection to the client - the method takes the IP address (as a string, e.g. '192.168.1.11') as an argument.""" 58 self.
client = ModbusTcpClient(address)
61 """Close connection""" 65 """Send a command to the Gripper - the method takes a list of uint8 as an argument. The meaning of each variable depends on the Gripper model (see support.robotiq.com for more details)""" 67 if(len(data) % 2 == 1):
74 for i
in range(0, len(data)/2):
75 message.append((data[2*i] << 8) + data[2*i+1])
79 self.client.write_registers(0, message)
82 """Sends a request to read, wait for the response and returns the Gripper status. The method gets the number of bytes to read as an argument""" 83 numRegs = int(ceil(numBytes/2.0))
88 response = self.client.read_input_registers(0, numRegs)
94 for i
in range(0, numRegs):
95 output.append((response.getRegister(i) & 0xFF00) >> 8)
96 output.append( response.getRegister(i) & 0x00FF)
def getStatus(self, numBytes)
def disconnectFromDevice(self)
def connectToDevice(self, address)
def sendCommand(self, data)