41 Module comModbusRtu: defines a class which communicates with Robotiq Grippers using the Modbus RTU protocol. 43 The module depends on pymodbus (http://code.google.com/p/pymodbus/) for the Modbus RTU client. 46 from pymodbus.client.sync
import ModbusSerialClient
55 """Connection to the client - the method takes the IP address (as a string, e.g. '192.168.1.11') as an argument.""" 56 self.
client = ModbusSerialClient(method=
'rtu',port=device,stopbits=1, bytesize=8, baudrate=115200, timeout=0.2)
57 if not self.client.connect():
58 print "Unable to connect to %s" % device
63 """Close connection""" 67 """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)""" 69 if(len(data) % 2 == 1):
76 for i
in range(0, len(data)/2):
77 message.append((data[2*i] << 8) + data[2*i+1])
80 self.client.write_registers(0x03E8, message, unit=0x0009)
83 """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""" 84 numRegs = int(ceil(numBytes/2.0))
88 response = self.client.read_holding_registers(0x07D0, numRegs, unit=0x0009)
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 connectToDevice(self, device)
def disconnectFromDevice(self)
def sendCommand(self, data)