arbotix.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 
00003 # Copyright (c) 2008-2011 Vanadium Labs LLC. 
00004 # All right reserved.
00005 #
00006 # Redistribution and use in source and binary forms, with or without
00007 # modification, are permitted provided that the following conditions are met:
00008 #
00009 #   * Redistributions of source code must retain the above copyright
00010 #     notice, this list of conditions and the following disclaimer.
00011 #   * Redistributions in binary form must reproduce the above copyright
00012 #     notice, this list of conditions and the following disclaimer in the
00013 #     documentation and/or other materials provided with the distribution.
00014 #   * Neither the name of Vanadium Labs LLC nor the names of its 
00015 #     contributors may be used to endorse or promote products derived 
00016 #     from this software without specific prior written permission.
00017 #
00018 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00019 # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00020 # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 # DISCLAIMED. IN NO EVENT SHALL VANADIUM LABS BE LIABLE FOR ANY DIRECT, INDIRECT,
00022 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT
00023 # LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA,
00024 # OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
00025 # LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE
00026 # OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF
00027 # ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 
00029 # Author: Michael Ferguson
00030 
00031 ## @file arbotix.py Low-level code to control an ArbotiX.
00032 
00033 import serial, time, sys, thread
00034 from ax12 import *
00035 from struct import unpack
00036 
00037 ## @brief ArbotiX errors. Used by now to handle broken serial connections.
00038 class ArbotiXException(Exception):
00039     pass
00040 
00041 ## @brief This class controls an ArbotiX, USBDynamixel, or similar board through a serial connection.
00042 class ArbotiX:
00043 
00044     ## @brief Constructs an ArbotiX instance, optionally opening the serial connection.
00045     ##
00046     ## @param port The name of the serial port to open.
00047     ## 
00048     ## @param baud The baud rate to run the port at. 
00049     ##
00050     ## @param timeout The timeout to use for the port. When operating over a wireless link, you may need to
00051     ## increase this.
00052     ##
00053     ## @param open Whether to open immediately the serial port.
00054     def __init__(self, port="/dev/ttyUSB0", baud=115200, timeout=0.1, open_port=True):
00055         self._mutex = thread.allocate_lock()
00056         self._ser = serial.Serial()
00057         
00058         self._ser.port = port
00059         self._ser.baudrate = baud
00060         self._ser.timeout = timeout
00061 
00062         if open_port:
00063             self._ser.open()
00064 
00065         ## The last error level read back
00066         self.error = 0
00067 
00068     def __write__(self, msg):
00069         try:
00070             self._ser.write(msg)
00071         except serial.SerialException as e:
00072             self._mutex.release()
00073             raise ArbotiXException(e)
00074 
00075     def openPort(self):
00076         self._ser.close()
00077         try:
00078             self._ser.open()
00079         except serial.SerialException as e:
00080             raise ArbotiXException(e)
00081 
00082     def closePort(self):
00083         self._ser.close()
00084 
00085     ## @brief Read a dynamixel return packet in an iterative attempt.
00086     ##
00087     ## @param mode This should be 0 to start reading packet. 
00088     ##
00089     ## @return The error level returned by the device. 
00090     def getPacket(self, mode, id=-1, leng=-1, error=-1, params = None):
00091         try:
00092             d = self._ser.read()     
00093         except Exception as e:
00094             print e
00095             return None
00096         # need a positive byte
00097         if d == '':
00098             return None
00099 
00100         # now process our byte
00101         if mode == 0:           # get our first 0xFF
00102             if ord(d) == 0xff:   
00103                 return self.getPacket(1)
00104             else:
00105                 return self.getPacket(0)
00106         elif mode == 1:         # get our second 0xFF
00107             if ord(d) == 0xff:
00108                 return self.getPacket(2)
00109             else:
00110                 return self.getPacket(0)
00111         elif mode == 2:         # get id
00112             if d != 0xff:
00113                 return self.getPacket(3, ord(d))
00114             else:              
00115                 return self.getPacket(0)
00116         elif mode == 3:         # get length
00117             return self.getPacket(4, id, ord(d))
00118         elif mode == 4:         # read error    
00119             self.error = ord(d)
00120             if leng == 2:
00121                 return self.getPacket(6, id, leng, ord(d), list())
00122             else:
00123                 return self.getPacket(5, id, leng, ord(d), list())
00124         elif mode == 5:         # read params
00125             params.append(ord(d))
00126             if len(params) + 2 == leng:
00127                 return self.getPacket(6, id, leng, error, params)
00128             else:
00129                 return self.getPacket(5, id, leng, error, params)
00130         elif mode == 6:         # read checksum
00131             checksum = id + leng + error + sum(params) + ord(d)
00132             if checksum % 256 != 255:
00133                 return None
00134             return params
00135         # fail
00136         return None
00137 
00138     ## @brief Send an instruction to the device. 
00139     ##
00140     ## @param index The ID of the servo to write.
00141     ##
00142     ## @param ins The instruction to send.
00143     ##
00144     ## @param params A list of the params to send.
00145     ##
00146     ## @param ret Whether to read a return packet.
00147     ##
00148     ## @return The return packet, if read.
00149     def execute(self, index, ins, params, ret=True):
00150         values = None
00151         self._mutex.acquire()  
00152         try:      
00153             self._ser.flushInput()
00154         except Exception as e:
00155             print e
00156         length = 2 + len(params)
00157         checksum = 255 - ((index + length + ins + sum(params))%256)
00158         self.__write__(chr(0xFF)+chr(0xFF)+chr(index)+chr(length)+chr(ins))
00159         for val in params:
00160             self.__write__(chr(val))
00161         self.__write__(chr(checksum))
00162         if ret:
00163             values = self.getPacket(0)
00164         self._mutex.release()
00165         return values
00166     
00167     ## @brief Read values of registers.
00168     ##
00169     ## @param index The ID of the servo.
00170     ## 
00171     ## @param start The starting register address to begin the read at.
00172     ##
00173     ## @param length The number of bytes to read.
00174     ##
00175     ## @return A list of the bytes read, or -1 if failure.
00176     def read(self, index, start, length):
00177         values = self.execute(index, AX_READ_DATA, [start, length])
00178         if values == None:
00179             return -1        
00180         else:
00181             return values
00182 
00183     ## @brief Write values to registers.
00184     ##
00185     ## @param index The ID of the servo.
00186     ##
00187     ## @param start The starting register address to begin writing to.
00188     ##
00189     ## @param values The data to write, in a list.
00190     ##
00191     ## @return The error level.
00192     def write(self, index, start, values):
00193         self.execute(index, AX_WRITE_DATA, [start] + values)
00194         return self.error     
00195 
00196     ## @brief Write values to registers on many servos.
00197     ##
00198     ## @param start The starting register address to begin writing to.
00199     ##
00200     ## @param values The data to write, in a list of lists. Format should be
00201     ## [(id1, val1, val2), (id2, val1, val2)]
00202     def syncWrite(self, start, values):
00203         output = list()
00204         for i in values:
00205             output = output + i 
00206         length = len(output) + 4                # length of overall packet
00207         lbytes = len(values[0])-1               # length of bytes to write to a servo               
00208         self._mutex.acquire()  
00209         try:      
00210             self._ser.flushInput()
00211         except:
00212             pass  
00213         self.__write__(chr(0xFF)+chr(0xFF)+chr(254)+chr(length)+chr(AX_SYNC_WRITE))
00214         self.__write__(chr(start))              # start address
00215         self.__write__(chr(lbytes))             # bytes to write each servo
00216         for i in output:
00217             self.__write__(chr(i))
00218         checksum = 255 - ((254 + length + AX_SYNC_WRITE + start + lbytes + sum(output))%256)
00219         self.__write__(chr(checksum))
00220         self._mutex.release()
00221 
00222     ## @brief Read values of registers on many servos.
00223     ##
00224     ## @param servos A list of the servo IDs to read from.
00225     ##
00226     ## @param start The starting register address to begin reading at.
00227     ##
00228     ## @param length The number of bytes to read from each servo.
00229     ##
00230     ## @return A list of bytes read.
00231     def syncRead(self, servos, start, length):
00232         return self.execute(0xFE, AX_SYNC_READ, [start, length] + servos )
00233     
00234     ## @brief Set baud rate of a device.
00235     ##
00236     ## @param index The ID of the device to write (Note: ArbotiX is 253).
00237     ##
00238     ## @param baud The baud rate.
00239     ##
00240     ## @return The error level.
00241     def setBaud(self, index, baud):
00242         return self.write(index, P_BAUD_RATE, [baud, ])
00243 
00244     ## @brief Get the return level of a device.
00245     ##
00246     ## @param index The ID of the device to read.
00247     ##
00248     ## @return The return level, .
00249     def getReturnLevel(self, index):
00250         try:
00251             return int(self.read(index, P_RETURN_LEVEL, 1)[0])
00252         except:
00253             return -1
00254 
00255     ## @brief Set the return level of a device.
00256     ##
00257     ## @param index The ID of the device to write.
00258     ##
00259     ## @param value The return level.
00260     ##
00261     ## @return The error level.
00262     def setReturnLevel(self, index, value):
00263         return self.write(index, P_RETURN_LEVEL, [value])        
00264 
00265     ## @brief Turn on the torque of a servo.
00266     ##
00267     ## @param index The ID of the device to enable.
00268     ##
00269     ## @return The error level.
00270     def enableTorque(self, index):
00271         return self.write(index, P_TORQUE_ENABLE, [1])
00272 
00273     ## @brief Turn on the torque of a servo.
00274     ##
00275     ## @param index The ID of the device to disable.
00276     ##
00277     ## @return The error level.
00278     def disableTorque(self, index):
00279         return self.write(index, P_TORQUE_ENABLE, [0])
00280 
00281     ## @brief Set the status of the LED on a servo.
00282     ##
00283     ## @param index The ID of the device to write.
00284     ##
00285     ## @param value 0 to turn the LED off, >0 to turn it on
00286     ##
00287     ## @return The error level.
00288     def setLed(self, index, value):
00289         return self.write(index, P_LED, [value])
00290 
00291     ## @brief Set the position of a servo.
00292     ##
00293     ## @param index The ID of the device to write.
00294     ##
00295     ## @param value The position to go to in, in servo ticks.
00296     ##
00297     ## @return The error level.
00298     def setPosition(self, index, value):
00299         return self.write(index, P_GOAL_POSITION_L, [value%256, value>>8])
00300 
00301     ## @brief Set the speed of a servo.
00302     ##
00303     ## @param index The ID of the device to write.
00304     ##
00305     ## @param value The speed to write.
00306     ##
00307     ## @return The error level.
00308     def setSpeed(self, index, value):
00309         return self.write(index, P_GOAL_SPEED_L, [value%256, value>>8])
00310 
00311     ## @brief Get the position of a servo.
00312     ##
00313     ## @param index The ID of the device to read.
00314     ##
00315     ## @return The servo position.
00316     def getPosition(self, index):
00317         values = self.read(index, P_PRESENT_POSITION_L, 2)
00318         try:
00319             return int(values[0]) + (int(values[1])<<8)
00320         except:
00321             return -1
00322 
00323     ## @brief Get the speed of a servo.
00324     ##
00325     ## @param index The ID of the device to read.
00326     ##
00327     ## @return The servo speed.
00328     def getSpeed(self, index):
00329         values = self.read(index, P_PRESENT_SPEED_L, 2)
00330         try:
00331             return int(values[0]) + (int(values[1])<<8)
00332         except:
00333             return -1
00334         
00335     ## @brief Get the goal speed of a servo.
00336     ##
00337     ## @param index The ID of the device to read.
00338     ##
00339     ## @return The servo goal speed.
00340     def getGoalSpeed(self, index):
00341         values = self.read(index, P_GOAL_SPEED_L, 2)
00342         try:
00343             return int(values[0]) + (int(values[1])<<8)
00344         except:
00345             return -1
00346 
00347     ## @brief Get the voltage of a device.
00348     ##
00349     ## @param index The ID of the device to read.
00350     ##
00351     ## @return The voltage, in Volts.
00352     def getVoltage(self, index):
00353         try:
00354             return int(self.read(index, P_PRESENT_VOLTAGE, 1)[0])/10.0
00355         except:
00356             return -1    
00357 
00358     ## @brief Get the temperature of a device.
00359     ##
00360     ## @param index The ID of the device to read.
00361     ##
00362     ## @return The temperature, in degrees C.
00363     def getTemperature(self, index):
00364         try:
00365             return int(self.read(index, P_PRESENT_TEMPERATURE, 1)[0])
00366         except:
00367             return -1
00368 
00369     ## @brief Determine if a device is moving.
00370     ##
00371     ## @param index The ID of the device to read.
00372     ##
00373     ## @return True if servo is moving.
00374     def isMoving(self, index):
00375         try:
00376             d = self.read(index, P_MOVING, 1)[0]
00377         except:
00378             return True
00379         return d != 0
00380     
00381     ## @brief Put a servo into wheel mode (continuous rotation).
00382     ##
00383     ## @param index The ID of the device to write.
00384     def enableWheelMode(self, index):
00385         self.write(index, P_CCW_ANGLE_LIMIT_L, [0,0])
00386 
00387     ## @brief Put a servo into servo mode.
00388     ##
00389     ## @param index The ID of the device to write.
00390     ##
00391     ## @param resolution The resolution of the encoder on the servo. NOTE: if using 
00392     ## 12-bit resolution servos (EX-106, MX-28, etc), you must pass resolution = 12.
00393     ##
00394     ## @return 
00395     def disableWheelMode(self, index, resolution=10):
00396         resolution = (2 ** resolution) - 1
00397         self.write(index, P_CCW_ANGLE_LIMIT_L, [resolution%256,resolution>>8])
00398 
00399     ## Direction definition for setWheelSpeed
00400     FORWARD = 0
00401     ## Direction definition for setWheelSpeed
00402     BACKWARD = 1
00403 
00404     ## @brief Set the speed and direction of a servo which is in wheel mode (continuous rotation).
00405     ##
00406     ## @param index The ID of the device to write.
00407     ##
00408     ## @param direction The direction of rotation, either FORWARD or BACKWARD
00409     ##
00410     ## @param speed The speed to move at (0-1023).
00411     ##
00412     ## @return 
00413     def setWheelSpeed(self, index, direction, speed):
00414         if speed > 1023:
00415             speed = 1023
00416         if direction == self.FORWARD:
00417             # 0~1023 is forward, it is stopped by setting to 0 while rotating to CCW direction.
00418             self.write(index, P_GOAL_SPEED_L, [speed%256, speed>>8])
00419         else:
00420             # 1024~2047 is backward, it is stopped by setting to 1024 while rotating to CW direction.
00421             speed += 1024
00422             self.write(index, P_GOAL_SPEED_L, [speed%256, speed>>8])
00423 
00424     ###########################################################################
00425     # Extended ArbotiX Driver
00426 
00427     ## Helper definition for analog and digital access.
00428     LOW = 0
00429     ## Helper definition for analog and digital access.
00430     HIGH = 0xff
00431     ## Helper definition for analog and digital access.
00432     INPUT = 0
00433     ## Helper definition for analog and digital access.
00434     OUTPUT = 0xff
00435 
00436     # ArbotiX-specific register table
00437     # We do Model, Version, ID, Baud, just like the AX-12
00438     ## Register base address for reading digital ports
00439     REG_DIGITAL_IN0 = 5
00440     REG_DIGITAL_IN1 = 6
00441     REG_DIGITAL_IN2 = 7
00442     REG_DIGITAL_IN3 = 8
00443     ## Register address for triggering rescan
00444     REG_RESCAN = 15
00445     # 16, 17 = RETURN, ALARM
00446     ## Register address of first analog port (read only).
00447     ## Each additional port is BASE + index.
00448     ANA_BASE = 18
00449     ## Register address of analog servos. Up to 10 servos, each
00450     ## uses 2 bytes (L, then H), pulse width (0, 1000-2000ms) (Write only)
00451     SERVO_BASE = 26
00452     # Address 46 is Moving, just like an AX-12
00453     REG_DIGITAL_OUT0 = 47
00454 
00455     ## @brief Force the ArbotiX2 to rescan the Dynamixel busses.
00456     def rescan(self):
00457         self.write(253, self.REG_RESCAN, [1,])
00458 
00459     ## @brief Get the value of an analog input pin.
00460     ##
00461     ## @param index The ID of the pin to read (0 to 7).
00462     ##
00463     ## @param leng The number of bytes to read (1 or 2).
00464     ##
00465     ## @return 8-bit/16-bit analog value of the pin, -1 if error.
00466     def getAnalog(self, index, leng=1):
00467         try:
00468             val = self.read(253, self.ANA_BASE+int(index), leng)
00469             return sum(val[i] << (i * 8) for i in range(leng))
00470         except:
00471             return -1
00472 
00473     ## @brief Get the value of an digital input pin.
00474     ##
00475     ## @param index The ID of the pin to read (0 to 31).
00476     ##
00477     ## @return 0 for low, 255 for high, -1 if error.
00478     def getDigital(self, index):
00479         try:
00480             if index < 32:
00481                 x = self.read(253, self.REG_DIGITAL_IN0 + int(index/8), 1)[0]
00482             else:
00483                 return -1
00484         except:
00485             return -1
00486         if x & (2**(index%8)):
00487             return 255
00488         else:
00489             return 0
00490 
00491     ## @brief Get the value of an digital input pin.
00492     ##
00493     ## @param index The ID of the pin to write (0 to 31).
00494     ##
00495     ## @param value The value of the port, >0 is high.
00496     ##
00497     ## @param direction The direction of the port, >0 is output.
00498     ##
00499     ## @return -1 if error.
00500     def setDigital(self, index, value, direction=0xff):
00501         if index > 31: return -1
00502         if value == 0 and direction > 0:
00503             self.write(253, self.REG_DIGITAL_OUT0 + int(index), [1])
00504         elif value > 0 and direction > 0:
00505             self.write(253, self.REG_DIGITAL_OUT0 + int(index), [3])
00506         elif value > 0 and direction == 0:
00507             self.write(253, self.REG_DIGITAL_OUT0 + int(index), [2])
00508         else:
00509             self.write(253, self.REG_DIGITAL_OUT0 + int(index), [0])
00510         return 0
00511 
00512     ## @brief Set the position of a hobby servo.
00513     ##
00514     ## @param index The ID of the servo to write (0 to 7).
00515     ##
00516     ## @param value The position of the servo in milliseconds (1500-2500). 
00517     ## A value of 0 disables servo output.
00518     ##
00519     ## @return -1 if error.
00520     def setServo(self, index, value):
00521         if index > 7: return -1
00522         if value != 0 and (value < 500 or value > 2500):
00523             print "ArbotiX Error: Servo value out of range:", value
00524         else:
00525             self.write(253, self._SERVO_BASE + 2*index, [value%256, value>>8])
00526         return 0
00527 


arbotix_python
Author(s): Michael Ferguson
autogenerated on Sat Jun 8 2019 19:34:55