33 import serial, time, sys, thread
35 from struct
import unpack
54 def __init__(self, port="/dev/ttyUSB0", baud=115200, timeout=0.1, open_port=True):
56 self.
_ser = serial.Serial()
59 self._ser.baudrate = baud
60 self._ser.timeout = timeout
71 except serial.SerialException
as e:
79 except serial.SerialException
as e:
90 def getPacket(self, mode, id=-1, leng=-1, error=-1, params = None):
93 except Exception
as e:
121 return self.
getPacket(6, id, leng, ord(d), list())
123 return self.
getPacket(5, id, leng, ord(d), list())
125 params.append(ord(d))
126 if len(params) + 2 == leng:
127 return self.
getPacket(6, id, leng, error, params)
129 return self.
getPacket(5, id, leng, error, params)
131 checksum = id + leng + error + sum(params) + ord(d)
132 if checksum % 256 != 255:
149 def execute(self, index, ins, params, ret=True):
151 self._mutex.acquire()
153 self._ser.flushInput()
154 except Exception
as e:
156 length = 2 + len(params)
157 checksum = 255 - ((index + length + ins + sum(params))%256)
158 self.
__write__(chr(0xFF)+chr(0xFF)+chr(index)+chr(length)+chr(ins))
164 self._mutex.release()
176 def read(self, index, start, length):
177 values = self.
execute(index, AX_READ_DATA, [start, length])
192 def write(self, index, start, values):
193 self.
execute(index, AX_WRITE_DATA, [start] + values)
206 length = len(output) + 4
207 lbytes = len(values[0])-1
208 self._mutex.acquire()
210 self._ser.flushInput()
213 self.
__write__(chr(0xFF)+chr(0xFF)+chr(254)+chr(length)+chr(AX_SYNC_WRITE))
218 checksum = 255 - ((254 + length + AX_SYNC_WRITE + start + lbytes + sum(output))%256)
220 self._mutex.release()
232 return self.
execute(0xFE, AX_SYNC_READ, [start, length] + servos )
242 return self.
write(index, P_BAUD_RATE, [baud, ])
251 return int(self.
read(index, P_RETURN_LEVEL, 1)[0])
263 return self.
write(index, P_RETURN_LEVEL, [value])
271 return self.
write(index, P_TORQUE_ENABLE, [1])
279 return self.
write(index, P_TORQUE_ENABLE, [0])
289 return self.
write(index, P_LED, [value])
299 return self.
write(index, P_GOAL_POSITION_L, [value%256, value>>8])
309 return self.
write(index, P_GOAL_SPEED_L, [value%256, value>>8])
317 values = self.
read(index, P_PRESENT_POSITION_L, 2)
319 return int(values[0]) + (int(values[1])<<8)
329 values = self.
read(index, P_PRESENT_SPEED_L, 2)
331 return int(values[0]) + (int(values[1])<<8)
341 values = self.
read(index, P_GOAL_SPEED_L, 2)
343 return int(values[0]) + (int(values[1])<<8)
354 return int(self.
read(index, P_PRESENT_VOLTAGE, 1)[0])/10.0
365 return int(self.
read(index, P_PRESENT_TEMPERATURE, 1)[0])
376 d = self.
read(index, P_MOVING, 1)[0]
385 self.
write(index, P_CCW_ANGLE_LIMIT_L, [0,0])
396 resolution = (2 ** resolution) - 1
397 self.
write(index, P_CCW_ANGLE_LIMIT_L, [resolution%256,resolution>>8])
418 self.
write(index, P_GOAL_SPEED_L, [speed%256, speed>>8])
422 self.
write(index, P_GOAL_SPEED_L, [speed%256, speed>>8])
453 REG_DIGITAL_OUT0 = 47
469 return sum(val[i] << (i * 8)
for i
in range(leng))
486 if x & (2**(index%8)):
501 if index > 31:
return -1
502 if value == 0
and direction > 0:
504 elif value > 0
and direction > 0:
506 elif value > 0
and direction == 0:
521 if index > 7:
return -1
522 if value != 0
and (value < 500
or value > 2500):
523 print "ArbotiX Error: Servo value out of range:", value
525 self.
write(253, self._SERVO_BASE + 2*index, [value%256, value>>8])
def rescan(self)
Force the ArbotiX2 to rescan the Dynamixel busses.
def getPacket(self, mode, id=-1, leng=-1, error=-1, params=None)
Read a dynamixel return packet in an iterative attempt.
def enableWheelMode(self, index)
Put a servo into wheel mode (continuous rotation).
def disableTorque(self, index)
Turn on the torque of a servo.
def getReturnLevel(self, index)
Get the return level of a device.
int REG_RESCAN
Register address for triggering rescan.
def setDigital(self, index, value, direction=0xff)
Get the value of an digital input pin.
def setPosition(self, index, value)
Set the position of a servo.
def __init__(self, port="/dev/ttyUSB0", baud=115200, timeout=0.1, open_port=True)
Constructs an ArbotiX instance, optionally opening the serial connection.
def execute(self, index, ins, params, ret=True)
Send an instruction to the device.
def setReturnLevel(self, index, value)
Set the return level of a device.
def write(self, index, start, values)
Write values to registers.
def setBaud(self, index, baud)
Set baud rate of a device.
def syncRead(self, servos, start, length)
Read values of registers on many servos.
def getSpeed(self, index)
Get the speed of a servo.
def getVoltage(self, index)
Get the voltage of a device.
def disableWheelMode(self, index, resolution=10)
Put a servo into servo mode.
def getAnalog(self, index, leng=1)
Get the value of an analog input pin.
def setServo(self, index, value)
Set the position of a hobby servo.
int REG_DIGITAL_IN0
Register base address for reading digital ports.
def getTemperature(self, index)
Get the temperature of a device.
int FORWARD
Direction definition for setWheelSpeed.
This class controls an ArbotiX, USBDynamixel, or similar board through a serial connection.
def setLed(self, index, value)
Set the status of the LED on a servo.
def enableTorque(self, index)
Turn on the torque of a servo.
def setSpeed(self, index, value)
Set the speed of a servo.
def read(self, index, start, length)
Read values of registers.
def getPosition(self, index)
Get the position of a servo.
def getDigital(self, index)
Get the value of an digital input pin.
def setWheelSpeed(self, index, direction, speed)
Set the speed and direction of a servo which is in wheel mode (continuous rotation).
def isMoving(self, index)
Determine if a device is moving.
def syncWrite(self, start, values)
Write values to registers on many servos.
int ANA_BASE
Register address of first analog port (read only).
def getGoalSpeed(self, index)
Get the goal speed of a servo.
error
The last error level read back.