00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
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
00050 from dynamixel_const import *
00051 from dynamixel_ros_commands 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.ser = None
00066 self.ser = serial.Serial(port)
00067 self.ser.setTimeout(0.015)
00068 self.ser.baudrate = baudrate
00069 except SerialOpenError:
00070 raise SerialOpenError(port, baudrate)
00071
00072 def __del__(self):
00073 """ Destructor calls DynamixelIO.close """
00074 self.close()
00075
00076 def close(self):
00077 """
00078 Be nice, close the serial port.
00079 """
00080 if self.ser:
00081 self.ser.flushInput()
00082 self.ser.flushOutput()
00083 self.ser.close()
00084
00085 def __read_response(self, servo_id):
00086 data = []
00087
00088 try:
00089 data.extend(self.ser.read(4))
00090 if not data[0:2] == ['\xff', '\xff']: raise Exception('Wrong packet prefix %s' % data[0:2])
00091 data.extend(self.ser.read(ord(data[3])))
00092 data = array('B', ''.join(data)).tolist()
00093 except Exception, e:
00094 raise DroppedPacketError('Invalid response received from motor %d. %s' % (servo_id, e))
00095
00096
00097 checksum = 255 - sum(data[2:-1]) % 256
00098 if not checksum == data[-1]: raise ChecksumError(data, checksum)
00099
00100 return data
00101
00102 def read(self, servo_id, address, size):
00103 """ Read "size" bytes of data from servo with "servo_id" starting at the
00104 register with "address". "address" is an integer between 0 and 57. It is
00105 recommended to use the constants in module dynamixel_const for readability.
00106
00107 To read the position from servo with id 1, the method should be called
00108 like:
00109 read(1, DXL_GOAL_POSITION_L, 2)
00110 """
00111 self.ser.flushInput()
00112
00113
00114 length = 4
00115
00116
00117
00118
00119 checksum = 255 - ( (servo_id + length + DXL_READ_DATA + address + size) % 256 )
00120
00121
00122 packet = [0xFF, 0xFF, servo_id, length, DXL_READ_DATA, address, size, checksum]
00123 packetStr = array('B', packet).tostring()
00124 self.ser.write(packetStr)
00125
00126
00127 timestamp = time.time()
00128 time.sleep(0.0013)
00129
00130
00131 data = self.__read_response(servo_id)
00132 data.append(timestamp)
00133
00134 return data
00135
00136 def write(self, servo_id, address, data):
00137 """ Write the values from the "data" list to the servo with "servo_id"
00138 starting with data[0] at "address", continuing through data[n-1] at
00139 "address" + (n-1), where n = len(data). "address" is an integer between
00140 0 and 49. It is recommended to use the constants in module dynamixel_const
00141 for readability. "data" is a list/tuple of integers.
00142
00143 To set servo with id 1 to position 276, the method should be called
00144 like:
00145 write(1, DXL_GOAL_POSITION_L, (20, 1))
00146 """
00147 self.ser.flushInput()
00148
00149
00150 length = 3 + len(data)
00151
00152
00153
00154
00155 checksum = 255 - ((servo_id + length + DXL_WRITE_DATA + address + sum(data)) % 256)
00156
00157
00158 packet = [0xFF, 0xFF, servo_id, length, DXL_WRITE_DATA, address]
00159 packet.extend(data)
00160 packet.append(checksum)
00161
00162 packetStr = array('B', packet).tostring()
00163 self.ser.write(packetStr)
00164
00165
00166 timestamp = time.time()
00167 time.sleep(0.0013)
00168
00169
00170 data = self.__read_response(servo_id)
00171 data.append(timestamp)
00172
00173 return data
00174
00175 def sync_write(self, address, data):
00176 """ Use Broadcast message to send multiple servos instructions at the
00177 same time. No "status packet" will be returned from any servos.
00178 "address" is an integer between 0 and 49. It is recommended to use the
00179 constants in module dynamixel_const for readability. "data" is a tuple of
00180 tuples. Each tuple in "data" must contain the servo id followed by the
00181 data that should be written from the starting address. The amount of
00182 data can be as long as needed.
00183
00184 To set servo with id 1 to position 276 and servo with id 2 to position
00185 550, the method should be called like:
00186 sync_write(DXL_GOAL_POSITION_L, ( (1, 20, 1), (2 ,38, 2) ))
00187 """
00188 self.ser.flushInput()
00189
00190
00191 flattened = [value for servo in data for value in servo]
00192
00193
00194 length = 4 + len(flattened)
00195
00196 checksum = 255 - ((DXL_BROADCAST + length + \
00197 DXL_SYNC_WRITE + address + len(data[0][1:]) + \
00198 sum(flattened)) % 256)
00199
00200
00201 packet = [0xFF, 0xFF, DXL_BROADCAST, length, DXL_SYNC_WRITE, address, len(data[0][1:])]
00202 packet.extend(flattened)
00203 packet.append(checksum)
00204
00205 packetStr = array('B', packet).tostring()
00206 self.ser.write(packetStr)
00207
00208 def ping(self, servo_id):
00209 """ Ping the servo with "servo_id". This causes the servo to return a
00210 "status packet". This can tell us if the servo is attached and powered,
00211 and if so, if there are any errors.
00212 """
00213 self.ser.flushInput()
00214
00215
00216 length = 2
00217
00218
00219
00220
00221 checksum = 255 - ((servo_id + length + DXL_PING) % 256)
00222
00223
00224 packet = [0xFF, 0xFF, servo_id, length, DXL_PING, checksum]
00225 packetStr = array('B', packet).tostring()
00226 self.ser.write(packetStr)
00227
00228
00229 timestamp = time.time()
00230 time.sleep(0.0013)
00231
00232
00233 try:
00234 response = self.__read_response(servo_id)
00235 response.append(timestamp)
00236 except Exception, e:
00237 response = []
00238
00239 if response:
00240 self.exception_on_error(response[4], servo_id, 'ping')
00241 return response
00242
00243 def test_bit(self, number, offset):
00244 mask = 1 << offset
00245 return (number & mask)
00246
00247 def write_packet(self, packet):
00248 command = packet[0]
00249
00250 register = 0
00251 values = []
00252 two_byte_cmd = False
00253
00254 if command == DXL_SET_TORQUE_ENABLE:
00255 register = DXL_TORQUE_ENABLE
00256 elif command == DXL_SET_CW_COMPLIANCE_MARGIN:
00257 register = DXL_CW_COMPLIANCE_MARGIN
00258 elif command == DXL_SET_CCW_COMPLIANCE_MARGIN:
00259 register = DXL_CCW_COMPLIANCE_MARGIN
00260 elif command == DXL_SET_COMPLIANCE_MARGINS:
00261 two_byte_cmd = True
00262 register = DXL_CW_COMPLIANCE_MARGIN
00263 elif command == DXL_SET_CW_COMPLIANCE_SLOPE:
00264 register = DXL_CW_COMPLIANCE_SLOPE
00265 elif command == DXL_SET_CCW_COMPLIANCE_SLOPE:
00266 register = DXL_CCW_COMPLIANCE_SLOPE
00267 elif command == DXL_SET_COMPLIANCE_SLOPES:
00268 two_byte_cmd = True
00269 register = DXL_CW_COMPLIANCE_SLOPE
00270 elif command == DXL_SET_GOAL_POSITION:
00271 two_byte_cmd = True
00272 register = DXL_GOAL_POSITION_L
00273 elif command == DXL_SET_GOAL_SPEED:
00274 two_byte_cmd = True
00275 register = DXL_GOAL_SPEED_L
00276 elif command == DXL_SET_TORQUE_LIMIT:
00277 two_byte_cmd = True
00278 register = DXL_TORQUE_LIMIT_L
00279 elif command == DXL_SET_PUNCH:
00280 two_byte_cmd = True
00281 register = DXL_PUNCH_L
00282
00283 for val in packet[1]:
00284 motor_id = val[0]
00285 value = val[1]
00286 if two_byte_cmd:
00287 if value >= 0:
00288 loByte = int(value % 256)
00289 hiByte = int(value >> 8)
00290 else:
00291 loByte = int((1023 - value) % 256)
00292 hiByte = int((1023 - value) >> 8)
00293 values.append((motor_id, loByte, hiByte))
00294 else:
00295 values.append((motor_id, value))
00296 self.sync_write(register, tuple(values))
00297
00298
00299
00300
00301
00302
00303 def set_id(self, old_id, new_id):
00304 """
00305 Sets a new unique number to identify a motor. The range from 1 to 253
00306 (0xFD) can be used.
00307 """
00308 response = self.write(old_id, DXL_ID, [new_id])
00309 if response:
00310 self.exception_on_error(response[4], old_id, 'setting id to %d' % new_id)
00311 return response
00312
00313 def set_baud_rate(self, servo_id, baud_rate):
00314 """
00315 Sets servo communication speed. The range from 0 to 254.
00316 """
00317 response = self.write(servo_id, DXL_BAUD_RATE, [baud_rate])
00318 if response:
00319 self.exception_on_error(response[4], servo_id, 'setting baud rate to %d' % baud_rate)
00320 return response
00321
00322 def set_return_delay_time(self, servo_id, delay):
00323 """
00324 Sets the delay time from the transmission of Instruction Packet until
00325 the return of Status Packet. 0 to 254 (0xFE) can be used, and the delay
00326 time per data value is 2 usec.
00327 """
00328 response = self.write(servo_id, DXL_RETURN_DELAY_TIME, [delay])
00329 if response:
00330 self.exception_on_error(response[4], servo_id, 'setting return delay time to %d' % delay)
00331 return response
00332
00333 def set_angle_limit_cw(self, servo_id, angle_cw):
00334 """
00335 Set the min (CW) angle of rotation limit.
00336 """
00337 loVal = int(angle_cw % 256)
00338 hiVal = int(angle_cw >> 8)
00339
00340 response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loVal, hiVal))
00341 if response:
00342 self.exception_on_error(response[4], servo_id, 'setting CW angle limits to %d' % angle_cw)
00343 return response
00344
00345 def set_angle_limit_ccw(self, servo_id, angle_ccw):
00346 """
00347 Set the max (CCW) angle of rotation limit.
00348 """
00349 loVal = int(angle_ccw % 256)
00350 hiVal = int(angle_ccw >> 8)
00351
00352 response = self.write(servo_id, DXL_CCW_ANGLE_LIMIT_L, (loVal, hiVal))
00353 if response:
00354 self.exception_on_error(response[4], servo_id, 'setting CCW angle limits to %d' % angle_ccw)
00355 return response
00356
00357 def set_angle_limits(self, servo_id, min_angle, max_angle):
00358 """
00359 Set the min (CW) and max (CCW) angle of rotation limits.
00360 """
00361 loMinVal = int(min_angle % 256)
00362 hiMinVal = int(min_angle >> 8)
00363 loMaxVal = int(max_angle % 256)
00364 hiMaxVal = int(max_angle >> 8)
00365
00366
00367 response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loMinVal, hiMinVal, loMaxVal, hiMaxVal))
00368 if response:
00369 self.exception_on_error(response[4], servo_id, 'setting CW and CCW angle limits to %d and %d' %(min_angle, max_angle))
00370 return response
00371
00372 def set_voltage_limit_min(self, servo_id, min_voltage):
00373 """
00374 Set the minimum voltage limit.
00375 NOTE: the absolute min is 5v
00376 """
00377
00378 if min_voltage < 5: min_voltage = 5
00379 minVal = int(min_voltage * 10)
00380
00381 response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, [minVal])
00382 if response:
00383 self.exception_on_error(response[4], servo_id, 'setting minimum voltage level to %d' % min_voltage)
00384 return response
00385
00386 def set_voltage_limit_max(self, servo_id, max_voltage):
00387 """
00388 Set the maximum voltage limit.
00389 NOTE: the absolute min is 25v
00390 """
00391
00392 if max_voltage > 25: max_voltage = 25
00393 maxVal = int(max_voltage * 10)
00394
00395 response = self.write(servo_id, DXL_UP_LIMIT_VOLTAGE, [maxVal])
00396 if response:
00397 self.exception_on_error(response[4], servo_id, 'setting maximum voltage level to %d' % max_voltage)
00398 return response
00399
00400 def set_voltage_limits(self, servo_id, min_voltage, max_voltage):
00401 """
00402 Set the min and max voltage limits.
00403 NOTE: the absolute min is 5v and the absolute max is 25v
00404 """
00405
00406 if min_voltage < 5: min_voltage = 5
00407 if max_voltage > 25: max_voltage = 25
00408
00409 minVal = int(min_voltage * 10)
00410 maxVal = int(max_voltage * 10)
00411
00412 response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, (minVal, maxVal))
00413 if response:
00414 self.exception_on_error(response[4], servo_id, 'setting min and max voltage levels to %d and %d' %(min_voltage, max_voltage))
00415 return response
00416
00417
00418
00419
00420
00421
00422 def set_torque_enabled(self, servo_id, enabled):
00423 """
00424 Sets the value of the torque enabled register to 1 or 0. When the
00425 torque is disabled the servo can be moved manually while the motor is
00426 still powered.
00427 """
00428 response = self.write(servo_id, DXL_TORQUE_ENABLE, [enabled])
00429 if response:
00430 self.exception_on_error(response[4], servo_id, '%sabling torque' % 'en' if enabled else 'dis')
00431 return response
00432
00433 def set_compliance_margin_cw(self, servo_id, margin):
00434 """
00435 The error between goal position and present position in CW direction.
00436 The range of the value is 0 to 255, and the unit is the same as Goal Position.
00437 The greater the value, the more difference occurs.
00438 """
00439 response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, [margin])
00440 if response:
00441 self.exception_on_error(response[4], servo_id, 'setting CW compliance margin to %d' % margin)
00442 return response
00443
00444 def set_compliance_margin_ccw(self, servo_id, margin):
00445 """
00446 The error between goal position and present position in CCW direction.
00447 The range of the value is 0 to 255, and the unit is the same as Goal Position.
00448 The greater the value, the more difference occurs.
00449 """
00450 response = self.write(servo_id, DXL_CCW_COMPLIANCE_MARGIN, [margin])
00451 if response:
00452 self.exception_on_error(response[4], servo_id, 'setting CCW compliance margin to %d' % margin)
00453 return response
00454
00455 def set_compliance_margins(self, servo_id, margin_cw, margin_ccw):
00456 """
00457 The error between goal position and present position in CCW direction.
00458 The range of the value is 0 to 255, and the unit is the same as Goal Position.
00459 The greater the value, the more difference occurs.
00460 """
00461 response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, (margin_cw, margin_ccw))
00462 if response:
00463 self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance margins to values %d and %d' %(margin_cw, margin_ccw))
00464 return response
00465
00466 def set_compliance_slope_cw(self, servo_id, slope):
00467 """
00468 Sets the level of Torque near the goal position in CW direction.
00469 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00470 """
00471 response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, [slope])
00472 if response:
00473 self.exception_on_error(response[4], servo_id, 'setting CW compliance slope to %d' % slope)
00474 return response
00475
00476 def set_compliance_slope_ccw(self, servo_id, slope):
00477 """
00478 Sets the level of Torque near the goal position in CCW direction.
00479 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00480 """
00481 response = self.write(servo_id, DXL_CCW_COMPLIANCE_SLOPE, [slope])
00482 if response:
00483 self.exception_on_error(response[4], servo_id, 'setting CCW compliance slope to %d' % slope)
00484 return response
00485
00486 def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw):
00487 """
00488 Sets the level of Torque near the goal position in CW/CCW direction.
00489 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained.
00490 """
00491 response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, (slope_cw, slope_ccw))
00492 if response:
00493 self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance slopes to %d and %d' %(slope_cw, slope_ccw))
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_position(self, servo_id, position):
00511 """
00512 Set the servo with servo_id to the specified goal position.
00513 Position value must be positive.
00514 """
00515 loVal = int(position % 256)
00516 hiVal = int(position >> 8)
00517
00518 response = self.write(servo_id, DXL_GOAL_POSITION_L, (loVal, hiVal))
00519 if response:
00520 self.exception_on_error(response[4], servo_id, 'setting goal position to %d' % position)
00521 return response
00522
00523 def set_speed(self, servo_id, speed):
00524 """
00525 Set the servo with servo_id to the specified goal speed.
00526 Speed can be negative only if the dynamixel is in "freespin" mode.
00527 """
00528
00529 if speed >= 0:
00530 loVal = int(speed % 256)
00531 hiVal = int(speed >> 8)
00532 else:
00533 loVal = int((1023 - speed) % 256)
00534 hiVal = int((1023 - speed) >> 8)
00535
00536
00537 response = self.write(servo_id, DXL_GOAL_SPEED_L, (loVal, hiVal))
00538 if response:
00539 self.exception_on_error(response[4], servo_id, 'setting moving speed to %d' % speed)
00540 return response
00541
00542 def set_torque_limit(self, servo_id, torque):
00543 """
00544 Sets the value of the maximum torque limit for servo with id servo_id.
00545 Valid values are 0 to 1023 (0x3FF), and the unit is about 0.1%.
00546 For example, if the value is 512 only 50% of the maximum torque will be used.
00547 If the power is turned on, the value of Max Torque (Address 14, 15) is used as the initial value.
00548 """
00549 loVal = int(torque % 256)
00550 hiVal = int(torque >> 8)
00551
00552 response = self.write(servo_id, DXL_TORQUE_LIMIT_L, (loVal, hiVal))
00553 if response:
00554 self.exception_on_error(response[4], servo_id, 'setting torque limit to %d' % torque)
00555 return response
00556
00557 def set_position_and_speed(self, servo_id, position, speed):
00558 """
00559 Set the servo with servo_id to specified position and speed.
00560 Speed can be negative only if the dynamixel is in "freespin" mode.
00561 """
00562
00563 if speed >= 0:
00564 loSpeedVal = int(speed % 256)
00565 hiSpeedVal = int(speed >> 8)
00566 else:
00567 loSpeedVal = int((1023 - speed) % 256)
00568 hiSpeedVal = int((1023 - speed) >> 8)
00569
00570
00571 loPositionVal = int(position % 256)
00572 hiPositionVal = int(position >> 8)
00573
00574 response = self.write(servo_id, DXL_GOAL_POSITION_L, (loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal))
00575 if response:
00576 self.exception_on_error(response[4], servo_id, 'setting goal position to %d and moving speed to %d' %(position, speed))
00577 return response
00578
00579
00580
00581
00582
00583
00584 def set_multi_servo_speeds(self, valueTuples):
00585 """
00586 Set different speeds for multiple servos.
00587 Should be called as such:
00588 set_multi_servo_speeds( ( (id1, speed1), (id2, speed2), (id3, speed3) ) )
00589 """
00590
00591 writeableVals = []
00592
00593 for vals in valueTuples:
00594 sid = vals[0]
00595 speed = vals[1]
00596
00597
00598 if speed >= 0:
00599 loVal = int(speed % 256)
00600 hiVal = int(speed >> 8)
00601 else:
00602 loVal = int((1023 - speed) % 256)
00603 hiVal = int((1023 - speed) >> 8)
00604
00605 writeableVals.append( (sid, loVal, hiVal) )
00606
00607
00608 self.sync_write(DXL_GOAL_SPEED_L, tuple(writeableVals))
00609
00610 def set_multi_servo_positions(self, valueTuples):
00611 """
00612 Set different positions for multiple servos.
00613 Should be called as such:
00614 set_multi_servo_positions( ( (id1, position1), (id2, position2), (id3, position3) ) )
00615 """
00616
00617 writeableVals = []
00618
00619 for vals in valueTuples:
00620 sid = vals[0]
00621 position = vals[1]
00622
00623 loVal = int(position % 256)
00624 hiVal = int(position >> 8)
00625 writeableVals.append( (sid, loVal, hiVal) )
00626
00627
00628 self.sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals))
00629
00630 def set_multi_servo_positions_and_speeds(self, valueTuples):
00631 """
00632 Set different positions and speeds for multiple servos.
00633 Should be called as such:
00634 set_multi_servo_speeds( ( (id1, position1, speed1), (id2, position2, speed2), (id3, position3, speed3) ) )
00635 """
00636
00637 writeableVals = []
00638
00639 for vals in valueTuples:
00640 sid = vals[0]
00641 position = vals[1]
00642 speed = vals[2]
00643
00644
00645 if speed >= 0:
00646 loSpeedVal = int(speed % 256)
00647 hiSpeedVal = int(speed >> 8)
00648 else:
00649 loSpeedVal = int((1023 - speed) % 256)
00650 hiSpeedVal = int((1023 - speed) >> 8)
00651
00652
00653 loPositionVal = int(position % 256)
00654 hiPositionVal = int(position >> 8)
00655 writeableVals.append( (sid, loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal) )
00656
00657
00658 self.sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals))
00659
00660 def set_multi_servos_to_torque_enabled(self, servo_ids, enabled):
00661 """
00662 Method to set multiple servos torque enabled.
00663 Should be called as such:
00664 set_multi_servos_to_torque_enabled( (id1, id2, id3), True)
00665 """
00666
00667 writeableVals = [(sid, enabled) for sid in servo_ids]
00668
00669
00670 self.sync_write(DXL_TORQUE_ENABLE, tuple(writeableVals))
00671
00672
00673
00674
00675
00676
00677 def get_model_number(self, servo_id):
00678 """ Reads the servo's model number (e.g. 12 for AX-12+). """
00679 response = self.read(servo_id, DXL_MODEL_NUMBER_L, 2)
00680 if response:
00681 self.exception_on_error(response[4], servo_id, 'fetching model number')
00682 return response[5] + (response[6] << 8)
00683
00684 def get_firmware_version(self, servo_id):
00685 """ Reads the servo's firmware version. """
00686 response = self.read(servo_id, DXL_VERSION, 1)
00687 if response:
00688 self.exception_on_error(response[4], servo_id, 'fetching firmware version')
00689 return response[5]
00690
00691 def get_return_delay_time(self, servo_id):
00692 """ Reads the servo's return delay time. """
00693 response = self.read(servo_id, DXL_RETURN_DELAY_TIME, 1)
00694 if response:
00695 self.exception_on_error(response[4], servo_id, 'fetching return delay time')
00696 return response[5]
00697
00698 def get_angle_limits(self, servo_id):
00699 """
00700 Returns the min and max angle limits from the specified servo.
00701 """
00702
00703 response = self.read(servo_id, DXL_CW_ANGLE_LIMIT_L, 4)
00704 if response:
00705 self.exception_on_error(response[4], servo_id, 'fetching CW/CCW angle limits')
00706
00707 cwLimit = response[5] + (response[6] << 8)
00708 ccwLimit = response[7] + (response[8] << 8)
00709
00710
00711 return {'min':cwLimit, 'max':ccwLimit}
00712
00713 def get_position(self, servo_id):
00714 """ Reads the servo's position value from its registers. """
00715 response = self.read(servo_id, DXL_PRESENT_POSITION_L, 2)
00716 if response:
00717 self.exception_on_error(response[4], servo_id, 'fetching present position')
00718 position = response[5] + (response[6] << 8)
00719 return position
00720
00721 def get_speed(self, servo_id):
00722 """ Reads the servo's speed value from its registers. """
00723 response = self.read(servo_id, DXL_PRESENT_SPEED_L, 2)
00724 if response:
00725 self.exception_on_error(response[4], servo_id, 'fetching present speed')
00726 speed = response[5] + (response[6] << 8)
00727 if speed > 1023:
00728 return 1023 - speed
00729 return speed
00730
00731 def get_voltage(self, servo_id):
00732 """ Reads the servo's voltage. """
00733 response = self.read(servo_id, DXL_PRESENT_VOLTAGE, 1)
00734 if response:
00735 self.exception_on_error(response[4], servo_id, 'fetching supplied voltage')
00736 return response[5] / 10.0
00737
00738 def get_feedback(self, servo_id):
00739 """
00740 Returns the id, goal, position, error, speed, load, voltage, temperature
00741 and moving values from the specified servo.
00742 """
00743
00744 response = self.read(servo_id, DXL_GOAL_POSITION_L, 17)
00745
00746 if response:
00747 self.exception_on_error(response[4], servo_id, 'fetching full servo status')
00748 if len(response) == 24:
00749
00750 goal = response[5] + (response[6] << 8)
00751 position = response[11] + (response[12] << 8)
00752 error = position - goal
00753 speed = response[13] + ( response[14] << 8)
00754 if speed > 1023: speed = 1023 - speed
00755 load_raw = response[15] + (response[16] << 8)
00756 load_direction = 1 if self.test_bit(load_raw, 10) else 0
00757 load = (load_raw & int('1111111111', 2)) / 1024.0
00758 if load_direction == 1: load = -load
00759 voltage = response[17] / 10.0
00760 temperature = response[18]
00761 moving = response[21]
00762 timestamp = response[-1]
00763
00764
00765 return { 'timestamp': timestamp,
00766 'id': servo_id,
00767 'goal': goal,
00768 'position': position,
00769 'error': error,
00770 'speed': speed,
00771 'load': load,
00772 'voltage': voltage,
00773 'temperature': temperature,
00774 'moving': bool(moving) }
00775
00776 def exception_on_error(self, error_code, servo_id, command_failed):
00777 global exception
00778 exception = None
00779 ex_message = '[servo #%d on %s@%sbps]: %s failed' % (servo_id, self.ser.port, self.ser.baudrate, command_failed)
00780
00781 if not error_code & DXL_OVERHEATING_ERROR == 0:
00782 msg = 'Overheating Error ' + ex_message
00783 exception = FatalErrorCodeError(msg, error_code)
00784 if not error_code & DXL_OVERLOAD_ERROR == 0:
00785 msg = 'Overload Error ' + ex_message
00786 exception = FatalErrorCodeError(msg, error_code)
00787 if not error_code & DXL_INPUT_VOLTAGE_ERROR == 0:
00788 msg = 'Input Voltage Error ' + ex_message
00789 exception = NonfatalErrorCodeError(msg, error_code)
00790 if not error_code & DXL_ANGLE_LIMIT_ERROR == 0:
00791 msg = 'Angle Limit Error ' + ex_message
00792 exception = NonfatalErrorCodeError(msg, error_code)
00793 if not error_code & DXL_RANGE_ERROR == 0:
00794 msg = 'Range Error ' + ex_message
00795 exception = NonfatalErrorCodeError(msg, error_code)
00796 if not error_code & DXL_CHECKSUM_ERROR == 0:
00797 msg = 'Checksum Error ' + ex_message
00798 exception = NonfatalErrorCodeError(msg, error_code)
00799 if not error_code & DXL_INSTRUCTION_ERROR == 0:
00800 msg = 'Instruction Error ' + ex_message
00801 exception = NonfatalErrorCodeError(msg, error_code)
00802
00803 class SerialOpenError(Exception):
00804 def __init__(self, port, baud):
00805 Exception.__init__(self)
00806 self.message = "Cannot open port '%s' at %d bps" %(port, baud)
00807 self.port = port
00808 self.baud = baud
00809 def __str__(self):
00810 return self.message
00811
00812 class ChecksumError(Exception):
00813 def __init__(self, response, checksum):
00814 Exception.__init__(self)
00815 self.message = 'Checksum of %d does not match the checksum from servo of %d' \
00816 %(response[-1], checksum)
00817 self.response_data = response
00818 self.expected_checksum = checksum
00819 def __str__(self):
00820 return self.message
00821
00822 class FatalErrorCodeError(Exception):
00823 def __init__(self, message, ec_const):
00824 Exception.__init__(self)
00825 self.message = message
00826 self.error_code = ec_const
00827 def __str__(self):
00828 return self.message
00829
00830 class NonfatalErrorCodeError(Exception):
00831 def __init__(self, message, ec_const):
00832 Exception.__init__(self)
00833 self.message = message
00834 self.error_code = ec_const
00835 def __str__(self):
00836 return self.message
00837
00838 class ErrorCodeError(Exception):
00839 def __init__(self, message, ec_const):
00840 Exception.__init__(self)
00841 self.message = message
00842 self.error_code = ec_const
00843 def __str__(self):
00844 return self.message
00845
00846 class DroppedPacketError(Exception):
00847 def __init__(self, message):
00848 Exception.__init__(self)
00849 self.message = message
00850 def __str__(self):
00851 return self.message
00852