dynamixel_const.py
Go to the documentation of this file.
00001 # -*- coding: utf-8 -*-
00002 #
00003 # Software License Agreement (BSD License)
00004 #
00005 # Copyright (c) 2010-2011, Cody Jorgensen, Antons Rebguns.
00006 # All rights reserved.
00007 #
00008 # Redistribution and use in source and binary forms, with or without
00009 # modification, are permitted provided that the following conditions
00010 # are met:
00011 #
00012 #  * Redistributions of source code must retain the above copyright
00013 #    notice, this list of conditions and the following disclaimer.
00014 #  * Redistributions in binary form must reproduce the above
00015 #    copyright notice, this list of conditions and the following
00016 #    disclaimer in the documentation and/or other materials provided
00017 #    with the distribution.
00018 #  * Neither the name of University of Arizona nor the names of its
00019 #    contributors may be used to endorse or promote products derived
00020 #    from this software without specific prior written permission.
00021 #
00022 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00023 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00024 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00025 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00026 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00027 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00028 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00029 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00030 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00031 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00032 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00033 # POSSIBILITY OF SUCH DAMAGE.
00034 
00035 
00036 __author__ = 'Cody Jorgensen, Antons Rebguns'
00037 __copyright__ = 'Copyright (c) 2010-2011 Cody Jorgensen, Antons Rebguns'
00038 
00039 __license__ = 'BSD'
00040 __maintainer__ = 'Antons Rebguns'
00041 __email__ = 'anton@email.arizona.edu'
00042 
00043 
00044 """
00045 Dynamixel Constants
00046 """
00047 # Control Table Constants
00048 DXL_MODEL_NUMBER_L = 0
00049 DXL_MODEL_NUMBER_H = 1
00050 DXL_VERSION = 2
00051 DXL_ID = 3
00052 DXL_BAUD_RATE = 4
00053 DXL_RETURN_DELAY_TIME = 5
00054 DXL_CW_ANGLE_LIMIT_L = 6
00055 DXL_CW_ANGLE_LIMIT_H = 7
00056 DXL_CCW_ANGLE_LIMIT_L = 8
00057 DXL_CCW_ANGLE_LIMIT_H = 9
00058 DXL_DRIVE_MODE = 10
00059 DXL_LIMIT_TEMPERATURE = 11
00060 DXL_DOWN_LIMIT_VOLTAGE = 12
00061 DXL_UP_LIMIT_VOLTAGE = 13
00062 DXL_MAX_TORQUE_L = 14
00063 DXL_MAX_TORQUE_H = 15
00064 DXL_RETURN_LEVEL = 16
00065 DXL_ALARM_LED = 17
00066 DXL_ALARM_SHUTDOWN = 18
00067 DXL_OPERATING_MODE = 19
00068 DXL_DOWN_CALIBRATION_L = 20
00069 DXL_DOWN_CALIBRATION_H = 21
00070 DXL_UP_CALIBRATION_L = 22
00071 DXL_UP_CALIBRATION_H = 23
00072 DXL_TORQUE_ENABLE = 24
00073 DXL_LED = 25
00074 DXL_CW_COMPLIANCE_MARGIN = 26
00075 DXL_CCW_COMPLIANCE_MARGIN = 27
00076 DXL_CW_COMPLIANCE_SLOPE = 28
00077 DXL_CCW_COMPLIANCE_SLOPE = 29
00078 DXL_D_GAIN = 26
00079 DXL_I_GAIN = 27
00080 DXL_P_GAIN = 28
00081 DXL_GOAL_POSITION_L = 30
00082 DXL_GOAL_POSITION_H = 31
00083 DXL_GOAL_SPEED_L = 32
00084 DXL_GOAL_SPEED_H = 33
00085 DXL_TORQUE_LIMIT_L = 34
00086 DXL_TORQUE_LIMIT_H = 35
00087 DXL_PRESENT_POSITION_L = 36
00088 DXL_PRESENT_POSITION_H = 37
00089 DXL_PRESENT_SPEED_L = 38
00090 DXL_PRESENT_SPEED_H = 39
00091 DXL_PRESENT_LOAD_L = 40
00092 DXL_PRESENT_LOAD_H = 41
00093 DXL_PRESENT_VOLTAGE = 42
00094 DXL_PRESENT_TEMPERATURE = 43
00095 DXL_REGISTERED_INSTRUCTION = 44
00096 DXL_PAUSE_TIME = 45
00097 DXL_MOVING = 46
00098 DXL_LOCK = 47
00099 DXL_PUNCH_L = 48
00100 DXL_PUNCH_H = 49
00101 DXL_SENSED_CURRENT_L = 56
00102 DXL_SENSED_CURRENT_H = 57
00103 
00104 # Status Return Levels
00105 DXL_RETURN_NONE = 0
00106 DXL_RETURN_READ = 1
00107 DXL_RETURN_ALL = 2
00108 
00109 # Instruction Set
00110 DXL_PING = 1
00111 DXL_READ_DATA = 2
00112 DXL_WRITE_DATA = 3
00113 DXL_REG_WRITE = 4
00114 DXL_ACTION = 5
00115 DXL_RESET = 6
00116 DXL_SYNC_WRITE = 131
00117 
00118 # Broadcast Constant
00119 DXL_BROADCAST = 254
00120 
00121 # Error Codes
00122 DXL_INSTRUCTION_ERROR = 64
00123 DXL_OVERLOAD_ERROR = 32
00124 DXL_CHECKSUM_ERROR = 16
00125 DXL_RANGE_ERROR = 8
00126 DXL_OVERHEATING_ERROR = 4
00127 DXL_ANGLE_LIMIT_ERROR = 2
00128 DXL_INPUT_VOLTAGE_ERROR = 1
00129 DXL_NO_ERROR = 0
00130 
00131 # Static parameters
00132 DXL_MIN_COMPLIANCE_MARGIN = 0
00133 DXL_MAX_COMPLIANCE_MARGIN = 255
00134 
00135 DXL_MIN_COMPLIANCE_SLOPE = 1
00136 DXL_MAX_COMPLIANCE_SLOPE = 254
00137 
00138 # These are guesses as Dynamixel documentation doesn't have any info about it
00139 DXL_MIN_PUNCH = 0
00140 DXL_MAX_PUNCH = 255
00141 
00142 DXL_MAX_SPEED_TICK = 1023                   # maximum speed in encoder units
00143 DXL_MAX_TORQUE_TICK = 1023                  # maximum torque in encoder units
00144 
00145 KGCM_TO_NM = 0.0980665                      # 1 kg-cm is that many N-m
00146 RPM_TO_RADSEC = 0.104719755                 # 1 RPM is that many rad/sec
00147 
00148 # maximum holding torque is in N-m per volt
00149 # maximum velocity is in rad/sec per volt
00150 DXL_MODEL_TO_PARAMS = \
00151 {
00152     113: { 'name':               'DX-113',
00153            'encoder_resolution': 1024,
00154            'range_degrees':      300.0,
00155            'torque_per_volt':    1.0 / 12.0,                       #  1.0 NM @ 12V
00156            'velocity_per_volt':  (54 * RPM_TO_RADSEC) / 12.0,      #  54 RPM @ 12V
00157          },
00158     116: { 'name':               'DX-116',
00159            'encoder_resolution': 1024,
00160            'range_degrees':      300.0,
00161            'torque_per_volt':    2.1 / 12.0,                       #  2.1 NM @ 12V
00162            'velocity_per_volt':  (78 * RPM_TO_RADSEC) / 12.0,      #  78 RPM @ 12V
00163          },
00164     117: { 'name':               'DX-117',
00165            'encoder_resolution': 1024,
00166            'range_degrees':      300.0,
00167            'torque_per_volt':    3.7 / 18.5,                       #  3.7 NM @ 18.5V
00168            'velocity_per_volt':  (85 * RPM_TO_RADSEC) / 18.5,      #  85 RPM @ 18.5V
00169          },
00170      12: { 'name':               'AX-12',
00171            'encoder_resolution': 1024,
00172            'range_degrees':      300.0,
00173            'torque_per_volt':    1.5 / 12.0,                       #  1.5 NM @ 12V
00174            'velocity_per_volt':  (59 * RPM_TO_RADSEC) / 12.0,      #  59 RPM @ 12V
00175          },
00176      18: { 'name':               'AX-18',
00177            'encoder_resolution': 1024,
00178            'range_degrees':      300.0,
00179            'torque_per_volt':    1.8 / 12.0,                       #  1.8 NM @ 12V
00180            'velocity_per_volt':  (97 * RPM_TO_RADSEC) / 12.0,      #  97 RPM @ 12V
00181          },
00182      10: { 'name':               'RX-10',
00183            'encoder_resolution': 1024,
00184            'range_degrees':      300.0,
00185            'torque_per_volt':    1.3 / 12.0,                       #  1.3 NM @ 12V
00186            'velocity_per_volt':  (54 * RPM_TO_RADSEC) / 12.0,      #  54 RPM @ 12V
00187          },
00188      24: { 'name':               'RX-24',
00189            'encoder_resolution': 1024,
00190            'range_degrees':      300.0,
00191            'torque_per_volt':    2.6 / 12.0,                       #  2.6 NM @ 12V
00192            'velocity_per_volt':  (126 * RPM_TO_RADSEC) / 12.0,     # 126 RPM @ 12V
00193          },
00194      28: { 'name':               'RX-28',
00195            'encoder_resolution': 1024,
00196            'range_degrees':      300.0,
00197            'torque_per_volt':    3.7 / 18.5,                       #  3.7 NM @ 18.5V
00198            'velocity_per_volt':  (85 * RPM_TO_RADSEC) / 18.5,      #  85 RPM @ 18.5V
00199          },
00200      64: { 'name':               'RX-64',
00201            'encoder_resolution': 1024,
00202            'range_degrees':      300.0,
00203            'torque_per_volt':    5.3 / 18.5,                       #  5.3 NM @ 18.5V
00204            'velocity_per_volt':  (64 * RPM_TO_RADSEC) / 18.5,      #  64 RPM @ 18.5V
00205          },
00206     107: { 'name':               'EX-106',
00207            'encoder_resolution': 4096,
00208            'range_degrees':      250.92,
00209            'torque_per_volt':    10.9 / 18.5,                      # 10.9 NM @ 18.5V
00210            'velocity_per_volt':  (91 * RPM_TO_RADSEC) / 18.5,      #  91 RPM @ 18.5V
00211          },
00212      29: { 'name':               'MX-28',
00213            'encoder_resolution': 4096,
00214            'range_degrees':      360.0,
00215            'torque_per_volt':    2.5 / 12.0,                       #  2.5 NM @ 12V
00216            'velocity_per_volt':  (55 * RPM_TO_RADSEC) / 12.0,      #  54 RPM @ 12.0V
00217          },
00218     310: { 'name':               'MX-64',
00219            'encoder_resolution': 4096,
00220            'range_degrees':      360.0,
00221            'torque_per_volt':    6.0 / 12.0,                       #  6 NM @ 12V
00222            'velocity_per_volt':  (63 * RPM_TO_RADSEC) / 12.0,      #  63 RPM @ 12.0V
00223          },
00224     320: { 'name':               'MX-106',
00225            'encoder_resolution': 4096,
00226            'range_degrees':      360.0,
00227            'torque_per_volt':    8.4 / 12.0,                       #  8.4 NM @ 12V
00228            'velocity_per_volt':  (45 * RPM_TO_RADSEC) / 12.0,      #  45 RPM @ 12.0V
00229          },
00230 }
00231 


dynamixel_driver
Author(s): Antons Rebguns, Cody Jorgensen
autogenerated on Fri Jan 3 2014 11:19:42