$search
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): 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 except SerialOpenError: 00072 raise SerialOpenError(port, baudrate) 00073 00074 def __del__(self): 00075 """ Destructor calls DynamixelIO.close """ 00076 self.close() 00077 00078 def close(self): 00079 """ 00080 Be nice, close the serial port. 00081 """ 00082 if self.ser: 00083 self.ser.flushInput() 00084 self.ser.flushOutput() 00085 self.ser.close() 00086 00087 def __write_serial(self, data): 00088 self.ser.flushInput() 00089 self.ser.flushOutput() 00090 self.ser.write(data) 00091 00092 def __read_response(self, servo_id): 00093 data = [] 00094 00095 try: 00096 data.extend(self.ser.read(4)) 00097 if not data[0:2] == ['\xff', '\xff']: raise Exception('Wrong packet prefix %s' % data[0:2]) 00098 data.extend(self.ser.read(ord(data[3]))) 00099 data = array('B', ''.join(data)).tolist() # [int(b2a_hex(byte), 16) for byte in data] 00100 except Exception, e: 00101 raise DroppedPacketError('Invalid response received from motor %d. %s' % (servo_id, e)) 00102 00103 # verify checksum 00104 checksum = 255 - sum(data[2:-1]) % 256 00105 if not checksum == data[-1]: raise ChecksumError(servo_id, data, checksum) 00106 00107 return data 00108 00109 def read(self, servo_id, address, size): 00110 """ Read "size" bytes of data from servo with "servo_id" starting at the 00111 register with "address". "address" is an integer between 0 and 57. It is 00112 recommended to use the constants in module dynamixel_const for readability. 00113 00114 To read the position from servo with id 1, the method should be called 00115 like: 00116 read(1, DXL_GOAL_POSITION_L, 2) 00117 """ 00118 # Number of bytes following standard header (0xFF, 0xFF, id, length) 00119 length = 4 # instruction, address, size, checksum 00120 00121 # directly from AX-12 manual: 00122 # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N) 00123 # If the calculated value is > 255, the lower byte is the check sum. 00124 checksum = 255 - ( (servo_id + length + DXL_READ_DATA + address + size) % 256 ) 00125 00126 # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM 00127 packet = [0xFF, 0xFF, servo_id, length, DXL_READ_DATA, address, size, checksum] 00128 packetStr = array('B', packet).tostring() # same as: packetStr = ''.join([chr(byte) for byte in packet]) 00129 00130 with self.serial_mutex: 00131 self.__write_serial(packetStr) 00132 00133 # wait for response packet from the motor 00134 timestamp = time.time() 00135 time.sleep(0.0013)#0.00235) 00136 00137 # read response 00138 data = self.__read_response(servo_id) 00139 data.append(timestamp) 00140 00141 return data 00142 00143 def write(self, servo_id, address, data): 00144 """ Write the values from the "data" list to the servo with "servo_id" 00145 starting with data[0] at "address", continuing through data[n-1] at 00146 "address" + (n-1), where n = len(data). "address" is an integer between 00147 0 and 49. It is recommended to use the constants in module dynamixel_const 00148 for readability. "data" is a list/tuple of integers. 00149 00150 To set servo with id 1 to position 276, the method should be called 00151 like: 00152 write(1, DXL_GOAL_POSITION_L, (20, 1)) 00153 """ 00154 # Number of bytes following standard header (0xFF, 0xFF, id, length) 00155 length = 3 + len(data) # instruction, address, len(data), checksum 00156 00157 # directly from AX-12 manual: 00158 # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N) 00159 # If the calculated value is > 255, the lower byte is the check sum. 00160 checksum = 255 - ((servo_id + length + DXL_WRITE_DATA + address + sum(data)) % 256) 00161 00162 # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM 00163 packet = [0xFF, 0xFF, servo_id, length, DXL_WRITE_DATA, address] 00164 packet.extend(data) 00165 packet.append(checksum) 00166 00167 packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet]) 00168 00169 with self.serial_mutex: 00170 self.__write_serial(packetStr) 00171 00172 # wait for response packet from the motor 00173 timestamp = time.time() 00174 time.sleep(0.0013) 00175 00176 # read response 00177 data = self.__read_response(servo_id) 00178 data.append(timestamp) 00179 00180 return data 00181 00182 def sync_write(self, address, data): 00183 """ Use Broadcast message to send multiple servos instructions at the 00184 same time. No "status packet" will be returned from any servos. 00185 "address" is an integer between 0 and 49. It is recommended to use the 00186 constants in module dynamixel_const for readability. "data" is a tuple of 00187 tuples. Each tuple in "data" must contain the servo id followed by the 00188 data that should be written from the starting address. The amount of 00189 data can be as long as needed. 00190 00191 To set servo with id 1 to position 276 and servo with id 2 to position 00192 550, the method should be called like: 00193 sync_write(DXL_GOAL_POSITION_L, ( (1, 20, 1), (2 ,38, 2) )) 00194 """ 00195 # Calculate length and sum of all data 00196 flattened = [value for servo in data for value in servo] 00197 00198 # Number of bytes following standard header (0xFF, 0xFF, id, length) plus data 00199 length = 4 + len(flattened) 00200 00201 checksum = 255 - ((DXL_BROADCAST + length + \ 00202 DXL_SYNC_WRITE + address + len(data[0][1:]) + \ 00203 sum(flattened)) % 256) 00204 00205 # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM 00206 packet = [0xFF, 0xFF, DXL_BROADCAST, length, DXL_SYNC_WRITE, address, len(data[0][1:])] 00207 packet.extend(flattened) 00208 packet.append(checksum) 00209 00210 packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet]) 00211 00212 with self.serial_mutex: 00213 self.__write_serial(packetStr) 00214 00215 def ping(self, servo_id): 00216 """ Ping the servo with "servo_id". This causes the servo to return a 00217 "status packet". This can tell us if the servo is attached and powered, 00218 and if so, if there are any errors. 00219 """ 00220 # Number of bytes following standard header (0xFF, 0xFF, id, length) 00221 length = 2 # instruction, checksum 00222 00223 # directly from AX-12 manual: 00224 # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N) 00225 # If the calculated value is > 255, the lower byte is the check sum. 00226 checksum = 255 - ((servo_id + length + DXL_PING) % 256) 00227 00228 # packet: FF FF ID LENGTH INSTRUCTION CHECKSUM 00229 packet = [0xFF, 0xFF, servo_id, length, DXL_PING, checksum] 00230 packetStr = array('B', packet).tostring() 00231 00232 with self.serial_mutex: 00233 self.__write_serial(packetStr) 00234 00235 # wait for response packet from the motor 00236 timestamp = time.time() 00237 time.sleep(0.0013) 00238 00239 # read response 00240 try: 00241 response = self.__read_response(servo_id) 00242 response.append(timestamp) 00243 except Exception, e: 00244 response = [] 00245 00246 if response: 00247 self.exception_on_error(response[4], servo_id, 'ping') 00248 return response 00249 00250 def test_bit(self, number, offset): 00251 mask = 1 << offset 00252 return (number & mask) 00253 00254 00255 ###################################################################### 00256 # These function modify EEPROM data which persists after power cycle # 00257 ###################################################################### 00258 00259 def set_id(self, old_id, new_id): 00260 """ 00261 Sets a new unique number to identify a motor. The range from 1 to 253 00262 (0xFD) can be used. 00263 """ 00264 response = self.write(old_id, DXL_ID, [new_id]) 00265 if response: 00266 self.exception_on_error(response[4], old_id, 'setting id to %d' % new_id) 00267 return response 00268 00269 def set_baud_rate(self, servo_id, baud_rate): 00270 """ 00271 Sets servo communication speed. The range from 0 to 254. 00272 """ 00273 response = self.write(servo_id, DXL_BAUD_RATE, [baud_rate]) 00274 if response: 00275 self.exception_on_error(response[4], servo_id, 'setting baud rate to %d' % baud_rate) 00276 return response 00277 00278 def set_return_delay_time(self, servo_id, delay): 00279 """ 00280 Sets the delay time from the transmission of Instruction Packet until 00281 the return of Status Packet. 0 to 254 (0xFE) can be used, and the delay 00282 time per data value is 2 usec. 00283 """ 00284 response = self.write(servo_id, DXL_RETURN_DELAY_TIME, [delay]) 00285 if response: 00286 self.exception_on_error(response[4], servo_id, 'setting return delay time to %d' % delay) 00287 return response 00288 00289 def set_angle_limit_cw(self, servo_id, angle_cw): 00290 """ 00291 Set the min (CW) angle of rotation limit. 00292 """ 00293 loVal = int(angle_cw % 256) 00294 hiVal = int(angle_cw >> 8) 00295 00296 response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loVal, hiVal)) 00297 if response: 00298 self.exception_on_error(response[4], servo_id, 'setting CW angle limits to %d' % angle_cw) 00299 return response 00300 00301 def set_angle_limit_ccw(self, servo_id, angle_ccw): 00302 """ 00303 Set the max (CCW) angle of rotation limit. 00304 """ 00305 loVal = int(angle_ccw % 256) 00306 hiVal = int(angle_ccw >> 8) 00307 00308 response = self.write(servo_id, DXL_CCW_ANGLE_LIMIT_L, (loVal, hiVal)) 00309 if response: 00310 self.exception_on_error(response[4], servo_id, 'setting CCW angle limits to %d' % angle_ccw) 00311 return response 00312 00313 def set_angle_limits(self, servo_id, min_angle, max_angle): 00314 """ 00315 Set the min (CW) and max (CCW) angle of rotation limits. 00316 """ 00317 loMinVal = int(min_angle % 256) 00318 hiMinVal = int(min_angle >> 8) 00319 loMaxVal = int(max_angle % 256) 00320 hiMaxVal = int(max_angle >> 8) 00321 00322 # set 4 register values with low and high bytes for min and max angles 00323 response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loMinVal, hiMinVal, loMaxVal, hiMaxVal)) 00324 if response: 00325 self.exception_on_error(response[4], servo_id, 'setting CW and CCW angle limits to %d and %d' %(min_angle, max_angle)) 00326 return response 00327 00328 def set_drive_mode(self, servo_id, is_slave=False, is_reverse=False): 00329 """ 00330 Sets the drive mode for EX-106 motors 00331 """ 00332 drive_mode = (is_slave << 1) + is_reverse 00333 00334 response = self.write(servo_id, DXL_DRIVE_MODE, [drive_mode]) 00335 if response: 00336 self.exception_on_error(response[4], servo_id, 'setting drive mode to %d' % drive_mode) 00337 return response 00338 00339 def set_voltage_limit_min(self, servo_id, min_voltage): 00340 """ 00341 Set the minimum voltage limit. 00342 NOTE: the absolute min is 5v 00343 """ 00344 00345 if min_voltage < 5: min_voltage = 5 00346 minVal = int(min_voltage * 10) 00347 00348 response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, [minVal]) 00349 if response: 00350 self.exception_on_error(response[4], servo_id, 'setting minimum voltage level to %d' % min_voltage) 00351 return response 00352 00353 def set_voltage_limit_max(self, servo_id, max_voltage): 00354 """ 00355 Set the maximum voltage limit. 00356 NOTE: the absolute min is 25v 00357 """ 00358 00359 if max_voltage > 25: max_voltage = 25 00360 maxVal = int(max_voltage * 10) 00361 00362 response = self.write(servo_id, DXL_UP_LIMIT_VOLTAGE, [maxVal]) 00363 if response: 00364 self.exception_on_error(response[4], servo_id, 'setting maximum voltage level to %d' % max_voltage) 00365 return response 00366 00367 def set_voltage_limits(self, servo_id, min_voltage, max_voltage): 00368 """ 00369 Set the min and max voltage limits. 00370 NOTE: the absolute min is 5v and the absolute max is 25v 00371 """ 00372 00373 if min_voltage < 5: min_voltage = 5 00374 if max_voltage > 25: max_voltage = 25 00375 00376 minVal = int(min_voltage * 10) 00377 maxVal = int(max_voltage * 10) 00378 00379 response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, (minVal, maxVal)) 00380 if response: 00381 self.exception_on_error(response[4], servo_id, 'setting min and max voltage levels to %d and %d' %(min_voltage, max_voltage)) 00382 return response 00383 00384 00385 ############################################################### 00386 # These functions can send a single command to a single servo # 00387 ############################################################### 00388 00389 def set_torque_enabled(self, servo_id, enabled): 00390 """ 00391 Sets the value of the torque enabled register to 1 or 0. When the 00392 torque is disabled the servo can be moved manually while the motor is 00393 still powered. 00394 """ 00395 response = self.write(servo_id, DXL_TORQUE_ENABLE, [enabled]) 00396 if response: 00397 self.exception_on_error(response[4], servo_id, '%sabling torque' % 'en' if enabled else 'dis') 00398 return response 00399 00400 def set_compliance_margin_cw(self, servo_id, margin): 00401 """ 00402 The error between goal position and present position in CW direction. 00403 The range of the value is 0 to 255, and the unit is the same as Goal Position. 00404 The greater the value, the more difference occurs. 00405 """ 00406 response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, [margin]) 00407 if response: 00408 self.exception_on_error(response[4], servo_id, 'setting CW compliance margin to %d' % margin) 00409 return response 00410 00411 def set_compliance_margin_ccw(self, servo_id, margin): 00412 """ 00413 The error between goal position and present position in CCW direction. 00414 The range of the value is 0 to 255, and the unit is the same as Goal Position. 00415 The greater the value, the more difference occurs. 00416 """ 00417 response = self.write(servo_id, DXL_CCW_COMPLIANCE_MARGIN, [margin]) 00418 if response: 00419 self.exception_on_error(response[4], servo_id, 'setting CCW compliance margin to %d' % margin) 00420 return response 00421 00422 def set_compliance_margins(self, servo_id, margin_cw, margin_ccw): 00423 """ 00424 The error between goal position and present position in CCW direction. 00425 The range of the value is 0 to 255, and the unit is the same as Goal Position. 00426 The greater the value, the more difference occurs. 00427 """ 00428 response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, (margin_cw, margin_ccw)) 00429 if response: 00430 self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance margins to values %d and %d' %(margin_cw, margin_ccw)) 00431 return response 00432 00433 def set_compliance_slope_cw(self, servo_id, slope): 00434 """ 00435 Sets the level of Torque near the goal position in CW direction. 00436 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 00437 """ 00438 response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, [slope]) 00439 if response: 00440 self.exception_on_error(response[4], servo_id, 'setting CW compliance slope to %d' % slope) 00441 return response 00442 00443 def set_compliance_slope_ccw(self, servo_id, slope): 00444 """ 00445 Sets the level of Torque near the goal position in CCW direction. 00446 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 00447 """ 00448 response = self.write(servo_id, DXL_CCW_COMPLIANCE_SLOPE, [slope]) 00449 if response: 00450 self.exception_on_error(response[4], servo_id, 'setting CCW compliance slope to %d' % slope) 00451 return response 00452 00453 def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw): 00454 """ 00455 Sets the level of Torque near the goal position in CW/CCW direction. 00456 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 00457 """ 00458 response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, (slope_cw, slope_ccw)) 00459 if response: 00460 self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance slopes to %d and %d' %(slope_cw, slope_ccw)) 00461 return response 00462 00463 def set_d_gain(self, servo_id, d_gain): 00464 """ 00465 Sets the value of derivative action of PID controller. 00466 Gain value is in range 0 to 254. 00467 """ 00468 response = self.write(servo_id, DXL_D_GAIN, [d_gain]) 00469 if response: 00470 self.exception_on_error(response[4], servo_id, 'setting D gain value of PID controller to %d' % slope) 00471 return response 00472 00473 def set_i_gain(self, servo_id, i_gain): 00474 """ 00475 Sets the value of integral action of PID controller. 00476 Gain value is in range 0 to 254. 00477 """ 00478 response = self.write(servo_id, DXL_I_GAIN, [i_gain]) 00479 if response: 00480 self.exception_on_error(response[4], servo_id, 'setting I gain value of PID controller to %d' % slope) 00481 return response 00482 00483 def set_p_gain(self, servo_id, p_gain): 00484 """ 00485 Sets the value of proportional action of PID controller. 00486 Gain value is in range 0 to 254. 00487 """ 00488 response = self.write(servo_id, DXL_P_GAIN, [p_gain]) 00489 if response: 00490 self.exception_on_error(response[4], servo_id, 'setting P gain value of PID controller to %d' % slope) 00491 return response 00492 00493 def set_punch(self, servo_id, punch): 00494 """ 00495 Sets the limit value of torque being reduced when the output torque is 00496 decreased in the Compliance Slope area. In other words, it is the mimimum 00497 torque. The initial value is 32 (0x20) and can be extended up to 1023 00498 (0x3FF). (Refer to Compliance margin & Slope) 00499 """ 00500 loVal = int(punch % 256) 00501 hiVal = int(punch >> 8) 00502 response = self.write(servo_id, DXL_PUNCH_L, (loVal, hiVal)) 00503 if response: 00504 self.exception_on_error(response[4], servo_id, 'setting punch to %d' % punch) 00505 return response 00506 00507 def set_position(self, servo_id, position): 00508 """ 00509 Set the servo with servo_id to the specified goal position. 00510 Position value must be positive. 00511 """ 00512 loVal = int(position % 256) 00513 hiVal = int(position >> 8) 00514 00515 response = self.write(servo_id, DXL_GOAL_POSITION_L, (loVal, hiVal)) 00516 if response: 00517 self.exception_on_error(response[4], servo_id, 'setting goal position to %d' % position) 00518 return response 00519 00520 def set_speed(self, servo_id, speed): 00521 """ 00522 Set the servo with servo_id to the specified goal speed. 00523 Speed can be negative only if the dynamixel is in "freespin" mode. 00524 """ 00525 # split speed into 2 bytes 00526 if speed >= 0: 00527 loVal = int(speed % 256) 00528 hiVal = int(speed >> 8) 00529 else: 00530 loVal = int((1023 - speed) % 256) 00531 hiVal = int((1023 - speed) >> 8) 00532 00533 # set two register values with low and high byte for the speed 00534 response = self.write(servo_id, DXL_GOAL_SPEED_L, (loVal, hiVal)) 00535 if response: 00536 self.exception_on_error(response[4], servo_id, 'setting moving speed to %d' % speed) 00537 return response 00538 00539 def set_torque_limit(self, servo_id, torque): 00540 """ 00541 Sets the value of the maximum torque limit for servo with id servo_id. 00542 Valid values are 0 to 1023 (0x3FF), and the unit is about 0.1%. 00543 For example, if the value is 512 only 50% of the maximum torque will be used. 00544 If the power is turned on, the value of Max Torque (Address 14, 15) is used as the initial value. 00545 """ 00546 loVal = int(torque % 256) 00547 hiVal = int(torque >> 8) 00548 00549 response = self.write(servo_id, DXL_TORQUE_LIMIT_L, (loVal, hiVal)) 00550 if response: 00551 self.exception_on_error(response[4], servo_id, 'setting torque limit to %d' % torque) 00552 return response 00553 00554 def set_position_and_speed(self, servo_id, position, speed): 00555 """ 00556 Set the servo with servo_id to specified position and speed. 00557 Speed can be negative only if the dynamixel is in "freespin" mode. 00558 """ 00559 # split speed into 2 bytes 00560 if speed >= 0: 00561 loSpeedVal = int(speed % 256) 00562 hiSpeedVal = int(speed >> 8) 00563 else: 00564 loSpeedVal = int((1023 - speed) % 256) 00565 hiSpeedVal = int((1023 - speed) >> 8) 00566 00567 # split position into 2 bytes 00568 loPositionVal = int(position % 256) 00569 hiPositionVal = int(position >> 8) 00570 00571 response = self.write(servo_id, DXL_GOAL_POSITION_L, (loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal)) 00572 if response: 00573 self.exception_on_error(response[4], servo_id, 'setting goal position to %d and moving speed to %d' %(position, speed)) 00574 return response 00575 00576 00577 ################################################################# 00578 # These functions can send multiple commands to multiple servos # 00579 # These commands are used in ROS wrapper as they don't send a # 00580 # response packet, ROS wrapper gets motor states at a set rate # 00581 ################################################################# 00582 00583 def set_multi_torque_enabled(self, valueTuples): 00584 """ 00585 Method to set multiple servos torque enabled. 00586 Should be called as such: 00587 set_multi_servos_to_torque_enabled( (id1, True), (id2, True), (id3, True) ) 00588 """ 00589 # use sync write to broadcast multi servo message 00590 self.sync_write(DXL_TORQUE_ENABLE, tuple(valueTuples)) 00591 00592 def set_multi_compliance_margin_cw(self, valueTuples): 00593 """ 00594 Set different CW compliance margin for multiple servos. 00595 Should be called as such: 00596 set_multi_compliance_margin_cw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) ) 00597 """ 00598 self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples)) 00599 00600 def set_multi_compliance_margin_ccw(self, valueTuples): 00601 """ 00602 Set different CCW compliance margin for multiple servos. 00603 Should be called as such: 00604 set_multi_compliance_margin_ccw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) ) 00605 """ 00606 self.sync_write(DXL_CCW_COMPLIANCE_MARGIN, tuple(valueTuples)) 00607 00608 def set_multi_compliance_margins(self, valueTuples): 00609 """ 00610 Set different CW and CCW compliance margins for multiple servos. 00611 Should be called as such: 00612 set_multi_compliance_margins( ( (id1, cw_margin1, ccw_margin1), (id2, cw_margin2, ccw_margin2) ) ) 00613 """ 00614 self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples)) 00615 00616 def set_multi_compliance_slope_cw(self, valueTuples): 00617 """ 00618 Set different CW compliance slope for multiple servos. 00619 Should be called as such: 00620 set_multi_compliance_slope_cw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) ) 00621 """ 00622 self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples)) 00623 00624 def set_multi_compliance_slope_ccw(self, valueTuples): 00625 """ 00626 Set different CCW compliance slope for multiple servos. 00627 Should be called as such: 00628 set_multi_compliance_slope_ccw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) ) 00629 """ 00630 self.sync_write(DXL_CCW_COMPLIANCE_SLOPE, tuple(valueTuples)) 00631 00632 def set_multi_compliance_slopes(self, valueTuples): 00633 """ 00634 Set different CW and CCW compliance slopes for multiple servos. 00635 Should be called as such: 00636 set_multi_compliance_slopes( ( (id1, cw_slope1, ccw_slope1), (id2, cw_slope2, ccw_slope2) ) ) 00637 """ 00638 self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples)) 00639 00640 def set_multi_punch(self, valueTuples): 00641 """ 00642 Set different punch values for multiple servos. 00643 NOTE: according to documentation, currently this value is not being used. 00644 Should be called as such: 00645 set_multi_punch( ( (id1, punch1), (id2, punch2), (id3, punch3) ) ) 00646 """ 00647 # prepare value tuples for call to syncwrite 00648 writeableVals = [] 00649 00650 for sid,punch in valueTuples: 00651 # split punch into 2 bytes 00652 loVal = int(punch % 256) 00653 hiVal = int(punch >> 8) 00654 writeableVals.append( (sid, loVal, hiVal) ) 00655 00656 # use sync write to broadcast multi servo message 00657 self.sync_write(DXL_PUNCH_L, writeableVals) 00658 00659 def set_multi_position(self, valueTuples): 00660 """ 00661 Set different positions for multiple servos. 00662 Should be called as such: 00663 set_multi_position( ( (id1, position1), (id2, position2), (id3, position3) ) ) 00664 """ 00665 # prepare value tuples for call to syncwrite 00666 writeableVals = [] 00667 00668 for vals in valueTuples: 00669 sid = vals[0] 00670 position = vals[1] 00671 # split position into 2 bytes 00672 loVal = int(position % 256) 00673 hiVal = int(position >> 8) 00674 writeableVals.append( (sid, loVal, hiVal) ) 00675 00676 # use sync write to broadcast multi servo message 00677 self.sync_write(DXL_GOAL_POSITION_L, writeableVals) 00678 00679 def set_multi_speed(self, valueTuples): 00680 """ 00681 Set different speeds for multiple servos. 00682 Should be called as such: 00683 set_multi_speed( ( (id1, speed1), (id2, speed2), (id3, speed3) ) ) 00684 """ 00685 # prepare value tuples for call to syncwrite 00686 writeableVals = [] 00687 00688 for vals in valueTuples: 00689 sid = vals[0] 00690 speed = vals[1] 00691 00692 # split speed into 2 bytes 00693 if speed >= 0: 00694 loVal = int(speed % 256) 00695 hiVal = int(speed >> 8) 00696 else: 00697 loVal = int((1023 - speed) % 256) 00698 hiVal = int((1023 - speed) >> 8) 00699 00700 writeableVals.append( (sid, loVal, hiVal) ) 00701 00702 # use sync write to broadcast multi servo message 00703 self.sync_write(DXL_GOAL_SPEED_L, writeableVals) 00704 00705 def set_multi_torque_limit(self, valueTuples): 00706 """ 00707 Set different torque limits for multiple servos. 00708 Should be called as such: 00709 set_multi_torque_limit( ( (id1, torque1), (id2, torque2), (id3, torque3) ) ) 00710 """ 00711 # prepare value tuples for call to syncwrite 00712 writeableVals = [] 00713 00714 for sid,torque in valueTuples: 00715 # split torque into 2 bytes 00716 loVal = int(torque % 256) 00717 hiVal = int(torque >> 8) 00718 writeableVals.append( (sid, loVal, hiVal) ) 00719 00720 # use sync write to broadcast multi servo message 00721 self.sync_write(DXL_TORQUE_LIMIT_L, writeableVals) 00722 00723 def set_multi_position_and_speed(self, valueTuples): 00724 """ 00725 Set different positions and speeds for multiple servos. 00726 Should be called as such: 00727 set_multi_position_and_speed( ( (id1, position1, speed1), (id2, position2, speed2), (id3, position3, speed3) ) ) 00728 """ 00729 # prepare value tuples for call to syncwrite 00730 writeableVals = [] 00731 00732 for vals in valueTuples: 00733 sid = vals[0] 00734 position = vals[1] 00735 speed = vals[2] 00736 00737 # split speed into 2 bytes 00738 if speed >= 0: 00739 loSpeedVal = int(speed % 256) 00740 hiSpeedVal = int(speed >> 8) 00741 else: 00742 loSpeedVal = int((1023 - speed) % 256) 00743 hiSpeedVal = int((1023 - speed) >> 8) 00744 00745 # split position into 2 bytes 00746 loPositionVal = int(position % 256) 00747 hiPositionVal = int(position >> 8) 00748 writeableVals.append( (sid, loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal) ) 00749 00750 # use sync write to broadcast multi servo message 00751 self.sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals)) 00752 00753 00754 ################################# 00755 # Servo status access functions # 00756 ################################# 00757 00758 def get_model_number(self, servo_id): 00759 """ Reads the servo's model number (e.g. 12 for AX-12+). """ 00760 response = self.read(servo_id, DXL_MODEL_NUMBER_L, 2) 00761 if response: 00762 self.exception_on_error(response[4], servo_id, 'fetching model number') 00763 return response[5] + (response[6] << 8) 00764 00765 def get_firmware_version(self, servo_id): 00766 """ Reads the servo's firmware version. """ 00767 response = self.read(servo_id, DXL_VERSION, 1) 00768 if response: 00769 self.exception_on_error(response[4], servo_id, 'fetching firmware version') 00770 return response[5] 00771 00772 def get_return_delay_time(self, servo_id): 00773 """ Reads the servo's return delay time. """ 00774 response = self.read(servo_id, DXL_RETURN_DELAY_TIME, 1) 00775 if response: 00776 self.exception_on_error(response[4], servo_id, 'fetching return delay time') 00777 return response[5] 00778 00779 def get_angle_limits(self, servo_id): 00780 """ 00781 Returns the min and max angle limits from the specified servo. 00782 """ 00783 # read in 4 consecutive bytes starting with low value of clockwise angle limit 00784 response = self.read(servo_id, DXL_CW_ANGLE_LIMIT_L, 4) 00785 if response: 00786 self.exception_on_error(response[4], servo_id, 'fetching CW/CCW angle limits') 00787 # extract data valus from the raw data 00788 cwLimit = response[5] + (response[6] << 8) 00789 ccwLimit = response[7] + (response[8] << 8) 00790 00791 # return the data in a dictionary 00792 return {'min':cwLimit, 'max':ccwLimit} 00793 00794 def get_drive_mode(self, servo_id): 00795 """ Reads the servo's drive mode. """ 00796 response = self.read(servo_id, DXL_DRIVE_MODE, 1) 00797 if response: 00798 self.exception_on_error(response[4], servo_id, 'fetching drive mode') 00799 return response[5] 00800 00801 def get_voltage_limits(self, servo_id): 00802 """ 00803 Returns the min and max voltage limits from the specified servo. 00804 """ 00805 response = self.read(servo_id, DXL_DOWN_LIMIT_VOLTAGE, 2) 00806 if response: 00807 self.exception_on_error(response[4], servo_id, 'fetching voltage limits') 00808 # extract data valus from the raw data 00809 min_voltage = response[5] / 10.0 00810 max_voltage = response[6] / 10.0 00811 00812 # return the data in a dictionary 00813 return {'min':min_voltage, 'max':max_voltage} 00814 00815 def get_position(self, servo_id): 00816 """ Reads the servo's position value from its registers. """ 00817 response = self.read(servo_id, DXL_PRESENT_POSITION_L, 2) 00818 if response: 00819 self.exception_on_error(response[4], servo_id, 'fetching present position') 00820 position = response[5] + (response[6] << 8) 00821 return position 00822 00823 def get_speed(self, servo_id): 00824 """ Reads the servo's speed value from its registers. """ 00825 response = self.read(servo_id, DXL_PRESENT_SPEED_L, 2) 00826 if response: 00827 self.exception_on_error(response[4], servo_id, 'fetching present speed') 00828 speed = response[5] + (response[6] << 8) 00829 if speed > 1023: 00830 return 1023 - speed 00831 return speed 00832 00833 def get_voltage(self, servo_id): 00834 """ Reads the servo's voltage. """ 00835 response = self.read(servo_id, DXL_PRESENT_VOLTAGE, 1) 00836 if response: 00837 self.exception_on_error(response[4], servo_id, 'fetching supplied voltage') 00838 return response[5] / 10.0 00839 00840 def get_feedback(self, servo_id): 00841 """ 00842 Returns the id, goal, position, error, speed, load, voltage, temperature 00843 and moving values from the specified servo. 00844 """ 00845 # read in 17 consecutive bytes starting with low value for goal position 00846 response = self.read(servo_id, DXL_GOAL_POSITION_L, 17) 00847 00848 if response: 00849 self.exception_on_error(response[4], servo_id, 'fetching full servo status') 00850 if len(response) == 24: 00851 # extract data values from the raw data 00852 goal = response[5] + (response[6] << 8) 00853 position = response[11] + (response[12] << 8) 00854 error = position - goal 00855 speed = response[13] + ( response[14] << 8) 00856 if speed > 1023: speed = 1023 - speed 00857 load_raw = response[15] + (response[16] << 8) 00858 load_direction = 1 if self.test_bit(load_raw, 10) else 0 00859 load = (load_raw & int('1111111111', 2)) / 1024.0 00860 if load_direction == 1: load = -load 00861 voltage = response[17] / 10.0 00862 temperature = response[18] 00863 moving = response[21] 00864 timestamp = response[-1] 00865 00866 # return the data in a dictionary 00867 return { 'timestamp': timestamp, 00868 'id': servo_id, 00869 'goal': goal, 00870 'position': position, 00871 'error': error, 00872 'speed': speed, 00873 'load': load, 00874 'voltage': voltage, 00875 'temperature': temperature, 00876 'moving': bool(moving) } 00877 00878 def exception_on_error(self, error_code, servo_id, command_failed): 00879 global exception 00880 exception = None 00881 ex_message = '[servo #%d on %s@%sbps]: %s failed' % (servo_id, self.ser.port, self.ser.baudrate, command_failed) 00882 00883 if not error_code & DXL_OVERHEATING_ERROR == 0: 00884 msg = 'Overheating Error ' + ex_message 00885 exception = FatalErrorCodeError(msg, error_code) 00886 if not error_code & DXL_OVERLOAD_ERROR == 0: 00887 msg = 'Overload Error ' + ex_message 00888 exception = FatalErrorCodeError(msg, error_code) 00889 if not error_code & DXL_INPUT_VOLTAGE_ERROR == 0: 00890 msg = 'Input Voltage Error ' + ex_message 00891 exception = NonfatalErrorCodeError(msg, error_code) 00892 if not error_code & DXL_ANGLE_LIMIT_ERROR == 0: 00893 msg = 'Angle Limit Error ' + ex_message 00894 exception = NonfatalErrorCodeError(msg, error_code) 00895 if not error_code & DXL_RANGE_ERROR == 0: 00896 msg = 'Range Error ' + ex_message 00897 exception = NonfatalErrorCodeError(msg, error_code) 00898 if not error_code & DXL_CHECKSUM_ERROR == 0: 00899 msg = 'Checksum Error ' + ex_message 00900 exception = NonfatalErrorCodeError(msg, error_code) 00901 if not error_code & DXL_INSTRUCTION_ERROR == 0: 00902 msg = 'Instruction Error ' + ex_message 00903 exception = NonfatalErrorCodeError(msg, error_code) 00904 00905 class SerialOpenError(Exception): 00906 def __init__(self, port, baud): 00907 Exception.__init__(self) 00908 self.message = "Cannot open port '%s' at %d bps" %(port, baud) 00909 self.port = port 00910 self.baud = baud 00911 def __str__(self): 00912 return self.message 00913 00914 class ChecksumError(Exception): 00915 def __init__(self, servo_id, response, checksum): 00916 Exception.__init__(self) 00917 self.message = 'Checksum received from motor %d does not match the expected one (%d != %d)' \ 00918 %(servo_id, response[-1], checksum) 00919 self.response_data = response 00920 self.expected_checksum = checksum 00921 def __str__(self): 00922 return self.message 00923 00924 class FatalErrorCodeError(Exception): 00925 def __init__(self, message, ec_const): 00926 Exception.__init__(self) 00927 self.message = message 00928 self.error_code = ec_const 00929 def __str__(self): 00930 return self.message 00931 00932 class NonfatalErrorCodeError(Exception): 00933 def __init__(self, message, ec_const): 00934 Exception.__init__(self) 00935 self.message = message 00936 self.error_code = ec_const 00937 def __str__(self): 00938 return self.message 00939 00940 class ErrorCodeError(Exception): 00941 def __init__(self, message, ec_const): 00942 Exception.__init__(self) 00943 self.message = message 00944 self.error_code = ec_const 00945 def __str__(self): 00946 return self.message 00947 00948 class DroppedPacketError(Exception): 00949 def __init__(self, message): 00950 Exception.__init__(self) 00951 self.message = message 00952 def __str__(self): 00953 return self.message 00954