37 __author__ =
'Cody Jorgensen, Antons Rebguns' 38 __copyright__ =
'Copyright (c) 2010-2011 Cody Jorgensen, Antons Rebguns' 41 __maintainer__ =
'Antons Rebguns' 42 __email__ =
'anton@email.arizona.edu' 47 from array
import array
48 from binascii
import b2a_hex
49 from threading
import Lock
51 from dynamixel_const
import *
56 """ Provides low level IO with the Dynamixel servos through pyserial. Has the 57 ability to write instruction packets, request and read register value 58 packets, send and receive a response to a ping packet, and send a SYNC WRITE 59 multi-servo instruction packet. 62 def __init__(self, port, baudrate, readback_echo=False):
63 """ Constructor takes serial port and baudrate as arguments. """ 67 self.
ser = serial.Serial(port, baudrate, timeout=0.015)
70 except SerialOpenError:
74 """ Destructor calls DynamixelIO.close """ 79 Be nice, close the serial port. 83 self.ser.flushOutput()
88 self.ser.flushOutput()
91 self.ser.read(len(data))
97 data.extend(self.ser.read(4))
98 if not data[0:2] == [
'\xff',
'\xff']:
raise Exception(
'Wrong packet prefix %s' % data[0:2])
99 data.extend(self.ser.read(ord(data[3])))
100 data = array(
'B',
''.join(data)).tolist()
102 raise DroppedPacketError(
'Invalid response received from motor %d. %s' % (servo_id, e))
105 checksum = 255 - sum(data[2:-1]) % 256
106 if not checksum == data[-1]:
raise ChecksumError(servo_id, data, checksum)
110 def read(self, servo_id, address, size):
111 """ Read "size" bytes of data from servo with "servo_id" starting at the 112 register with "address". "address" is an integer between 0 and 57. It is 113 recommended to use the constants in module dynamixel_const for readability. 115 To read the position from servo with id 1, the method should be called 117 read(1, DXL_GOAL_POSITION_L, 2) 125 checksum = 255 - ( (servo_id + length + DXL_READ_DATA + address + size) % 256 )
128 packet = [0xFF, 0xFF, servo_id, length, DXL_READ_DATA, address, size, checksum]
129 packetStr = array(
'B', packet).tostring()
135 timestamp = time.time()
140 data.append(timestamp)
144 def write(self, servo_id, address, data):
145 """ Write the values from the "data" list to the servo with "servo_id" 146 starting with data[0] at "address", continuing through data[n-1] at 147 "address" + (n-1), where n = len(data). "address" is an integer between 148 0 and 49. It is recommended to use the constants in module dynamixel_const 149 for readability. "data" is a list/tuple of integers. 151 To set servo with id 1 to position 276, the method should be called 153 write(1, DXL_GOAL_POSITION_L, (20, 1)) 156 length = 3 + len(data)
161 checksum = 255 - ((servo_id + length + DXL_WRITE_DATA + address + sum(data)) % 256)
164 packet = [0xFF, 0xFF, servo_id, length, DXL_WRITE_DATA, address]
166 packet.append(checksum)
168 packetStr = array(
'B', packet).tostring()
174 timestamp = time.time()
179 data.append(timestamp)
184 """ Use Broadcast message to send multiple servos instructions at the 185 same time. No "status packet" will be returned from any servos. 186 "address" is an integer between 0 and 49. It is recommended to use the 187 constants in module dynamixel_const for readability. "data" is a tuple of 188 tuples. Each tuple in "data" must contain the servo id followed by the 189 data that should be written from the starting address. The amount of 190 data can be as long as needed. 192 To set servo with id 1 to position 276 and servo with id 2 to position 193 550, the method should be called like: 194 sync_write(DXL_GOAL_POSITION_L, ( (1, 20, 1), (2 ,38, 2) )) 197 flattened = [value
for servo
in data
for value
in servo]
200 length = 4 + len(flattened)
202 checksum = 255 - ((DXL_BROADCAST + length + \
203 DXL_SYNC_WRITE + address + len(data[0][1:]) + \
204 sum(flattened)) % 256)
207 packet = [0xFF, 0xFF, DXL_BROADCAST, length, DXL_SYNC_WRITE, address, len(data[0][1:])]
208 packet.extend(flattened)
209 packet.append(checksum)
211 packetStr = array(
'B', packet).tostring()
217 """ Ping the servo with "servo_id". This causes the servo to return a 218 "status packet". This can tell us if the servo is attached and powered, 219 and if so, if there are any errors. 227 checksum = 255 - ((servo_id + length + DXL_PING) % 256)
230 packet = [0xFF, 0xFF, servo_id, length, DXL_PING, checksum]
231 packetStr = array(
'B', packet).tostring()
237 timestamp = time.time()
243 response.append(timestamp)
253 return (number & mask)
262 Sets a new unique number to identify a motor. The range from 1 to 253 265 response = self.
write(old_id, DXL_ID, [new_id])
272 Sets servo communication speed. The range from 0 to 254. 274 response = self.
write(servo_id, DXL_BAUD_RATE, [baud_rate])
281 Sets the delay time from the transmission of Instruction Packet until 282 the return of Status Packet. 0 to 254 (0xFE) can be used, and the delay 283 time per data value is 2 usec. 285 response = self.
write(servo_id, DXL_RETURN_DELAY_TIME, [delay])
287 self.
exception_on_error(response[4], servo_id,
'setting return delay time to %d' % delay)
292 Set the min (CW) angle of rotation limit. 294 loVal = int(angle_cw % 256)
295 hiVal = int(angle_cw >> 8)
297 response = self.
write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loVal, hiVal))
299 self.
exception_on_error(response[4], servo_id,
'setting CW angle limits to %d' % angle_cw)
304 Set the max (CCW) angle of rotation limit. 306 loVal = int(angle_ccw % 256)
307 hiVal = int(angle_ccw >> 8)
309 response = self.
write(servo_id, DXL_CCW_ANGLE_LIMIT_L, (loVal, hiVal))
311 self.
exception_on_error(response[4], servo_id,
'setting CCW angle limits to %d' % angle_ccw)
316 Set the min (CW) and max (CCW) angle of rotation limits. 318 loMinVal = int(min_angle % 256)
319 hiMinVal = int(min_angle >> 8)
320 loMaxVal = int(max_angle % 256)
321 hiMaxVal = int(max_angle >> 8)
324 response = self.
write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loMinVal, hiMinVal, loMaxVal, hiMaxVal))
326 self.
exception_on_error(response[4], servo_id,
'setting CW and CCW angle limits to %d and %d' %(min_angle, max_angle))
331 Sets the drive mode for EX-106 motors 333 drive_mode = (is_slave << 1) + is_reverse
335 response = self.
write(servo_id, DXL_DRIVE_MODE, [drive_mode])
337 self.
exception_on_error(response[4], servo_id,
'setting drive mode to %d' % drive_mode)
342 Set the minimum voltage limit. 343 NOTE: the absolute min is 5v 346 if min_voltage < 5: min_voltage = 5
347 minVal = int(min_voltage * 10)
349 response = self.
write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, [minVal])
351 self.
exception_on_error(response[4], servo_id,
'setting minimum voltage level to %d' % min_voltage)
356 Set the maximum voltage limit. 357 NOTE: the absolute min is 25v 360 if max_voltage > 25: max_voltage = 25
361 maxVal = int(max_voltage * 10)
363 response = self.
write(servo_id, DXL_UP_LIMIT_VOLTAGE, [maxVal])
365 self.
exception_on_error(response[4], servo_id,
'setting maximum voltage level to %d' % max_voltage)
370 Set the min and max voltage limits. 371 NOTE: the absolute min is 5v and the absolute max is 25v 374 if min_voltage < 5: min_voltage = 5
375 if max_voltage > 25: max_voltage = 25
377 minVal = int(min_voltage * 10)
378 maxVal = int(max_voltage * 10)
380 response = self.
write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, (minVal, maxVal))
382 self.
exception_on_error(response[4], servo_id,
'setting min and max voltage levels to %d and %d' %(min_voltage, max_voltage))
392 Sets the value of the torque enabled register to 1 or 0. When the 393 torque is disabled the servo can be moved manually while the motor is 396 response = self.
write(servo_id, DXL_TORQUE_ENABLE, [enabled])
398 self.
exception_on_error(response[4], servo_id,
'%sabling torque' %
'en' if enabled
else 'dis')
403 The error between goal position and present position in CW direction. 404 The range of the value is 0 to 255, and the unit is the same as Goal Position. 405 The greater the value, the more difference occurs. 407 response = self.
write(servo_id, DXL_CW_COMPLIANCE_MARGIN, [margin])
409 self.
exception_on_error(response[4], servo_id,
'setting CW compliance margin to %d' % margin)
414 The error between goal position and present position in CCW direction. 415 The range of the value is 0 to 255, and the unit is the same as Goal Position. 416 The greater the value, the more difference occurs. 418 response = self.
write(servo_id, DXL_CCW_COMPLIANCE_MARGIN, [margin])
420 self.
exception_on_error(response[4], servo_id,
'setting CCW compliance margin to %d' % margin)
425 The error between goal position and present position in CCW direction. 426 The range of the value is 0 to 255, and the unit is the same as Goal Position. 427 The greater the value, the more difference occurs. 429 response = self.
write(servo_id, DXL_CW_COMPLIANCE_MARGIN, (margin_cw, margin_ccw))
431 self.
exception_on_error(response[4], servo_id,
'setting CW and CCW compliance margins to values %d and %d' %(margin_cw, margin_ccw))
436 Sets the level of Torque near the goal position in CW direction. 437 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 439 response = self.
write(servo_id, DXL_CW_COMPLIANCE_SLOPE, [slope])
441 self.
exception_on_error(response[4], servo_id,
'setting CW compliance slope to %d' % slope)
446 Sets the level of Torque near the goal position in CCW direction. 447 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 449 response = self.
write(servo_id, DXL_CCW_COMPLIANCE_SLOPE, [slope])
451 self.
exception_on_error(response[4], servo_id,
'setting CCW compliance slope to %d' % slope)
456 Sets the level of Torque near the goal position in CW/CCW direction. 457 Compliance Slope is set in 7 steps, the higher the value, the more flexibility is obtained. 459 response = self.
write(servo_id, DXL_CW_COMPLIANCE_SLOPE, (slope_cw, slope_ccw))
461 self.
exception_on_error(response[4], servo_id,
'setting CW and CCW compliance slopes to %d and %d' %(slope_cw, slope_ccw))
466 Sets the value of derivative action of PID controller. 467 Gain value is in range 0 to 254. 469 response = self.
write(servo_id, DXL_D_GAIN, [d_gain])
471 self.
exception_on_error(response[4], servo_id,
'setting D gain value of PID controller to %d' % d_gain)
476 Sets the value of integral action of PID controller. 477 Gain value is in range 0 to 254. 479 response = self.
write(servo_id, DXL_I_GAIN, [i_gain])
481 self.
exception_on_error(response[4], servo_id,
'setting I gain value of PID controller to %d' % i_gain)
486 Sets the value of proportional action of PID controller. 487 Gain value is in range 0 to 254. 489 response = self.
write(servo_id, DXL_P_GAIN, [p_gain])
491 self.
exception_on_error(response[4], servo_id,
'setting P gain value of PID controller to %d' % p_gain)
496 Sets the limit value of torque being reduced when the output torque is 497 decreased in the Compliance Slope area. In other words, it is the mimimum 498 torque. The initial value is 32 (0x20) and can be extended up to 1023 499 (0x3FF). (Refer to Compliance margin & Slope) 501 loVal = int(punch % 256)
502 hiVal = int(punch >> 8)
503 response = self.
write(servo_id, DXL_PUNCH_L, (loVal, hiVal))
510 Sets the acceleration. The unit is 8.583 Degree / sec^2. 511 0 - acceleration control disabled, 1-254 - valid range for acceleration. 515 if not model
in DXL_MODEL_TO_PARAMS:
518 if DXL_GOAL_ACCELERATION
in DXL_MODEL_TO_PARAMS[model][
'features']:
519 response = self.
write(servo_id, DXL_GOAL_ACCELERATION, (acceleration, ))
521 self.
exception_on_error(response[4], servo_id,
'setting acceleration to %d' % acceleration)
528 Set the servo with servo_id to the specified goal position. 529 Position value must be positive. 531 loVal = int(position % 256)
532 hiVal = int(position >> 8)
534 response = self.
write(servo_id, DXL_GOAL_POSITION_L, (loVal, hiVal))
536 self.
exception_on_error(response[4], servo_id,
'setting goal position to %d' % position)
541 Set the servo with servo_id to the specified goal speed. 542 Speed can be negative only if the dynamixel is in "freespin" mode. 546 loVal = int(speed % 256)
547 hiVal = int(speed >> 8)
549 loVal = int((1023 - speed) % 256)
550 hiVal = int((1023 - speed) >> 8)
553 response = self.
write(servo_id, DXL_GOAL_SPEED_L, (loVal, hiVal))
560 Sets the value of the maximum torque limit for servo with id servo_id. 561 Valid values are 0 to 1023 (0x3FF), and the unit is about 0.1%. 562 For example, if the value is 512 only 50% of the maximum torque will be used. 563 If the power is turned on, the value of Max Torque (Address 14, 15) is used as the initial value. 565 loVal = int(torque % 256)
566 hiVal = int(torque >> 8)
568 response = self.
write(servo_id, DXL_TORQUE_LIMIT_L, (loVal, hiVal))
575 Set the servo to torque control mode (similar to wheel mode, but controlling the torque) 576 Valid values are from -1023 to 1023. 577 Anything outside this range or 'None' disables torque control. 581 if not model
in DXL_MODEL_TO_PARAMS:
584 valid_torque = torque
is not None and torque >= -1023
and torque <= 1023
585 if torque
is not None and torque < 0:
586 torque = 1024 - torque
588 if DXL_TORQUE_CONTROL_MODE
in DXL_MODEL_TO_PARAMS[model][
'features']:
590 loVal = int(torque % 256); hiVal = int(torque >> 8);
591 response = self.
write(servo_id, DXL_GOAL_TORQUE_L, (loVal, hiVal))
594 response = self.
write(servo_id, DXL_TORQUE_CONTROL_MODE, (int(valid_torque), ))
603 Set the servo with servo_id to specified position and speed. 604 Speed can be negative only if the dynamixel is in "freespin" mode. 608 loSpeedVal = int(speed % 256)
609 hiSpeedVal = int(speed >> 8)
611 loSpeedVal = int((1023 - speed) % 256)
612 hiSpeedVal = int((1023 - speed) >> 8)
615 loPositionVal = int(position % 256)
616 hiPositionVal = int(position >> 8)
618 response = self.
write(servo_id, DXL_GOAL_POSITION_L, (loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal))
620 self.
exception_on_error(response[4], servo_id,
'setting goal position to %d and moving speed to %d' %(position, speed))
625 Turn the LED of servo motor on/off. 626 Possible boolean state values: 627 True - turn the LED on, 628 False - turn the LED off. 630 response = self.
write(servo_id, DXL_LED, [led_state])
633 'setting a LED to %s' % led_state)
645 Method to set multiple servos torque enabled. 646 Should be called as such: 647 set_multi_servos_to_torque_enabled( (id1, True), (id2, True), (id3, True) ) 650 self.
sync_write(DXL_TORQUE_ENABLE, tuple(valueTuples))
654 Set different CW compliance margin for multiple servos. 655 Should be called as such: 656 set_multi_compliance_margin_cw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) ) 658 self.
sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
662 Set different CCW compliance margin for multiple servos. 663 Should be called as such: 664 set_multi_compliance_margin_ccw( ( (id1, margin1), (id2, margin2), (id3, margin3) ) ) 666 self.
sync_write(DXL_CCW_COMPLIANCE_MARGIN, tuple(valueTuples))
670 Set different CW and CCW compliance margins for multiple servos. 671 Should be called as such: 672 set_multi_compliance_margins( ( (id1, cw_margin1, ccw_margin1), (id2, cw_margin2, ccw_margin2) ) ) 674 self.
sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
678 Set different CW compliance slope for multiple servos. 679 Should be called as such: 680 set_multi_compliance_slope_cw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) ) 682 self.
sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
686 Set different CCW compliance slope for multiple servos. 687 Should be called as such: 688 set_multi_compliance_slope_ccw( ( (id1, slope1), (id2, slope2), (id3, slope3) ) ) 690 self.
sync_write(DXL_CCW_COMPLIANCE_SLOPE, tuple(valueTuples))
694 Set different CW and CCW compliance slopes for multiple servos. 695 Should be called as such: 696 set_multi_compliance_slopes( ( (id1, cw_slope1, ccw_slope1), (id2, cw_slope2, ccw_slope2) ) ) 698 self.
sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
702 Set different punch values for multiple servos. 703 NOTE: according to documentation, currently this value is not being used. 704 Should be called as such: 705 set_multi_punch( ( (id1, punch1), (id2, punch2), (id3, punch3) ) ) 710 for sid,punch
in valueTuples:
712 loVal = int(punch % 256)
713 hiVal = int(punch >> 8)
714 writeableVals.append( (sid, loVal, hiVal) )
721 Set different positions for multiple servos. 722 Should be called as such: 723 set_multi_position( ( (id1, position1), (id2, position2), (id3, position3) ) ) 728 for vals
in valueTuples:
732 loVal = int(position % 256)
733 hiVal = int(position >> 8)
734 writeableVals.append( (sid, loVal, hiVal) )
737 self.
sync_write(DXL_GOAL_POSITION_L, writeableVals)
741 Set different speeds for multiple servos. 742 Should be called as such: 743 set_multi_speed( ( (id1, speed1), (id2, speed2), (id3, speed3) ) ) 748 for vals
in valueTuples:
754 loVal = int(speed % 256)
755 hiVal = int(speed >> 8)
757 loVal = int((1023 - speed) % 256)
758 hiVal = int((1023 - speed) >> 8)
760 writeableVals.append( (sid, loVal, hiVal) )
763 self.
sync_write(DXL_GOAL_SPEED_L, writeableVals)
767 Set different torque limits for multiple servos. 768 Should be called as such: 769 set_multi_torque_limit( ( (id1, torque1), (id2, torque2), (id3, torque3) ) ) 774 for sid,torque
in valueTuples:
776 loVal = int(torque % 256)
777 hiVal = int(torque >> 8)
778 writeableVals.append( (sid, loVal, hiVal) )
781 self.
sync_write(DXL_TORQUE_LIMIT_L, writeableVals)
785 Set different positions and speeds for multiple servos. 786 Should be called as such: 787 set_multi_position_and_speed( ( (id1, position1, speed1), (id2, position2, speed2), (id3, position3, speed3) ) ) 792 for vals
in valueTuples:
799 loSpeedVal = int(speed % 256)
800 hiSpeedVal = int(speed >> 8)
802 loSpeedVal = int((1023 - speed) % 256)
803 hiSpeedVal = int((1023 - speed) >> 8)
806 loPositionVal = int(position % 256)
807 hiPositionVal = int(position >> 8)
808 writeableVals.append( (sid, loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal) )
811 self.
sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals))
819 """ Reads the servo's model number (e.g. 12 for AX-12+). """ 820 response = self.
read(servo_id, DXL_MODEL_NUMBER_L, 2)
823 return response[5] + (response[6] << 8)
826 """ Reads the servo's firmware version. """ 827 response = self.
read(servo_id, DXL_VERSION, 1)
833 """ Reads the servo's return delay time. """ 834 response = self.
read(servo_id, DXL_RETURN_DELAY_TIME, 1)
841 Returns the min and max angle limits from the specified servo. 844 response = self.
read(servo_id, DXL_CW_ANGLE_LIMIT_L, 4)
848 cwLimit = response[5] + (response[6] << 8)
849 ccwLimit = response[7] + (response[8] << 8)
852 return {
'min':cwLimit,
'max':ccwLimit}
855 """ Reads the servo's drive mode. """ 856 response = self.
read(servo_id, DXL_DRIVE_MODE, 1)
863 Returns the min and max voltage limits from the specified servo. 865 response = self.
read(servo_id, DXL_DOWN_LIMIT_VOLTAGE, 2)
869 min_voltage = response[5] / 10.0
870 max_voltage = response[6] / 10.0
873 return {
'min':min_voltage,
'max':max_voltage}
876 """ Reads the servo's position value from its registers. """ 877 response = self.
read(servo_id, DXL_PRESENT_POSITION_L, 2)
880 position = response[5] + (response[6] << 8)
884 """ Reads the servo's speed value from its registers. """ 885 response = self.
read(servo_id, DXL_PRESENT_SPEED_L, 2)
888 speed = response[5] + (response[6] << 8)
894 """ Reads the servo's voltage. """ 895 response = self.
read(servo_id, DXL_PRESENT_VOLTAGE, 1)
898 return response[5] / 10.0
901 """ Reads the servo's current consumption (if supported by model) """ 903 if not model
in DXL_MODEL_TO_PARAMS:
906 if DXL_CURRENT_L
in DXL_MODEL_TO_PARAMS[model][
'features']:
907 response = self.
read(servo_id, DXL_CURRENT_L, 2)
910 current = response[5] + (response[6] << 8)
911 return 0.0045 * (current - 2048)
913 if DXL_SENSED_CURRENT_L
in DXL_MODEL_TO_PARAMS[model][
'features']:
914 response = self.
read(servo_id, DXL_SENSED_CURRENT_L, 2)
917 current = response[5] + (response[6] << 8)
918 return 0.01 * (current - 512)
926 Returns the id, goal, position, error, speed, load, voltage, temperature 927 and moving values from the specified servo. 930 response = self.
read(servo_id, DXL_GOAL_POSITION_L, 17)
934 if len(response) == 24:
936 goal = response[5] + (response[6] << 8)
937 position = response[11] + (response[12] << 8)
938 error = position - goal
939 speed = response[13] + ( response[14] << 8)
940 if speed > 1023: speed = 1023 - speed
941 load_raw = response[15] + (response[16] << 8)
942 load_direction = 1
if self.
test_bit(load_raw, 10)
else 0
943 load = (load_raw & int(
'1111111111', 2)) / 1024.0
944 if load_direction == 1: load = -load
945 voltage = response[17] / 10.0
946 temperature = response[18]
947 moving = response[21]
948 timestamp = response[-1]
951 return {
'timestamp': timestamp,
954 'position': position,
959 'temperature': temperature,
960 'moving': bool(moving) }
964 Get status of the LED. Boolean return values: 968 response = self.
read(servo_id, DXL_LED, 1)
971 'fetching LED status')
973 return bool(response[5])
979 ex_message =
'[servo #%d on %s@%sbps]: %s failed' % (servo_id, self.ser.port, self.ser.baudrate, command_failed)
981 if not isinstance(error_code, int):
982 msg =
'Communcation Error ' + ex_message
985 if not error_code & DXL_OVERHEATING_ERROR == 0:
986 msg =
'Overheating Error ' + ex_message
988 if not error_code & DXL_OVERLOAD_ERROR == 0:
989 msg =
'Overload Error ' + ex_message
991 if not error_code & DXL_INPUT_VOLTAGE_ERROR == 0:
992 msg =
'Input Voltage Error ' + ex_message
994 if not error_code & DXL_ANGLE_LIMIT_ERROR == 0:
995 msg =
'Angle Limit Error ' + ex_message
997 if not error_code & DXL_RANGE_ERROR == 0:
998 msg =
'Range Error ' + ex_message
1000 if not error_code & DXL_CHECKSUM_ERROR == 0:
1001 msg =
'Checksum Error ' + ex_message
1003 if not error_code & DXL_INSTRUCTION_ERROR == 0:
1004 msg =
'Instruction Error ' + ex_message
1009 Exception.__init__(self)
1010 self.
message =
"Cannot open port '%s' at %d bps" %(port, baud)
1018 Exception.__init__(self)
1019 self.
message =
'Checksum received from motor %d does not match the expected one (%d != %d)' \
1020 %(servo_id, response[-1], checksum)
1028 Exception.__init__(self)
1036 Exception.__init__(self)
1044 Exception.__init__(self)
1052 Exception.__init__(self)
1059 Exception.__init__(self)
1060 if model_id
in DXL_MODEL_TO_PARAMS:
1061 model = DXL_MODEL_TO_PARAMS[model_id][
'name']
1064 self.
message =
"Feature %d not supported by model %d (%s)" %(feature_id, model_id, model)
def get_voltage_limits(self, servo_id)
def set_position_and_speed(self, servo_id, position, speed)
def set_goal_torque(self, servo_id, torque)
def get_led(self, servo_id)
def set_multi_position(self, valueTuples)
def set_voltage_limit_max(self, servo_id, max_voltage)
def __init__(self, servo_id, response, checksum)
def set_angle_limits(self, servo_id, min_angle, max_angle)
def exception_on_error(self, error_code, servo_id, command_failed)
def set_multi_compliance_margin_cw(self, valueTuples)
def get_feedback(self, servo_id)
def __read_response(self, servo_id)
def set_compliance_margins(self, servo_id, margin_cw, margin_ccw)
def set_position(self, servo_id, position)
def get_speed(self, servo_id)
def __init__(self, message, ec_const)
def set_torque_limit(self, servo_id, torque)
def set_voltage_limit_min(self, servo_id, min_voltage)
def set_compliance_slope_cw(self, servo_id, slope)
def set_multi_speed(self, valueTuples)
def set_compliance_margin_cw(self, servo_id, margin)
def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw)
def sync_write(self, address, data)
def write(self, servo_id, address, data)
def set_acceleration(self, servo_id, acceleration)
def __init__(self, port, baud)
def set_i_gain(self, servo_id, i_gain)
def set_punch(self, servo_id, punch)
def get_position(self, servo_id)
def get_drive_mode(self, servo_id)
def set_torque_enabled(self, servo_id, enabled)
These functions can send a single command to a single servo #.
def __init__(self, message)
def set_multi_compliance_margin_ccw(self, valueTuples)
def set_compliance_margin_ccw(self, servo_id, margin)
def set_drive_mode(self, servo_id, is_slave=False, is_reverse=False)
def read(self, servo_id, address, size)
def __write_serial(self, data)
def set_angle_limit_cw(self, servo_id, angle_cw)
def set_id(self, old_id, new_id)
These function modify EEPROM data which persists after power cycle #.
def __init__(self, message, ec_const)
def get_angle_limits(self, servo_id)
def set_multi_torque_enabled(self, valueTuples)
These functions can send multiple commands to multiple servos # These commands are used in ROS wrappe...
def get_current(self, servo_id)
def set_voltage_limits(self, servo_id, min_voltage, max_voltage)
def set_multi_punch(self, valueTuples)
def get_return_delay_time(self, servo_id)
def __init__(self, port, baudrate, readback_echo=False)
def set_angle_limit_ccw(self, servo_id, angle_ccw)
def set_return_delay_time(self, servo_id, delay)
def set_multi_position_and_speed(self, valueTuples)
def set_compliance_slope_ccw(self, servo_id, slope)
def test_bit(self, number, offset)
def __init__(self, model_id, feature_id)
def set_speed(self, servo_id, speed)
def set_multi_compliance_slope_ccw(self, valueTuples)
def set_multi_compliance_slopes(self, valueTuples)
def __init__(self, message, ec_const)
def set_led(self, servo_id, led_state)
def set_multi_compliance_slope_cw(self, valueTuples)
def set_p_gain(self, servo_id, p_gain)
def set_multi_compliance_margins(self, valueTuples)
def set_multi_torque_limit(self, valueTuples)
def get_voltage(self, servo_id)
def get_model_number(self, servo_id)
Servo status access functions #.
def set_d_gain(self, servo_id, d_gain)
def set_baud_rate(self, servo_id, baud_rate)
def get_firmware_version(self, servo_id)