dynamixel_io.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # -*- coding: utf-8 -*-
3 #
4 # Software License Agreement (BSD License)
5 #
6 # Copyright (c) 2010-2011, Cody Jorgensen, Antons Rebguns.
7 # All rights reserved.
8 #
9 # Redistribution and use in source and binary forms, with or without
10 # modification, are permitted provided that the following conditions
11 # are met:
12 #
13 # * Redistributions of source code must retain the above copyright
14 # notice, this list of conditions and the following disclaimer.
15 # * Redistributions in binary form must reproduce the above
16 # copyright notice, this list of conditions and the following
17 # disclaimer in the documentation and/or other materials provided
18 # with the distribution.
19 # * Neither the name of University of Arizona nor the names of its
20 # contributors may be used to endorse or promote products derived
21 # from this software without specific prior written permission.
22 #
23 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
24 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
25 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
26 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
27 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
28 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
29 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
30 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
31 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
32 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
33 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
34 # POSSIBILITY OF SUCH DAMAGE.
35 
36 
37 __author__ = 'Cody Jorgensen, Antons Rebguns'
38 __copyright__ = 'Copyright (c) 2010-2011 Cody Jorgensen, Antons Rebguns'
39 
40 __license__ = 'BSD'
41 __maintainer__ = 'Antons Rebguns'
42 __email__ = 'anton@email.arizona.edu'
43 
44 
45 import time
46 import serial
47 from array import array
48 from binascii import b2a_hex
49 from threading import Lock
50 
51 from dynamixel_const import *
52 
53 exception = None
54 
55 class DynamixelIO(object):
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.
60  """
61 
62  def __init__(self, port, baudrate, readback_echo=False):
63  """ Constructor takes serial port and baudrate as arguments. """
64  try:
65  self.serial_mutex = Lock()
66  self.ser = None
67  self.ser = serial.Serial(port, baudrate, timeout=0.015)
68  self.port_name = port
69  self.readback_echo = readback_echo
70  except SerialOpenError:
71  raise SerialOpenError(port, baudrate)
72 
73  def __del__(self):
74  """ Destructor calls DynamixelIO.close """
75  self.close()
76 
77  def close(self):
78  """
79  Be nice, close the serial port.
80  """
81  if self.ser:
82  self.ser.flushInput()
83  self.ser.flushOutput()
84  self.ser.close()
85 
86  def __write_serial(self, data):
87  self.ser.flushInput()
88  self.ser.flushOutput()
89  self.ser.write(data)
90  if self.readback_echo:
91  self.ser.read(len(data))
92 
93  def __read_response(self, servo_id):
94  data = []
95 
96  try:
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() # [int(b2a_hex(byte), 16) for byte in data]
101  except Exception, e:
102  raise DroppedPacketError('Invalid response received from motor %d. %s' % (servo_id, e))
103 
104  # verify checksum
105  checksum = 255 - sum(data[2:-1]) % 256
106  if not checksum == data[-1]: raise ChecksumError(servo_id, data, checksum)
107 
108  return data
109 
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.
114 
115  To read the position from servo with id 1, the method should be called
116  like:
117  read(1, DXL_GOAL_POSITION_L, 2)
118  """
119  # Number of bytes following standard header (0xFF, 0xFF, id, length)
120  length = 4 # instruction, address, size, checksum
121 
122  # directly from AX-12 manual:
123  # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
124  # If the calculated value is > 255, the lower byte is the check sum.
125  checksum = 255 - ( (servo_id + length + DXL_READ_DATA + address + size) % 256 )
126 
127  # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
128  packet = [0xFF, 0xFF, servo_id, length, DXL_READ_DATA, address, size, checksum]
129  packetStr = array('B', packet).tostring() # same as: packetStr = ''.join([chr(byte) for byte in packet])
130 
131  with self.serial_mutex:
132  self.__write_serial(packetStr)
133 
134  # wait for response packet from the motor
135  timestamp = time.time()
136  time.sleep(0.0013)#0.00235)
137 
138  # read response
139  data = self.__read_response(servo_id)
140  data.append(timestamp)
141 
142  return data
143 
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.
150 
151  To set servo with id 1 to position 276, the method should be called
152  like:
153  write(1, DXL_GOAL_POSITION_L, (20, 1))
154  """
155  # Number of bytes following standard header (0xFF, 0xFF, id, length)
156  length = 3 + len(data) # instruction, address, len(data), checksum
157 
158  # directly from AX-12 manual:
159  # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
160  # If the calculated value is > 255, the lower byte is the check sum.
161  checksum = 255 - ((servo_id + length + DXL_WRITE_DATA + address + sum(data)) % 256)
162 
163  # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
164  packet = [0xFF, 0xFF, servo_id, length, DXL_WRITE_DATA, address]
165  packet.extend(data)
166  packet.append(checksum)
167 
168  packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet])
169 
170  with self.serial_mutex:
171  self.__write_serial(packetStr)
172 
173  # wait for response packet from the motor
174  timestamp = time.time()
175  time.sleep(0.0013)
176 
177  # read response
178  data = self.__read_response(servo_id)
179  data.append(timestamp)
180 
181  return data
182 
183  def sync_write(self, address, data):
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.
191 
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) ))
195  """
196  # Calculate length and sum of all data
197  flattened = [value for servo in data for value in servo]
198 
199  # Number of bytes following standard header (0xFF, 0xFF, id, length) plus data
200  length = 4 + len(flattened)
201 
202  checksum = 255 - ((DXL_BROADCAST + length + \
203  DXL_SYNC_WRITE + address + len(data[0][1:]) + \
204  sum(flattened)) % 256)
205 
206  # packet: FF FF ID LENGTH INSTRUCTION PARAM_1 ... CHECKSUM
207  packet = [0xFF, 0xFF, DXL_BROADCAST, length, DXL_SYNC_WRITE, address, len(data[0][1:])]
208  packet.extend(flattened)
209  packet.append(checksum)
210 
211  packetStr = array('B', packet).tostring() # packetStr = ''.join([chr(byte) for byte in packet])
212 
213  with self.serial_mutex:
214  self.__write_serial(packetStr)
215 
216  def ping(self, servo_id):
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.
220  """
221  # Number of bytes following standard header (0xFF, 0xFF, id, length)
222  length = 2 # instruction, checksum
223 
224  # directly from AX-12 manual:
225  # Check Sum = ~ (ID + LENGTH + INSTRUCTION + PARAM_1 + ... + PARAM_N)
226  # If the calculated value is > 255, the lower byte is the check sum.
227  checksum = 255 - ((servo_id + length + DXL_PING) % 256)
228 
229  # packet: FF FF ID LENGTH INSTRUCTION CHECKSUM
230  packet = [0xFF, 0xFF, servo_id, length, DXL_PING, checksum]
231  packetStr = array('B', packet).tostring()
232 
233  with self.serial_mutex:
234  self.__write_serial(packetStr)
235 
236  # wait for response packet from the motor
237  timestamp = time.time()
238  time.sleep(0.0013)
239 
240  # read response
241  try:
242  response = self.__read_response(servo_id)
243  response.append(timestamp)
244  except Exception, e:
245  response = []
246 
247  if response:
248  self.exception_on_error(response[4], servo_id, 'ping')
249  return response
250 
251  def test_bit(self, number, offset):
252  mask = 1 << offset
253  return (number & mask)
254 
255 
256  ######################################################################
257  # These function modify EEPROM data which persists after power cycle #
258  ######################################################################
259 
260  def set_id(self, old_id, new_id):
261  """
262  Sets a new unique number to identify a motor. The range from 1 to 253
263  (0xFD) can be used.
264  """
265  response = self.write(old_id, DXL_ID, [new_id])
266  if response:
267  self.exception_on_error(response[4], old_id, 'setting id to %d' % new_id)
268  return response
269 
270  def set_baud_rate(self, servo_id, baud_rate):
271  """
272  Sets servo communication speed. The range from 0 to 254.
273  """
274  response = self.write(servo_id, DXL_BAUD_RATE, [baud_rate])
275  if response:
276  self.exception_on_error(response[4], servo_id, 'setting baud rate to %d' % baud_rate)
277  return response
278 
279  def set_return_delay_time(self, servo_id, delay):
280  """
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.
284  """
285  response = self.write(servo_id, DXL_RETURN_DELAY_TIME, [delay])
286  if response:
287  self.exception_on_error(response[4], servo_id, 'setting return delay time to %d' % delay)
288  return response
289 
290  def set_angle_limit_cw(self, servo_id, angle_cw):
291  """
292  Set the min (CW) angle of rotation limit.
293  """
294  loVal = int(angle_cw % 256)
295  hiVal = int(angle_cw >> 8)
296 
297  response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loVal, hiVal))
298  if response:
299  self.exception_on_error(response[4], servo_id, 'setting CW angle limits to %d' % angle_cw)
300  return response
301 
302  def set_angle_limit_ccw(self, servo_id, angle_ccw):
303  """
304  Set the max (CCW) angle of rotation limit.
305  """
306  loVal = int(angle_ccw % 256)
307  hiVal = int(angle_ccw >> 8)
308 
309  response = self.write(servo_id, DXL_CCW_ANGLE_LIMIT_L, (loVal, hiVal))
310  if response:
311  self.exception_on_error(response[4], servo_id, 'setting CCW angle limits to %d' % angle_ccw)
312  return response
313 
314  def set_angle_limits(self, servo_id, min_angle, max_angle):
315  """
316  Set the min (CW) and max (CCW) angle of rotation limits.
317  """
318  loMinVal = int(min_angle % 256)
319  hiMinVal = int(min_angle >> 8)
320  loMaxVal = int(max_angle % 256)
321  hiMaxVal = int(max_angle >> 8)
322 
323  # set 4 register values with low and high bytes for min and max angles
324  response = self.write(servo_id, DXL_CW_ANGLE_LIMIT_L, (loMinVal, hiMinVal, loMaxVal, hiMaxVal))
325  if response:
326  self.exception_on_error(response[4], servo_id, 'setting CW and CCW angle limits to %d and %d' %(min_angle, max_angle))
327  return response
328 
329  def set_drive_mode(self, servo_id, is_slave=False, is_reverse=False):
330  """
331  Sets the drive mode for EX-106 motors
332  """
333  drive_mode = (is_slave << 1) + is_reverse
334 
335  response = self.write(servo_id, DXL_DRIVE_MODE, [drive_mode])
336  if response:
337  self.exception_on_error(response[4], servo_id, 'setting drive mode to %d' % drive_mode)
338  return response
339 
340  def set_voltage_limit_min(self, servo_id, min_voltage):
341  """
342  Set the minimum voltage limit.
343  NOTE: the absolute min is 5v
344  """
345 
346  if min_voltage < 5: min_voltage = 5
347  minVal = int(min_voltage * 10)
348 
349  response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, [minVal])
350  if response:
351  self.exception_on_error(response[4], servo_id, 'setting minimum voltage level to %d' % min_voltage)
352  return response
353 
354  def set_voltage_limit_max(self, servo_id, max_voltage):
355  """
356  Set the maximum voltage limit.
357  NOTE: the absolute min is 25v
358  """
359 
360  if max_voltage > 25: max_voltage = 25
361  maxVal = int(max_voltage * 10)
362 
363  response = self.write(servo_id, DXL_UP_LIMIT_VOLTAGE, [maxVal])
364  if response:
365  self.exception_on_error(response[4], servo_id, 'setting maximum voltage level to %d' % max_voltage)
366  return response
367 
368  def set_voltage_limits(self, servo_id, min_voltage, max_voltage):
369  """
370  Set the min and max voltage limits.
371  NOTE: the absolute min is 5v and the absolute max is 25v
372  """
373 
374  if min_voltage < 5: min_voltage = 5
375  if max_voltage > 25: max_voltage = 25
376 
377  minVal = int(min_voltage * 10)
378  maxVal = int(max_voltage * 10)
379 
380  response = self.write(servo_id, DXL_DOWN_LIMIT_VOLTAGE, (minVal, maxVal))
381  if response:
382  self.exception_on_error(response[4], servo_id, 'setting min and max voltage levels to %d and %d' %(min_voltage, max_voltage))
383  return response
384 
385 
386  ###############################################################
387  # These functions can send a single command to a single servo #
388  ###############################################################
389 
390  def set_torque_enabled(self, servo_id, enabled):
391  """
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
394  still powered.
395  """
396  response = self.write(servo_id, DXL_TORQUE_ENABLE, [enabled])
397  if response:
398  self.exception_on_error(response[4], servo_id, '%sabling torque' % 'en' if enabled else 'dis')
399  return response
400 
401  def set_compliance_margin_cw(self, servo_id, margin):
402  """
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.
406  """
407  response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, [margin])
408  if response:
409  self.exception_on_error(response[4], servo_id, 'setting CW compliance margin to %d' % margin)
410  return response
411 
412  def set_compliance_margin_ccw(self, servo_id, margin):
413  """
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.
417  """
418  response = self.write(servo_id, DXL_CCW_COMPLIANCE_MARGIN, [margin])
419  if response:
420  self.exception_on_error(response[4], servo_id, 'setting CCW compliance margin to %d' % margin)
421  return response
422 
423  def set_compliance_margins(self, servo_id, margin_cw, margin_ccw):
424  """
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.
428  """
429  response = self.write(servo_id, DXL_CW_COMPLIANCE_MARGIN, (margin_cw, margin_ccw))
430  if response:
431  self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance margins to values %d and %d' %(margin_cw, margin_ccw))
432  return response
433 
434  def set_compliance_slope_cw(self, servo_id, slope):
435  """
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.
438  """
439  response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, [slope])
440  if response:
441  self.exception_on_error(response[4], servo_id, 'setting CW compliance slope to %d' % slope)
442  return response
443 
444  def set_compliance_slope_ccw(self, servo_id, slope):
445  """
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.
448  """
449  response = self.write(servo_id, DXL_CCW_COMPLIANCE_SLOPE, [slope])
450  if response:
451  self.exception_on_error(response[4], servo_id, 'setting CCW compliance slope to %d' % slope)
452  return response
453 
454  def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw):
455  """
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.
458  """
459  response = self.write(servo_id, DXL_CW_COMPLIANCE_SLOPE, (slope_cw, slope_ccw))
460  if response:
461  self.exception_on_error(response[4], servo_id, 'setting CW and CCW compliance slopes to %d and %d' %(slope_cw, slope_ccw))
462  return response
463 
464  def set_d_gain(self, servo_id, d_gain):
465  """
466  Sets the value of derivative action of PID controller.
467  Gain value is in range 0 to 254.
468  """
469  response = self.write(servo_id, DXL_D_GAIN, [d_gain])
470  if response:
471  self.exception_on_error(response[4], servo_id, 'setting D gain value of PID controller to %d' % d_gain)
472  return response
473 
474  def set_i_gain(self, servo_id, i_gain):
475  """
476  Sets the value of integral action of PID controller.
477  Gain value is in range 0 to 254.
478  """
479  response = self.write(servo_id, DXL_I_GAIN, [i_gain])
480  if response:
481  self.exception_on_error(response[4], servo_id, 'setting I gain value of PID controller to %d' % i_gain)
482  return response
483 
484  def set_p_gain(self, servo_id, p_gain):
485  """
486  Sets the value of proportional action of PID controller.
487  Gain value is in range 0 to 254.
488  """
489  response = self.write(servo_id, DXL_P_GAIN, [p_gain])
490  if response:
491  self.exception_on_error(response[4], servo_id, 'setting P gain value of PID controller to %d' % p_gain)
492  return response
493 
494  def set_punch(self, servo_id, punch):
495  """
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)
500  """
501  loVal = int(punch % 256)
502  hiVal = int(punch >> 8)
503  response = self.write(servo_id, DXL_PUNCH_L, (loVal, hiVal))
504  if response:
505  self.exception_on_error(response[4], servo_id, 'setting punch to %d' % punch)
506  return response
507 
508  def set_acceleration(self, servo_id, acceleration):
509  """
510  Sets the acceleration. The unit is 8.583 Degree / sec^2.
511  0 - acceleration control disabled, 1-254 - valid range for acceleration.
512  """
513 
514  model = self.get_model_number(servo_id)
515  if not model in DXL_MODEL_TO_PARAMS:
516  raise UnsupportedFeatureError(model, DXL_GOAL_ACCELERATION)
517 
518  if DXL_GOAL_ACCELERATION in DXL_MODEL_TO_PARAMS[model]['features']:
519  response = self.write(servo_id, DXL_GOAL_ACCELERATION, (acceleration, ))
520  if response:
521  self.exception_on_error(response[4], servo_id, 'setting acceleration to %d' % acceleration)
522  return response
523  else:
524  raise UnsupportedFeatureError(model, DXL_GOAL_ACCELERATION)
525 
526  def set_position(self, servo_id, position):
527  """
528  Set the servo with servo_id to the specified goal position.
529  Position value must be positive.
530  """
531  loVal = int(position % 256)
532  hiVal = int(position >> 8)
533 
534  response = self.write(servo_id, DXL_GOAL_POSITION_L, (loVal, hiVal))
535  if response:
536  self.exception_on_error(response[4], servo_id, 'setting goal position to %d' % position)
537  return response
538 
539  def set_speed(self, servo_id, speed):
540  """
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.
543  """
544  # split speed into 2 bytes
545  if speed >= 0:
546  loVal = int(speed % 256)
547  hiVal = int(speed >> 8)
548  else:
549  loVal = int((1023 - speed) % 256)
550  hiVal = int((1023 - speed) >> 8)
551 
552  # set two register values with low and high byte for the speed
553  response = self.write(servo_id, DXL_GOAL_SPEED_L, (loVal, hiVal))
554  if response:
555  self.exception_on_error(response[4], servo_id, 'setting moving speed to %d' % speed)
556  return response
557 
558  def set_torque_limit(self, servo_id, torque):
559  """
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.
564  """
565  loVal = int(torque % 256)
566  hiVal = int(torque >> 8)
567 
568  response = self.write(servo_id, DXL_TORQUE_LIMIT_L, (loVal, hiVal))
569  if response:
570  self.exception_on_error(response[4], servo_id, 'setting torque limit to %d' % torque)
571  return response
572 
573  def set_goal_torque(self, servo_id, torque):
574  """
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.
578  """
579 
580  model = self.get_model_number(servo_id)
581  if not model in DXL_MODEL_TO_PARAMS:
582  raise UnsupportedFeatureError(model, DXL_TORQUE_CONTROL_MODE)
583 
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
587 
588  if DXL_TORQUE_CONTROL_MODE in DXL_MODEL_TO_PARAMS[model]['features']:
589  if valid_torque:
590  loVal = int(torque % 256); hiVal = int(torque >> 8);
591  response = self.write(servo_id, DXL_GOAL_TORQUE_L, (loVal, hiVal))
592  if response:
593  self.exception_on_error(response[4], servo_id, 'setting goal torque to %d' % torque)
594  response = self.write(servo_id, DXL_TORQUE_CONTROL_MODE, (int(valid_torque), ))
595  if response:
596  self.exception_on_error(response[4], servo_id, 'enabling torque mode')
597  return response
598  else:
599  raise UnsupportedFeatureError(model, DXL_TORQUE_CONTROL_MODE)
600 
601  def set_position_and_speed(self, servo_id, position, speed):
602  """
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.
605  """
606  # split speed into 2 bytes
607  if speed >= 0:
608  loSpeedVal = int(speed % 256)
609  hiSpeedVal = int(speed >> 8)
610  else:
611  loSpeedVal = int((1023 - speed) % 256)
612  hiSpeedVal = int((1023 - speed) >> 8)
613 
614  # split position into 2 bytes
615  loPositionVal = int(position % 256)
616  hiPositionVal = int(position >> 8)
617 
618  response = self.write(servo_id, DXL_GOAL_POSITION_L, (loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal))
619  if response:
620  self.exception_on_error(response[4], servo_id, 'setting goal position to %d and moving speed to %d' %(position, speed))
621  return response
622 
623  def set_led(self, servo_id, led_state):
624  """
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.
629  """
630  response = self.write(servo_id, DXL_LED, [led_state])
631  if response:
632  self.exception_on_error(response[4], servo_id,
633  'setting a LED to %s' % led_state)
634  return response
635 
636 
637  #################################################################
638  # These functions can send multiple commands to multiple servos #
639  # These commands are used in ROS wrapper as they don't send a #
640  # response packet, ROS wrapper gets motor states at a set rate #
641  #################################################################
642 
643  def set_multi_torque_enabled(self, valueTuples):
644  """
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) )
648  """
649  # use sync write to broadcast multi servo message
650  self.sync_write(DXL_TORQUE_ENABLE, tuple(valueTuples))
651 
652  def set_multi_compliance_margin_cw(self, valueTuples):
653  """
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) ) )
657  """
658  self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
659 
660  def set_multi_compliance_margin_ccw(self, valueTuples):
661  """
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) ) )
665  """
666  self.sync_write(DXL_CCW_COMPLIANCE_MARGIN, tuple(valueTuples))
667 
668  def set_multi_compliance_margins(self, valueTuples):
669  """
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) ) )
673  """
674  self.sync_write(DXL_CW_COMPLIANCE_MARGIN, tuple(valueTuples))
675 
676  def set_multi_compliance_slope_cw(self, valueTuples):
677  """
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) ) )
681  """
682  self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
683 
684  def set_multi_compliance_slope_ccw(self, valueTuples):
685  """
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) ) )
689  """
690  self.sync_write(DXL_CCW_COMPLIANCE_SLOPE, tuple(valueTuples))
691 
692  def set_multi_compliance_slopes(self, valueTuples):
693  """
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) ) )
697  """
698  self.sync_write(DXL_CW_COMPLIANCE_SLOPE, tuple(valueTuples))
699 
700  def set_multi_punch(self, valueTuples):
701  """
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) ) )
706  """
707  # prepare value tuples for call to syncwrite
708  writeableVals = []
709 
710  for sid,punch in valueTuples:
711  # split punch into 2 bytes
712  loVal = int(punch % 256)
713  hiVal = int(punch >> 8)
714  writeableVals.append( (sid, loVal, hiVal) )
715 
716  # use sync write to broadcast multi servo message
717  self.sync_write(DXL_PUNCH_L, writeableVals)
718 
719  def set_multi_position(self, valueTuples):
720  """
721  Set different positions for multiple servos.
722  Should be called as such:
723  set_multi_position( ( (id1, position1), (id2, position2), (id3, position3) ) )
724  """
725  # prepare value tuples for call to syncwrite
726  writeableVals = []
727 
728  for vals in valueTuples:
729  sid = vals[0]
730  position = vals[1]
731  # split position into 2 bytes
732  loVal = int(position % 256)
733  hiVal = int(position >> 8)
734  writeableVals.append( (sid, loVal, hiVal) )
735 
736  # use sync write to broadcast multi servo message
737  self.sync_write(DXL_GOAL_POSITION_L, writeableVals)
738 
739  def set_multi_speed(self, valueTuples):
740  """
741  Set different speeds for multiple servos.
742  Should be called as such:
743  set_multi_speed( ( (id1, speed1), (id2, speed2), (id3, speed3) ) )
744  """
745  # prepare value tuples for call to syncwrite
746  writeableVals = []
747 
748  for vals in valueTuples:
749  sid = vals[0]
750  speed = vals[1]
751 
752  # split speed into 2 bytes
753  if speed >= 0:
754  loVal = int(speed % 256)
755  hiVal = int(speed >> 8)
756  else:
757  loVal = int((1023 - speed) % 256)
758  hiVal = int((1023 - speed) >> 8)
759 
760  writeableVals.append( (sid, loVal, hiVal) )
761 
762  # use sync write to broadcast multi servo message
763  self.sync_write(DXL_GOAL_SPEED_L, writeableVals)
764 
765  def set_multi_torque_limit(self, valueTuples):
766  """
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) ) )
770  """
771  # prepare value tuples for call to syncwrite
772  writeableVals = []
773 
774  for sid,torque in valueTuples:
775  # split torque into 2 bytes
776  loVal = int(torque % 256)
777  hiVal = int(torque >> 8)
778  writeableVals.append( (sid, loVal, hiVal) )
779 
780  # use sync write to broadcast multi servo message
781  self.sync_write(DXL_TORQUE_LIMIT_L, writeableVals)
782 
783  def set_multi_position_and_speed(self, valueTuples):
784  """
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) ) )
788  """
789  # prepare value tuples for call to syncwrite
790  writeableVals = []
791 
792  for vals in valueTuples:
793  sid = vals[0]
794  position = vals[1]
795  speed = vals[2]
796 
797  # split speed into 2 bytes
798  if speed >= 0:
799  loSpeedVal = int(speed % 256)
800  hiSpeedVal = int(speed >> 8)
801  else:
802  loSpeedVal = int((1023 - speed) % 256)
803  hiSpeedVal = int((1023 - speed) >> 8)
804 
805  # split position into 2 bytes
806  loPositionVal = int(position % 256)
807  hiPositionVal = int(position >> 8)
808  writeableVals.append( (sid, loPositionVal, hiPositionVal, loSpeedVal, hiSpeedVal) )
809 
810  # use sync write to broadcast multi servo message
811  self.sync_write(DXL_GOAL_POSITION_L, tuple(writeableVals))
812 
813 
814  #################################
815  # Servo status access functions #
816  #################################
817 
818  def get_model_number(self, servo_id):
819  """ Reads the servo's model number (e.g. 12 for AX-12+). """
820  response = self.read(servo_id, DXL_MODEL_NUMBER_L, 2)
821  if response:
822  self.exception_on_error(response[4], servo_id, 'fetching model number')
823  return response[5] + (response[6] << 8)
824 
825  def get_firmware_version(self, servo_id):
826  """ Reads the servo's firmware version. """
827  response = self.read(servo_id, DXL_VERSION, 1)
828  if response:
829  self.exception_on_error(response[4], servo_id, 'fetching firmware version')
830  return response[5]
831 
832  def get_return_delay_time(self, servo_id):
833  """ Reads the servo's return delay time. """
834  response = self.read(servo_id, DXL_RETURN_DELAY_TIME, 1)
835  if response:
836  self.exception_on_error(response[4], servo_id, 'fetching return delay time')
837  return response[5]
838 
839  def get_angle_limits(self, servo_id):
840  """
841  Returns the min and max angle limits from the specified servo.
842  """
843  # read in 4 consecutive bytes starting with low value of clockwise angle limit
844  response = self.read(servo_id, DXL_CW_ANGLE_LIMIT_L, 4)
845  if response:
846  self.exception_on_error(response[4], servo_id, 'fetching CW/CCW angle limits')
847  # extract data valus from the raw data
848  cwLimit = response[5] + (response[6] << 8)
849  ccwLimit = response[7] + (response[8] << 8)
850 
851  # return the data in a dictionary
852  return {'min':cwLimit, 'max':ccwLimit}
853 
854  def get_drive_mode(self, servo_id):
855  """ Reads the servo's drive mode. """
856  response = self.read(servo_id, DXL_DRIVE_MODE, 1)
857  if response:
858  self.exception_on_error(response[4], servo_id, 'fetching drive mode')
859  return response[5]
860 
861  def get_voltage_limits(self, servo_id):
862  """
863  Returns the min and max voltage limits from the specified servo.
864  """
865  response = self.read(servo_id, DXL_DOWN_LIMIT_VOLTAGE, 2)
866  if response:
867  self.exception_on_error(response[4], servo_id, 'fetching voltage limits')
868  # extract data valus from the raw data
869  min_voltage = response[5] / 10.0
870  max_voltage = response[6] / 10.0
871 
872  # return the data in a dictionary
873  return {'min':min_voltage, 'max':max_voltage}
874 
875  def get_position(self, servo_id):
876  """ Reads the servo's position value from its registers. """
877  response = self.read(servo_id, DXL_PRESENT_POSITION_L, 2)
878  if response:
879  self.exception_on_error(response[4], servo_id, 'fetching present position')
880  position = response[5] + (response[6] << 8)
881  return position
882 
883  def get_speed(self, servo_id):
884  """ Reads the servo's speed value from its registers. """
885  response = self.read(servo_id, DXL_PRESENT_SPEED_L, 2)
886  if response:
887  self.exception_on_error(response[4], servo_id, 'fetching present speed')
888  speed = response[5] + (response[6] << 8)
889  if speed > 1023:
890  return 1023 - speed
891  return speed
892 
893  def get_voltage(self, servo_id):
894  """ Reads the servo's voltage. """
895  response = self.read(servo_id, DXL_PRESENT_VOLTAGE, 1)
896  if response:
897  self.exception_on_error(response[4], servo_id, 'fetching supplied voltage')
898  return response[5] / 10.0
899 
900  def get_current(self, servo_id):
901  """ Reads the servo's current consumption (if supported by model) """
902  model = self.get_model_number(servo_id)
903  if not model in DXL_MODEL_TO_PARAMS:
904  raise UnsupportedFeatureError(model, DXL_CURRENT_L)
905 
906  if DXL_CURRENT_L in DXL_MODEL_TO_PARAMS[model]['features']:
907  response = self.read(servo_id, DXL_CURRENT_L, 2)
908  if response:
909  self.exception_on_error(response[4], servo_id, 'fetching sensed current')
910  current = response[5] + (response[6] << 8)
911  return 0.0045 * (current - 2048)
912 
913  if DXL_SENSED_CURRENT_L in DXL_MODEL_TO_PARAMS[model]['features']:
914  response = self.read(servo_id, DXL_SENSED_CURRENT_L, 2)
915  if response:
916  self.exception_on_error(response[4], servo_id, 'fetching sensed current')
917  current = response[5] + (response[6] << 8)
918  return 0.01 * (current - 512)
919 
920  else:
921  raise UnsupportedFeatureError(model, DXL_CURRENT_L)
922 
923 
924  def get_feedback(self, servo_id):
925  """
926  Returns the id, goal, position, error, speed, load, voltage, temperature
927  and moving values from the specified servo.
928  """
929  # read in 17 consecutive bytes starting with low value for goal position
930  response = self.read(servo_id, DXL_GOAL_POSITION_L, 17)
931 
932  if response:
933  self.exception_on_error(response[4], servo_id, 'fetching full servo status')
934  if len(response) == 24:
935  # extract data values from the raw data
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]
949 
950  # return the data in a dictionary
951  return { 'timestamp': timestamp,
952  'id': servo_id,
953  'goal': goal,
954  'position': position,
955  'error': error,
956  'speed': speed,
957  'load': load,
958  'voltage': voltage,
959  'temperature': temperature,
960  'moving': bool(moving) }
961 
962  def get_led(self, servo_id):
963  """
964  Get status of the LED. Boolean return values:
965  True - LED is on,
966  False - LED is off.
967  """
968  response = self.read(servo_id, DXL_LED, 1)
969  if response:
970  self.exception_on_error(response[4], servo_id,
971  'fetching LED status')
972 
973  return bool(response[5])
974 
975 
976  def exception_on_error(self, error_code, servo_id, command_failed):
977  global exception
978  exception = None
979  ex_message = '[servo #%d on %s@%sbps]: %s failed' % (servo_id, self.ser.port, self.ser.baudrate, command_failed)
980 
981  if not isinstance(error_code, int):
982  msg = 'Communcation Error ' + ex_message
983  exception = NonfatalErrorCodeError(msg, 0)
984  return
985  if not error_code & DXL_OVERHEATING_ERROR == 0:
986  msg = 'Overheating Error ' + ex_message
987  exception = FatalErrorCodeError(msg, error_code)
988  if not error_code & DXL_OVERLOAD_ERROR == 0:
989  msg = 'Overload Error ' + ex_message
990  exception = FatalErrorCodeError(msg, error_code)
991  if not error_code & DXL_INPUT_VOLTAGE_ERROR == 0:
992  msg = 'Input Voltage Error ' + ex_message
993  exception = NonfatalErrorCodeError(msg, error_code)
994  if not error_code & DXL_ANGLE_LIMIT_ERROR == 0:
995  msg = 'Angle Limit Error ' + ex_message
996  exception = NonfatalErrorCodeError(msg, error_code)
997  if not error_code & DXL_RANGE_ERROR == 0:
998  msg = 'Range Error ' + ex_message
999  exception = NonfatalErrorCodeError(msg, error_code)
1000  if not error_code & DXL_CHECKSUM_ERROR == 0:
1001  msg = 'Checksum Error ' + ex_message
1002  exception = NonfatalErrorCodeError(msg, error_code)
1003  if not error_code & DXL_INSTRUCTION_ERROR == 0:
1004  msg = 'Instruction Error ' + ex_message
1005  exception = NonfatalErrorCodeError(msg, error_code)
1006 
1007 class SerialOpenError(Exception):
1008  def __init__(self, port, baud):
1009  Exception.__init__(self)
1010  self.message = "Cannot open port '%s' at %d bps" %(port, baud)
1011  self.port = port
1012  self.baud = baud
1013  def __str__(self):
1014  return self.message
1015 
1016 class ChecksumError(Exception):
1017  def __init__(self, servo_id, response, checksum):
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)
1021  self.response_data = response
1022  self.expected_checksum = checksum
1023  def __str__(self):
1024  return self.message
1025 
1026 class FatalErrorCodeError(Exception):
1027  def __init__(self, message, ec_const):
1028  Exception.__init__(self)
1029  self.message = message
1030  self.error_code = ec_const
1031  def __str__(self):
1032  return self.message
1033 
1034 class NonfatalErrorCodeError(Exception):
1035  def __init__(self, message, ec_const):
1036  Exception.__init__(self)
1037  self.message = message
1038  self.error_code = ec_const
1039  def __str__(self):
1040  return self.message
1041 
1042 class ErrorCodeError(Exception):
1043  def __init__(self, message, ec_const):
1044  Exception.__init__(self)
1045  self.message = message
1046  self.error_code = ec_const
1047  def __str__(self):
1048  return self.message
1049 
1050 class DroppedPacketError(Exception):
1051  def __init__(self, message):
1052  Exception.__init__(self)
1053  self.message = message
1054  def __str__(self):
1055  return self.message
1056 
1057 class UnsupportedFeatureError(Exception):
1058  def __init__(self, model_id, feature_id):
1059  Exception.__init__(self)
1060  if model_id in DXL_MODEL_TO_PARAMS:
1061  model = DXL_MODEL_TO_PARAMS[model_id]['name']
1062  else:
1063  model = 'Unknown'
1064  self.message = "Feature %d not supported by model %d (%s)" %(feature_id, model_id, model)
1065  def __str__(self):
1066  return self.message
1067 
def set_position_and_speed(self, servo_id, position, speed)
def set_goal_torque(self, servo_id, torque)
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 set_compliance_margins(self, servo_id, margin_cw, margin_ccw)
def set_position(self, servo_id, position)
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_compliance_margin_cw(self, servo_id, margin)
def set_compliance_slopes(self, servo_id, slope_cw, slope_ccw)
def write(self, servo_id, address, data)
def set_acceleration(self, servo_id, acceleration)
def set_i_gain(self, servo_id, i_gain)
def set_punch(self, servo_id, punch)
def set_torque_enabled(self, servo_id, enabled)
These functions can send a single command to a single servo #.
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 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 set_multi_torque_enabled(self, valueTuples)
These functions can send multiple commands to multiple servos # These commands are used in ROS wrappe...
def set_voltage_limits(self, servo_id, min_voltage, max_voltage)
def __init__(self, port, baudrate, readback_echo=False)
Definition: dynamixel_io.py:62
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 set_speed(self, servo_id, speed)
def set_multi_compliance_slope_ccw(self, valueTuples)
def set_multi_compliance_slopes(self, valueTuples)
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_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)


dynamixel_driver
Author(s): Antons Rebguns, Cody Jorgensen
autogenerated on Tue May 12 2020 03:10:57