dynamixel_io.py
Go to the documentation of this file.
00001 #!/usr/bin/env python
00002 # -*- coding: utf-8 -*-
00003 #
00004 # Software License Agreement (BSD License)
00005 #
00006 # Copyright (c) 2010-2011, Cody Jorgensen, Antons Rebguns.
00007 # All rights reserved.
00008 #
00009 # Redistribution and use in source and binary forms, with or without
00010 # modification, are permitted provided that the following conditions
00011 # are met:
00012 #
00013 #  * Redistributions of source code must retain the above copyright
00014 #    notice, this list of conditions and the following disclaimer.
00015 #  * Redistributions in binary form must reproduce the above
00016 #    copyright notice, this list of conditions and the following
00017 #    disclaimer in the documentation and/or other materials provided
00018 #    with the distribution.
00019 #  * Neither the name of University of Arizona nor the names of its
00020 #    contributors may be used to endorse or promote products derived
00021 #    from this software without specific prior written permission.
00022 #
00023 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034 # POSSIBILITY OF SUCH DAMAGE.
00035 
00036 
00037 __author__ = 'Cody Jorgensen, Antons Rebguns'
00038 __copyright__ = 'Copyright (c) 2010-2011 Cody Jorgensen, Antons Rebguns'
00039 
00040 __license__ = 'BSD'
00041 __maintainer__ = 'Antons Rebguns'
00042 __email__ = 'anton@email.arizona.edu'
00043 
00044 
00045 import time
00046 import serial
00047 from array import array
00048 from binascii import b2a_hex
00049 from threading import Lock
00050 
00051 from dynamixel_const import *
00052 
00053 exception = None
00054 
00055 class DynamixelIO(object):
00056     """ Provides low level IO with the Dynamixel servos through pyserial. Has the
00057     ability to write instruction packets, request and read register value
00058     packets, send and receive a response to a ping packet, and send a SYNC WRITE
00059     multi-servo instruction packet.
00060     """
00061 
00062     def __init__(self, port, baudrate, readback_echo=False):
00063         """ Constructor takes serial port and baudrate as arguments. """
00064         try:
00065             self.serial_mutex = Lock()
00066             self.ser = None
00067             self.ser = serial.Serial(port)
00068             self.ser.setTimeout(0.015)
00069             self.ser.baudrate = baudrate
00070             self.port_name = port
00071             self.readback_echo = readback_echo
00072         except SerialOpenError:
00073            raise SerialOpenError(port, baudrate)
00074 
00075     def __del__(self):
00076         """ Destructor calls DynamixelIO.close """
00077         self.close()
00078 
00079     def close(self):
00080         """
00081         Be nice, close the serial port.
00082         """
00083         if self.ser:
00084             self.ser.flushInput()
00085             self.ser.flushOutput()
00086             self.ser.close()
00087 
00088     def __write_serial(self, data):
00089         self.ser.flushInput()
00090         self.ser.flushOutput()
00091         self.ser.write(data)
00092         if self.readback_echo:
00093             self.ser.read(len(data))
00094 
00095     def __read_response(self, servo_id):
00096         data = []
00097 
00098         try:
00099             data.extend(self.ser.read(4))
00100             if not data[0:2] == ['\xff', '\xff']: raise Exception('Wrong packet prefix %s' % data[0:2])
00101             data.extend(self.ser.read(ord(data[3])))
00102             data = array('B', ''.join(data)).tolist() # [int(b2a_hex(byte), 16) for byte in data]
00103         except Exception, e:
00104             raise DroppedPacketError('Invalid response received from motor %d. %s' % (servo_id, e))
00105 
00106         # verify checksum
00107         checksum = 255 - sum(data[2:-1]) % 256
00108         if not checksum == data[-1]: raise ChecksumError(servo_id, data, checksum)
00109 
00110         return data
00111 
00112     def read(self, servo_id, address, size):
00113         """ Read "size" bytes of data from servo with "servo_id" starting at the
00114         register with "address". "address" is an integer between 0 and 57. It is
00115         recommended to use the constants in module dynamixel_const for readability.
00116 
00117         To read the position from servo with id 1, the method should be called
00118         like:
00119             read(1, DXL_GOAL_POSITION_L, 2)
00120         """
00121         # Number of bytes following standard header (0xFF, 0xFF, id, length)
00122         length = 4  # instruction, address, size, checksum
00123 
00124         # directly from AX-12 manual:
00125         # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
00126         # If the calculated value is > 255, the lower byte is the check sum.
00127         checksum = 255 - ( (servo_id + length + DXL_READ_DATA + address + size) % 256 )
00128 
00129         # packet: FF  FF  ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
00130         packet = [0xFF, 0xFF, servo_id, length, DXL_READ_DATA, address, size, checksum]
00131         packetStr = array('B', packet).tostring() # same as: packetStr = ''.join([chr(byte) for byte in packet])
00132 
00133         with self.serial_mutex:
00134             self.__write_serial(packetStr)
00135 
00136             # wait for response packet from the motor
00137             timestamp = time.time()
00138             time.sleep(0.0013)#0.00235)
00139 
00140             # read response
00141             data = self.__read_response(servo_id)
00142             data.append(timestamp)
00143 
00144         return data
00145 
00146     def write(self, servo_id, address, data):
00147         """ Write the values from the "data" list to the servo with "servo_id"
00148         starting with data[0] at "address", continuing through data[n-1] at
00149         "address" + (n-1), where n = len(data). "address" is an integer between
00150         0 and 49. It is recommended to use the constants in module dynamixel_const
00151         for readability. "data" is a list/tuple of integers.
00152 
00153         To set servo with id 1 to position 276, the method should be called
00154         like:
00155             write(1, DXL_GOAL_POSITION_L, (20, 1))
00156         """
00157         # Number of bytes following standard header (0xFF, 0xFF, id, length)
00158         length = 3 + len(data)  # instruction, address, len(data), checksum
00159 
00160         # directly from AX-12 manual:
00161         # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
00162         # If the calculated value is > 255, the lower byte is the check sum.
00163         checksum = 255 - ((servo_id + length + DXL_WRITE_DATA + address + sum(data)) % 256)
00164 
00165         # packet: FF  FF  ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
00166         packet = [0xFF, 0xFF, servo_id, length, DXL_WRITE_DATA, address]
00167         packet.extend(data)
00168         packet.append(checksum)
00169 
00170         packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet])
00171 
00172         with self.serial_mutex:
00173             self.__write_serial(packetStr)
00174 
00175             # wait for response packet from the motor
00176             timestamp = time.time()
00177             time.sleep(0.0013)
00178 
00179             # read response
00180             data = self.__read_response(servo_id)
00181             data.append(timestamp)
00182 
00183         return data
00184 
00185     def sync_write(self, address, data):
00186         """ Use Broadcast message to send multiple servos instructions at the
00187         same time. No "status packet" will be returned from any servos.
00188         "address" is an integer between 0 and 49. It is recommended to use the
00189         constants in module dynamixel_const for readability. "data" is a tuple of
00190         tuples. Each tuple in "data" must contain the servo id followed by the
00191         data that should be written from the starting address. The amount of
00192         data can be as long as needed.
00193 
00194         To set servo with id 1 to position 276 and servo with id 2 to position
00195         550, the method should be called like:
00196             sync_write(DXL_GOAL_POSITION_L, ( (1, 20, 1), (2 ,38, 2) ))
00197         """
00198         # Calculate length and sum of all data
00199         flattened = [value for servo in data for value in servo]
00200 
00201         # Number of bytes following standard header (0xFF, 0xFF, id, length) plus data
00202         length = 4 + len(flattened)
00203 
00204         checksum = 255 - ((DXL_BROADCAST + length + \
00205                           DXL_SYNC_WRITE + address + len(data[0][1:]) + \
00206                           sum(flattened)) % 256)
00207 
00208         # packet: FF  FF  ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
00209         packet = [0xFF, 0xFF, DXL_BROADCAST, length, DXL_SYNC_WRITE, address, len(data[0][1:])]
00210         packet.extend(flattened)
00211         packet.append(checksum)
00212 
00213         packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet])
00214 
00215         with self.serial_mutex:
00216             self.__write_serial(packetStr)
00217 
00218     def ping(self, servo_id):
00219         """ Ping the servo with "servo_id". This causes the servo to return a
00220         "status packet". This can tell us if the servo is attached and powered,
00221         and if so, if there are any errors.
00222         """
00223         # Number of bytes following standard header (0xFF, 0xFF, id, length)
00224         length = 2  # instruction, checksum
00225 
00226         # directly from AX-12 manual:
00227         # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
00228         # If the calculated value is > 255, the lower byte is the check sum.
00229         checksum = 255 - ((servo_id + length + DXL_PING) % 256)
00230 
00231         # packet: FF  FF  ID LENGTH INSTRUCTION CHECKSUM
00232         packet = [0xFF, 0xFF, servo_id, length, DXL_PING, checksum]
00233         packetStr = array('B', packet).tostring()
00234 
00235         with self.serial_mutex:
00236             self.__write_serial(packetStr)
00237 
00238             # wait for response packet from the motor
00239             timestamp = time.time()
00240             time.sleep(0.0013)
00241 
00242             # read response
00243             try:
00244                 response = self.__read_response(servo_id)
00245                 response.append(timestamp)
00246             except Exception, e:
00247                 response = []
00248 
00249         if response:
00250             self.exception_on_error(response[4], servo_id, 'ping')
00251         return response
00252 
00253     def test_bit(self, number, offset):
00254         mask = 1 << offset
00255         return (number & mask)
00256 
00257 
00258     ######################################################################
00259     # These function modify EEPROM data which persists after power cycle #
00260     ######################################################################
00261 
00262     def set_id(self, old_id, new_id):
00263         """
00264         Sets a new unique number to identify a motor. The range from 1 to 253
00265         (0xFD) can be used.
00266         """
00267         response = self.write(old_id, DXL_ID, [new_id])
00268         if response:
00269             self.exception_on_error(response[4], old_id, 'setting id to %d' % new_id)
00270         return response
00271 
00272     def set_baud_rate(self, servo_id, baud_rate):
00273         """
00274         Sets servo communication speed. The range from 0 to 254.
00275         """
00276         response = self.write(servo_id, DXL_BAUD_RATE, [baud_rate])
00277         if response:
00278             self.exception_on_error(response[4], servo_id, 'setting baud rate to %d' % baud_rate)
00279         return response
00280 
00281     def set_return_delay_time(self, servo_id, delay):
00282         """
00283         Sets the delay time from the transmission of Instruction Packet until
00284         the return of Status Packet. 0 to 254 (0xFE) can be used, and the delay
00285         time per data value is 2 usec.
00286         """
00287         response = self.write(servo_id, DXL_RETURN_DELAY_TIME, [delay])
00288         if response:
00289             self.exception_on_error(response[4], servo_id, 'setting return delay time to %d' % delay)
00290         return response
00291 
00292     def set_angle_limit_cw(self, servo_id, angle_cw):
00293         """
00294         Set the min (CW) angle of rotation limit.
00295         """
00296         loVal = int(angle_cw % 256)
00297         hiVal = int(angle_cw >> 8)
00298 
00299         response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loVal, hiVal))
00300         if response:
00301             self.exception_on_error(response[4], servo_id, 'setting CW angle limits to %d' % angle_cw)
00302         return response
00303 
00304     def set_angle_limit_ccw(self, servo_id, angle_ccw):
00305         """
00306         Set the max (CCW) angle of rotation limit.
00307         """
00308         loVal = int(angle_ccw % 256)
00309         hiVal = int(angle_ccw >> 8)
00310 
00311         response = self.write(servo_id, DXL_CCW_ANGLE_LIMIT_L, (loVal, hiVal))
00312         if response:
00313             self.exception_on_error(response[4], servo_id, 'setting CCW angle limits to %d' % angle_ccw)
00314         return response
00315 
00316     def set_angle_limits(self, servo_id, min_angle, max_angle):
00317         """
00318         Set the min (CW) and max (CCW) angle of rotation limits.
00319         """
00320         loMinVal = int(min_angle % 256)
00321         hiMinVal = int(min_angle >> 8)
00322         loMaxVal = int(max_angle % 256)
00323         hiMaxVal = int(max_angle >> 8)
00324 
00325         # set 4 register values with low and high bytes for min and max angles
00326         response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loMinVal, hiMinVal, loMaxVal, hiMaxVal))
00327         if response:
00328             self.exception_on_error(response[4], servo_id, 'setting CW and CCW angle limits to %d and %d' %(min_angle, max_angle))
00329         return response
00330 
00331     def set_drive_mode(self, servo_id, is_slave=False, is_reverse=False):
00332         """
00333         Sets the drive mode for EX-106 motors
00334         """
00335         drive_mode = (is_slave << 1) + is_reverse
00336 
00337         response = self.write(servo_id, DXL_DRIVE_MODE, [drive_mode])
00338         if response:
00339             self.exception_on_error(response[4], servo_id, 'setting drive mode to %d' % drive_mode)
00340         return response
00341 
00342     def set_voltage_limit_min(self, servo_id, min_voltage):
00343         """
00344         Set the minimum voltage limit.
00345         NOTE: the absolute min is 5v
00346         """
00347 
00348         if min_voltage < 5: min_voltage = 5
00349         minVal = int(min_voltage * 10)
00350 
00351         response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, [minVal])
00352         if response:
00353             self.exception_on_error(response[4], servo_id, 'setting minimum voltage level to %d' % min_voltage)
00354         return response
00355 
00356     def set_voltage_limit_max(self, servo_id, max_voltage):
00357         """
00358         Set the maximum voltage limit.
00359         NOTE: the absolute min is 25v
00360         """
00361 
00362         if max_voltage > 25: max_voltage = 25
00363         maxVal = int(max_voltage * 10)
00364 
00365         response = self.write(servo_id, DXL_UP_LIMIT_VOLTAGE, [maxVal])
00366         if response:
00367             self.exception_on_error(response[4], servo_id, 'setting maximum voltage level to %d' % max_voltage)
00368         return response
00369 
00370     def set_voltage_limits(self, servo_id, min_voltage, max_voltage):
00371         """
00372         Set the min and max voltage limits.
00373         NOTE: the absolute min is 5v and the absolute max is 25v
00374         """
00375 
00376         if min_voltage < 5: min_voltage = 5
00377         if max_voltage > 25: max_voltage = 25
00378 
00379         minVal = int(min_voltage * 10)
00380         maxVal = int(max_voltage * 10)
00381 
00382         response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, (minVal, maxVal))
00383         if response:
00384             self.exception_on_error(response[4], servo_id, 'setting min and max voltage levels to %d and %d' %(min_voltage, max_voltage))
00385         return response
00386 
00387 
00388     ###############################################################
00389     # These functions can send a single command to a single servo #
00390     ###############################################################
00391 
00392     def set_torque_enabled(self, servo_id, enabled):
00393         """
00394         Sets the value of the torque enabled register to 1 or 0. When the
00395         torque is disabled the servo can be moved manually while the motor is
00396         still powered.
00397         """
00398         response = self.write(servo_id, DXL_TORQUE_ENABLE, [enabled])
00399         if response:
00400             self.exception_on_error(response[4], servo_id, '%sabling torque' % 'en' if enabled else 'dis')
00401         return response
00402 
00403     def set_compliance_margin_cw(self, servo_id, margin):
00404         """
00405         The error between goal position and present position in CW direction.
00406         The range of the value is 0 to 255, and the unit is the same as Goal Position.
00407         The greater the value, the more difference occurs.
00408         """
00409         response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, [margin])
00410         if response:
00411             self.exception_on_error(response[4], servo_id, 'setting CW compliance margin to %d' % margin)
00412         return response
00413 
00414     def set_compliance_margin_ccw(self, servo_id, margin):
00415         """
00416         The error between goal position and present position in CCW direction.
00417         The range of the value is 0 to 255, and the unit is the same as Goal Position.
00418         The greater the value, the more difference occurs.
00419         """
00420         response = self.write(servo_id, DXL_CCW_COMPLIANCE_MARGIN, [margin])
00421         if response:
00422             self.exception_on_error(response[4], servo_id, 'setting CCW compliance margin to %d' % margin)
00423         return response
00424 
00425     def set_compliance_margins(self, servo_id, margin_cw, margin_ccw):
00426         """
00427         The error between goal position and present position in CCW direction.
00428         The range of the value is 0 to 255, and the unit is the same as Goal Position.
00429         The greater the value, the more difference occurs.
00430         """
00431         response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, (margin_cw, margin_ccw))
00432         if response:
00433             self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance margins to values %d and %d' %(margin_cw, margin_ccw))
00434         return response
00435 
00436     def set_compliance_slope_cw(self, servo_id, slope):
00437         """
00438         Sets the level of Torque near the goal position in CW direction.
00439         Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00440         """
00441         response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, [slope])
00442         if response:
00443             self.exception_on_error(response[4], servo_id, 'setting CW compliance slope to %d' %  slope)
00444         return response
00445 
00446     def set_compliance_slope_ccw(self, servo_id, slope):
00447         """
00448         Sets the level of Torque near the goal position in CCW direction.
00449         Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00450         """
00451         response = self.write(servo_id, DXL_CCW_COMPLIANCE_SLOPE, [slope])
00452         if response:
00453             self.exception_on_error(response[4], servo_id, 'setting CCW compliance slope to %d' % slope)
00454         return response
00455 
00456     def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw):
00457         """
00458         Sets the level of Torque near the goal position in CW/CCW direction.
00459         Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00460         """
00461         response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, (slope_cw, slope_ccw))
00462         if response:
00463             self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance slopes to %d and %d' %(slope_cw, slope_ccw))
00464         return response
00465 
00466     def set_d_gain(self, servo_id, d_gain):
00467         """
00468         Sets the value of derivative action of PID controller.
00469         Gain value is in range 0 to 254.
00470         """
00471         response = self.write(servo_id, DXL_D_GAIN, [d_gain])
00472         if response:
00473             self.exception_on_error(response[4], servo_id, 'setting D gain value of PID controller to %d' % slope)
00474         return response
00475 
00476     def set_i_gain(self, servo_id, i_gain):
00477         """
00478         Sets the value of integral action of PID controller.
00479         Gain value is in range 0 to 254.
00480         """
00481         response = self.write(servo_id, DXL_I_GAIN, [i_gain])
00482         if response:
00483             self.exception_on_error(response[4], servo_id, 'setting I gain value of PID controller to %d' % slope)
00484         return response
00485 
00486     def set_p_gain(self, servo_id, p_gain):
00487         """
00488         Sets the value of proportional action of PID controller.
00489         Gain value is in range 0 to 254.
00490         """
00491         response = self.write(servo_id, DXL_P_GAIN, [p_gain])
00492         if response:
00493             self.exception_on_error(response[4], servo_id, 'setting P gain value of PID controller to %d' % slope)
00494         return response
00495 
00496     def set_punch(self, servo_id, punch):
00497         """
00498         Sets the limit value of torque being reduced when the output torque is
00499         decreased in the Compliance Slope area. In other words, it is the mimimum
00500         torque. The initial value is 32 (0x20) and can be extended up to 1023
00501         (0x3FF). (Refer to Compliance margin & Slope)
00502         """
00503         loVal = int(punch % 256)
00504         hiVal = int(punch >> 8)
00505         response = self.write(servo_id, DXL_PUNCH_L, (loVal, hiVal))
00506         if response:
00507             self.exception_on_error(response[4], servo_id, 'setting punch to %d' % punch)
00508         return response
00509 
00510     def set_acceleration(self, servo_id, acceleration):
00511         """
00512         Sets the acceleration. The unit is 8.583 Degree / sec^2.
00513         0 - acceleration control disabled, 1-254 - valid range for acceleration.
00514         """
00515 
00516         model = self.get_model_number(servo_id)
00517         if not model in DXL_MODEL_TO_PARAMS:
00518             raise UnsupportedFeatureError(model, DXL_GOAL_ACCELERATION)
00519 
00520         if DXL_GOAL_ACCELERATION in DXL_MODEL_TO_PARAMS[model]['features']:
00521             response = self.write(servo_id, DXL_GOAL_ACCELERATION, (acceleration, ))
00522             if response:
00523                 self.exception_on_error(response[4], servo_id, 'setting acceleration to %d' % acceleration)
00524             return response
00525         else:
00526             raise UnsupportedFeatureError(model, DXL_GOAL_ACCELERATION)
00527 
00528     def set_position(self, servo_id, position):
00529         """
00530         Set the servo with servo_id to the specified goal position.
00531         Position value must be positive.
00532         """
00533         loVal = int(position % 256)
00534         hiVal = int(position >> 8)
00535 
00536         response = self.write(servo_id, DXL_GOAL_POSITION_L, (loVal, hiVal))
00537         if response:
00538             self.exception_on_error(response[4], servo_id, 'setting goal position to %d' % position)
00539         return response
00540 
00541     def set_speed(self, servo_id, speed):
00542         """
00543         Set the servo with servo_id to the specified goal speed.
00544         Speed can be negative only if the dynamixel is in "freespin" mode.
00545         """
00546         # split speed into 2 bytes
00547         if speed >= 0:
00548             loVal = int(speed % 256)
00549             hiVal = int(speed >> 8)
00550         else:
00551             loVal = int((1023 - speed) % 256)
00552             hiVal = int((1023 - speed) >> 8)
00553 
00554         # set two register values with low and high byte for the speed
00555         response = self.write(servo_id, DXL_GOAL_SPEED_L, (loVal, hiVal))
00556         if response:
00557             self.exception_on_error(response[4], servo_id, 'setting moving speed to %d' % speed)
00558         return response
00559 
00560     def set_torque_limit(self, servo_id, torque):
00561         """
00562         Sets the value of the maximum torque limit for servo with id servo_id.
00563         Valid values are 0 to 1023 (0x3FF), and the unit is about 0.1%.
00564         For example, if the value is 512 only 50% of the maximum torque will be used.
00565         If the power is turned on, the value of Max Torque (Address 14, 15) is used as the initial value.
00566         """
00567         loVal = int(torque % 256)
00568         hiVal = int(torque >> 8)
00569 
00570         response = self.write(servo_id, DXL_TORQUE_LIMIT_L, (loVal, hiVal))
00571         if response:
00572             self.exception_on_error(response[4], servo_id, 'setting torque limit to %d' % torque)
00573         return response
00574 
00575     def set_goal_torque(self, servo_id, torque):
00576         """
00577         Set the servo to torque control mode (similar to wheel mode, but controlling the torque)
00578         Valid values are from -1023 to 1023.
00579         Anything outside this range or 'None' disables torque control.
00580         """
00581 
00582         model = self.get_model_number(servo_id)
00583         if not model in DXL_MODEL_TO_PARAMS:
00584             raise UnsupportedFeatureError(model, DXL_TORQUE_CONTROL_MODE)
00585 
00586         valid_torque = torque is not None and torque >= -1023 and torque <= 1023
00587         if torque is not None and torque < 0:
00588             torque = 1024 - torque
00589 
00590         if DXL_TORQUE_CONTROL_MODE in DXL_MODEL_TO_PARAMS[model]['features']:
00591             if valid_torque:
00592                 loVal = int(torque % 256); hiVal = int(torque >> 8);
00593                 response = self.write(servo_id, DXL_GOAL_TORQUE_L, (loVal, hiVal))
00594                 if response:
00595                     self.exception_on_error(response[4], servo_id, 'setting goal torque to %d' % torque)
00596             response = self.write(servo_id, DXL_TORQUE_CONTROL_MODE, (int(valid_torque), ))
00597             if response:
00598                 self.exception_on_error(response[4], servo_id, 'enabling torque mode')
00599             return response
00600         else:
00601             raise UnsupportedFeatureError(model, DXL_TORQUE_CONTROL_MODE)
00602 
00603     def set_position_and_speed(self, servo_id, position, speed):
00604         """
00605         Set the servo with servo_id to specified position and speed.
00606         Speed can be negative only if the dynamixel is in "freespin" mode.
00607         """
00608         # split speed into 2 bytes
00609         if speed >= 0:
00610             loSpeedVal = int(speed % 256)
00611             hiSpeedVal = int(speed >> 8)
00612         else:
00613             loSpeedVal = int((1023 - speed) % 256)
00614             hiSpeedVal = int((1023 - speed) >> 8)
00615 
00616         # split position into 2 bytes
00617         loPositionVal = int(position % 256)
00618         hiPositionVal = int(position >> 8)
00619 
00620         response = self.write(servo_id, DXL_GOAL_POSITION_L, (loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal))
00621         if response:
00622             self.exception_on_error(response[4], servo_id, 'setting goal position to %d and moving speed to %d' %(position, speed))
00623         return response
00624 
00625     def set_led(self, servo_id, led_state):
00626         """
00627         Turn the LED of servo motor on/off.
00628         Possible boolean state values:
00629             True - turn the LED on,
00630             False - turn the LED off.
00631         """
00632         response = self.write(servo_id, DXL_LED, [led_state])
00633         if response:
00634             self.exception_on_error(response[4], servo_id,
00635                     'setting a LED to %s' % led_state)
00636         return response
00637 
00638 
00639     #################################################################
00640     # These functions can send multiple commands to multiple servos #
00641     # These commands are used in ROS wrapper as they don't send a   #
00642     # response packet, ROS wrapper gets motor states at a set rate  #
00643     #################################################################
00644 
00645     def set_multi_torque_enabled(self, valueTuples):
00646         """
00647         Method to set multiple servos torque enabled.
00648         Should be called as such:
00649         set_multi_servos_to_torque_enabled( (id1, True), (id2, True), (id3, True) )
00650         """
00651         # use sync write to broadcast multi servo message
00652         self.sync_write(DXL_TORQUE_ENABLE, tuple(valueTuples))
00653 
00654     def set_multi_compliance_margin_cw(self, valueTuples):
00655         """
00656         Set different CW compliance margin for multiple servos.
00657         Should be called as such:
00658         set_multi_compliance_margin_cw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) )
00659         """
00660         self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
00661 
00662     def set_multi_compliance_margin_ccw(self, valueTuples):
00663         """
00664         Set different CCW compliance margin for multiple servos.
00665         Should be called as such:
00666         set_multi_compliance_margin_ccw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) )
00667         """
00668         self.sync_write(DXL_CCW_COMPLIANCE_MARGIN, tuple(valueTuples))
00669 
00670     def set_multi_compliance_margins(self, valueTuples):
00671         """
00672         Set different CW and CCW compliance margins for multiple servos.
00673         Should be called as such:
00674         set_multi_compliance_margins( ( (id1, cw_margin1, ccw_margin1), (id2, cw_margin2, ccw_margin2) ) )
00675         """
00676         self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
00677 
00678     def set_multi_compliance_slope_cw(self, valueTuples):
00679         """
00680         Set different CW compliance slope for multiple servos.
00681         Should be called as such:
00682         set_multi_compliance_slope_cw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) )
00683         """
00684         self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
00685 
00686     def set_multi_compliance_slope_ccw(self, valueTuples):
00687         """
00688         Set different CCW compliance slope for multiple servos.
00689         Should be called as such:
00690         set_multi_compliance_slope_ccw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) )
00691         """
00692         self.sync_write(DXL_CCW_COMPLIANCE_SLOPE, tuple(valueTuples))
00693 
00694     def set_multi_compliance_slopes(self, valueTuples):
00695         """
00696         Set different CW and CCW compliance slopes for multiple servos.
00697         Should be called as such:
00698         set_multi_compliance_slopes( ( (id1, cw_slope1, ccw_slope1), (id2, cw_slope2, ccw_slope2) ) )
00699         """
00700         self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
00701 
00702     def set_multi_punch(self, valueTuples):
00703         """
00704         Set different punch values for multiple servos.
00705         NOTE: according to documentation, currently this value is not being used.
00706         Should be called as such:
00707         set_multi_punch( ( (id1, punch1), (id2, punch2), (id3, punch3) ) )
00708         """
00709         # prepare value tuples for call to syncwrite
00710         writeableVals = []
00711 
00712         for sid,punch in valueTuples:
00713             # split punch into 2 bytes
00714             loVal = int(punch % 256)
00715             hiVal = int(punch >> 8)
00716             writeableVals.append( (sid, loVal, hiVal) )
00717 
00718         # use sync write to broadcast multi servo message
00719         self.sync_write(DXL_PUNCH_L, writeableVals)
00720 
00721     def set_multi_position(self, valueTuples):
00722         """
00723         Set different positions for multiple servos.
00724         Should be called as such:
00725         set_multi_position( ( (id1, position1), (id2, position2), (id3, position3) ) )
00726         """
00727         # prepare value tuples for call to syncwrite
00728         writeableVals = []
00729 
00730         for vals in valueTuples:
00731             sid = vals[0]
00732             position = vals[1]
00733             # split position into 2 bytes
00734             loVal = int(position % 256)
00735             hiVal = int(position >> 8)
00736             writeableVals.append( (sid, loVal, hiVal) )
00737 
00738         # use sync write to broadcast multi servo message
00739         self.sync_write(DXL_GOAL_POSITION_L, writeableVals)
00740 
00741     def set_multi_speed(self, valueTuples):
00742         """
00743         Set different speeds for multiple servos.
00744         Should be called as such:
00745         set_multi_speed( ( (id1, speed1), (id2, speed2), (id3, speed3) ) )
00746         """
00747         # prepare value tuples for call to syncwrite
00748         writeableVals = []
00749 
00750         for vals in valueTuples:
00751             sid = vals[0]
00752             speed = vals[1]
00753 
00754             # split speed into 2 bytes
00755             if speed >= 0:
00756                 loVal = int(speed % 256)
00757                 hiVal = int(speed >> 8)
00758             else:
00759                 loVal = int((1023 - speed) % 256)
00760                 hiVal = int((1023 - speed) >> 8)
00761 
00762             writeableVals.append( (sid, loVal, hiVal) )
00763 
00764         # use sync write to broadcast multi servo message
00765         self.sync_write(DXL_GOAL_SPEED_L, writeableVals)
00766 
00767     def set_multi_torque_limit(self, valueTuples):
00768         """
00769         Set different torque limits for multiple servos.
00770         Should be called as such:
00771         set_multi_torque_limit( ( (id1, torque1), (id2, torque2), (id3, torque3) ) )
00772         """
00773         # prepare value tuples for call to syncwrite
00774         writeableVals = []
00775 
00776         for sid,torque in valueTuples:
00777             # split torque into 2 bytes
00778             loVal = int(torque % 256)
00779             hiVal = int(torque >> 8)
00780             writeableVals.append( (sid, loVal, hiVal) )
00781 
00782         # use sync write to broadcast multi servo message
00783         self.sync_write(DXL_TORQUE_LIMIT_L, writeableVals)
00784 
00785     def set_multi_position_and_speed(self, valueTuples):
00786         """
00787         Set different positions and speeds for multiple servos.
00788         Should be called as such:
00789         set_multi_position_and_speed( ( (id1, position1, speed1), (id2, position2, speed2), (id3, position3, speed3) ) )
00790         """
00791         # prepare value tuples for call to syncwrite
00792         writeableVals = []
00793 
00794         for vals in valueTuples:
00795             sid = vals[0]
00796             position = vals[1]
00797             speed = vals[2]
00798 
00799             # split speed into 2 bytes
00800             if speed >= 0:
00801                 loSpeedVal = int(speed % 256)
00802                 hiSpeedVal = int(speed >> 8)
00803             else:
00804                 loSpeedVal = int((1023 - speed) % 256)
00805                 hiSpeedVal = int((1023 - speed) >> 8)
00806 
00807             # split position into 2 bytes
00808             loPositionVal = int(position % 256)
00809             hiPositionVal = int(position >> 8)
00810             writeableVals.append( (sid, loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal) )
00811 
00812         # use sync write to broadcast multi servo message
00813         self.sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals))
00814 
00815 
00816     #################################
00817     # Servo status access functions #
00818     #################################
00819 
00820     def get_model_number(self, servo_id):
00821         """ Reads the servo's model number (e.g. 12 for AX-12+). """
00822         response = self.read(servo_id, DXL_MODEL_NUMBER_L, 2)
00823         if response:
00824             self.exception_on_error(response[4], servo_id, 'fetching model number')
00825         return response[5] + (response[6] << 8)
00826 
00827     def get_firmware_version(self, servo_id):
00828         """ Reads the servo's firmware version. """
00829         response = self.read(servo_id, DXL_VERSION, 1)
00830         if response:
00831             self.exception_on_error(response[4], servo_id, 'fetching firmware version')
00832         return response[5]
00833 
00834     def get_return_delay_time(self, servo_id):
00835         """ Reads the servo's return delay time. """
00836         response = self.read(servo_id, DXL_RETURN_DELAY_TIME, 1)
00837         if response:
00838             self.exception_on_error(response[4], servo_id, 'fetching return delay time')
00839         return response[5]
00840 
00841     def get_angle_limits(self, servo_id):
00842         """
00843         Returns the min and max angle limits from the specified servo.
00844         """
00845         # read in 4 consecutive bytes starting with low value of clockwise angle limit
00846         response = self.read(servo_id, DXL_CW_ANGLE_LIMIT_L, 4)
00847         if response:
00848             self.exception_on_error(response[4], servo_id, 'fetching CW/CCW angle limits')
00849         # extract data valus from the raw data
00850         cwLimit = response[5] + (response[6] << 8)
00851         ccwLimit = response[7] + (response[8] << 8)
00852 
00853         # return the data in a dictionary
00854         return {'min':cwLimit, 'max':ccwLimit}
00855 
00856     def get_drive_mode(self, servo_id):
00857         """ Reads the servo's drive mode. """
00858         response = self.read(servo_id, DXL_DRIVE_MODE, 1)
00859         if response:
00860             self.exception_on_error(response[4], servo_id, 'fetching drive mode')
00861         return response[5]
00862 
00863     def get_voltage_limits(self, servo_id):
00864         """
00865         Returns the min and max voltage limits from the specified servo.
00866         """
00867         response = self.read(servo_id, DXL_DOWN_LIMIT_VOLTAGE, 2)
00868         if response:
00869             self.exception_on_error(response[4], servo_id, 'fetching voltage limits')
00870         # extract data valus from the raw data
00871         min_voltage = response[5] / 10.0
00872         max_voltage = response[6] / 10.0
00873 
00874         # return the data in a dictionary
00875         return {'min':min_voltage, 'max':max_voltage}
00876 
00877     def get_position(self, servo_id):
00878         """ Reads the servo's position value from its registers. """
00879         response = self.read(servo_id, DXL_PRESENT_POSITION_L, 2)
00880         if response:
00881             self.exception_on_error(response[4], servo_id, 'fetching present position')
00882         position = response[5] + (response[6] << 8)
00883         return position
00884 
00885     def get_speed(self, servo_id):
00886         """ Reads the servo's speed value from its registers. """
00887         response = self.read(servo_id, DXL_PRESENT_SPEED_L, 2)
00888         if response:
00889             self.exception_on_error(response[4], servo_id, 'fetching present speed')
00890         speed = response[5] + (response[6] << 8)
00891         if speed > 1023:
00892             return 1023 - speed
00893         return speed
00894 
00895     def get_voltage(self, servo_id):
00896         """ Reads the servo's voltage. """
00897         response = self.read(servo_id, DXL_PRESENT_VOLTAGE, 1)
00898         if response:
00899             self.exception_on_error(response[4], servo_id, 'fetching supplied voltage')
00900         return response[5] / 10.0
00901 
00902     def get_current(self, servo_id):
00903         """ Reads the servo's current consumption (if supported by model) """
00904         model = self.get_model_number(servo_id)
00905         if not model in DXL_MODEL_TO_PARAMS:
00906             raise UnsupportedFeatureError(model, DXL_CURRENT_L)
00907 
00908         if DXL_CURRENT_L in DXL_MODEL_TO_PARAMS[model]['features']:
00909             response = self.read(servo_id, DXL_CURRENT_L, 2)
00910             if response:
00911                 self.exception_on_error(response[4], servo_id, 'fetching sensed current')
00912             current = response[5] + (response[6] << 8)
00913             return 0.0045 * (current - 2048)
00914 
00915         if DXL_SENSED_CURRENT_L in DXL_MODEL_TO_PARAMS[model]['features']:
00916             response = self.read(servo_id, DXL_SENSED_CURRENT_L, 2)
00917             if response:
00918                 self.exception_on_error(response[4], servo_id, 'fetching sensed current')
00919             current = response[5] + (response[6] << 8)
00920             return 0.01 * (current - 512)
00921 
00922         else:
00923             raise UnsupportedFeatureError(model, DXL_CURRENT_L)
00924 
00925 
00926     def get_feedback(self, servo_id):
00927         """
00928         Returns the id, goal, position, error, speed, load, voltage, temperature
00929         and moving values from the specified servo.
00930         """
00931         # read in 17 consecutive bytes starting with low value for goal position
00932         response = self.read(servo_id, DXL_GOAL_POSITION_L, 17)
00933 
00934         if response:
00935             self.exception_on_error(response[4], servo_id, 'fetching full servo status')
00936         if len(response) == 24:
00937             # extract data values from the raw data
00938             goal = response[5] + (response[6] << 8)
00939             position = response[11] + (response[12] << 8)
00940             error = position - goal
00941             speed = response[13] + ( response[14] << 8)
00942             if speed > 1023: speed = 1023 - speed
00943             load_raw = response[15] + (response[16] << 8)
00944             load_direction = 1 if self.test_bit(load_raw, 10) else 0
00945             load = (load_raw & int('1111111111', 2)) / 1024.0
00946             if load_direction == 1: load = -load
00947             voltage = response[17] / 10.0
00948             temperature = response[18]
00949             moving = response[21]
00950             timestamp = response[-1]
00951 
00952             # return the data in a dictionary
00953             return { 'timestamp': timestamp,
00954                      'id': servo_id,
00955                      'goal': goal,
00956                      'position': position,
00957                      'error': error,
00958                      'speed': speed,
00959                      'load': load,
00960                      'voltage': voltage,
00961                      'temperature': temperature,
00962                      'moving': bool(moving) }
00963 
00964     def get_led(self, servo_id):
00965         """
00966         Get status of the LED. Boolean return values:
00967             True - LED is on,
00968             False - LED is off.
00969         """
00970         response = self.read(servo_id, DXL_LED, 1)
00971         if response:
00972             self.exception_on_error(response[4], servo_id,
00973                 'fetching LED status')
00974 
00975         return bool(response[5])
00976 
00977 
00978     def exception_on_error(self, error_code, servo_id, command_failed):
00979         global exception
00980         exception = None
00981         ex_message = '[servo #%d on %s@%sbps]: %s failed' % (servo_id, self.ser.port, self.ser.baudrate, command_failed)
00982 
00983         if not isinstance(error_code, int):
00984             msg = 'Communcation Error ' + ex_message
00985             exception = NonfatalErrorCodeError(msg, 0)
00986             return
00987         if not error_code & DXL_OVERHEATING_ERROR == 0:
00988             msg = 'Overheating Error ' + ex_message
00989             exception = FatalErrorCodeError(msg, error_code)
00990         if not error_code & DXL_OVERLOAD_ERROR == 0:
00991             msg = 'Overload Error ' + ex_message
00992             exception = FatalErrorCodeError(msg, error_code)
00993         if not error_code & DXL_INPUT_VOLTAGE_ERROR == 0:
00994             msg = 'Input Voltage Error ' + ex_message
00995             exception = NonfatalErrorCodeError(msg, error_code)
00996         if not error_code & DXL_ANGLE_LIMIT_ERROR == 0:
00997             msg = 'Angle Limit Error ' + ex_message
00998             exception = NonfatalErrorCodeError(msg, error_code)
00999         if not error_code & DXL_RANGE_ERROR == 0:
01000             msg = 'Range Error ' + ex_message
01001             exception = NonfatalErrorCodeError(msg, error_code)
01002         if not error_code & DXL_CHECKSUM_ERROR == 0:
01003             msg = 'Checksum Error ' + ex_message
01004             exception = NonfatalErrorCodeError(msg, error_code)
01005         if not error_code & DXL_INSTRUCTION_ERROR == 0:
01006             msg = 'Instruction Error ' + ex_message
01007             exception = NonfatalErrorCodeError(msg, error_code)
01008 
01009 class SerialOpenError(Exception):
01010     def __init__(self, port, baud):
01011         Exception.__init__(self)
01012         self.message = "Cannot open port '%s' at %d bps" %(port, baud)
01013         self.port = port
01014         self.baud = baud
01015     def __str__(self):
01016         return self.message
01017 
01018 class ChecksumError(Exception):
01019     def __init__(self, servo_id, response, checksum):
01020         Exception.__init__(self)
01021         self.message = 'Checksum received from motor %d does not match the expected one (%d != %d)' \
01022                        %(servo_id, response[-1], checksum)
01023         self.response_data = response
01024         self.expected_checksum = checksum
01025     def __str__(self):
01026         return self.message
01027 
01028 class FatalErrorCodeError(Exception):
01029     def __init__(self, message, ec_const):
01030         Exception.__init__(self)
01031         self.message = message
01032         self.error_code = ec_const
01033     def __str__(self):
01034         return self.message
01035 
01036 class NonfatalErrorCodeError(Exception):
01037     def __init__(self, message, ec_const):
01038         Exception.__init__(self)
01039         self.message = message
01040         self.error_code = ec_const
01041     def __str__(self):
01042         return self.message
01043 
01044 class ErrorCodeError(Exception):
01045     def __init__(self, message, ec_const):
01046         Exception.__init__(self)
01047         self.message = message
01048         self.error_code = ec_const
01049     def __str__(self):
01050         return self.message
01051 
01052 class DroppedPacketError(Exception):
01053     def __init__(self, message):
01054         Exception.__init__(self)
01055         self.message = message
01056     def __str__(self):
01057         return self.message
01058 
01059 class UnsupportedFeatureError(Exception):
01060     def __init__(self, model_id, feature_id):
01061         Exception.__init__(self)
01062         if model_id in DXL_MODEL_TO_PARAMS:
01063             model = DXL_MODEL_TO_PARAMS[model_id]['name']
01064         else:
01065             model = 'Unknown'
01066         self.message = "Feature %d not supported by model %d (%s)" %(feature_id, model_id, model)
01067     def __str__(self):
01068         return self.message
01069 


dynamixel_driver
Author(s): Antons Rebguns, Cody Jorgensen
autogenerated on Wed Aug 26 2015 11:24:35