$search
00001 # -*- coding: utf-8 -*- 00002 # 00003 # Software License Agreement (BSD License) 00004 # 00005 # Copyright (c) 2010-2011, 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 from __future__ import division 00036 00037 00038 __author__ = 'Antons Rebguns' 00039 __copyright__ = 'Copyright (c) 2010-2011 Antons Rebguns' 00040 __credits__ = 'Cara Slutter' 00041 00042 __license__ = 'BSD' 00043 __maintainer__ = 'Antons Rebguns' 00044 __email__ = 'anton@email.arizona.edu' 00045 00046 00047 import roslib 00048 roslib.load_manifest('dynamixel_controllers') 00049 00050 import rospy 00051 00052 from dynamixel_driver.dynamixel_const import * 00053 from dynamixel_controllers.joint_controller import JointController 00054 00055 from dynamixel_msgs.msg import JointState 00056 00057 class JointPositionController(JointController): 00058 def __init__(self, dxl_io, controller_namespace, port_namespace): 00059 JointController.__init__(self, dxl_io, controller_namespace, port_namespace) 00060 00061 self.motor_id = rospy.get_param(self.controller_namespace + '/motor/id') 00062 self.initial_position_raw = rospy.get_param(self.controller_namespace + '/motor/init') 00063 self.min_angle_raw = rospy.get_param(self.controller_namespace + '/motor/min') 00064 self.max_angle_raw = rospy.get_param(self.controller_namespace + '/motor/max') 00065 00066 self.flipped = self.min_angle_raw > self.max_angle_raw 00067 00068 self.joint_state = JointState(name=self.joint_name, motor_ids=[self.motor_id]) 00069 00070 def initialize(self): 00071 # verify that the expected motor is connected and responding 00072 available_ids = rospy.get_param('dynamixel/%s/connected_ids' % self.port_namespace, []) 00073 if not self.motor_id in available_ids: 00074 rospy.logwarn('The specified motor id is not connected and responding.') 00075 rospy.logwarn('Available ids: %s' % str(available_ids)) 00076 rospy.logwarn('Specified id: %d' % self.motor_id) 00077 return False 00078 00079 self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.motor_id)) 00080 self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.motor_id)) 00081 00082 if self.flipped: 00083 self.min_angle = (self.initial_position_raw - self.min_angle_raw) * self.RADIANS_PER_ENCODER_TICK 00084 self.max_angle = (self.initial_position_raw - self.max_angle_raw) * self.RADIANS_PER_ENCODER_TICK 00085 else: 00086 self.min_angle = (self.min_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK 00087 self.max_angle = (self.max_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK 00088 00089 self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.motor_id)) 00090 self.MAX_POSITION = self.ENCODER_RESOLUTION - 1 00091 self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.motor_id)) 00092 self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.motor_id)) 00093 self.MIN_VELOCITY = self.VELOCITY_PER_TICK 00094 00095 if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope) 00096 if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin) 00097 if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch) 00098 if self.torque_limit is not None: self.set_torque_limit(self.torque_limit) 00099 00100 self.joint_max_speed = rospy.get_param(self.controller_namespace + '/joint_max_speed', self.MAX_VELOCITY) 00101 00102 if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY 00103 elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY 00104 00105 if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY 00106 elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed 00107 00108 self.set_speed(self.joint_speed) 00109 00110 return True 00111 00112 def pos_rad_to_raw(self, pos_rad): 00113 if pos_rad < self.min_angle: pos_rad = self.min_angle 00114 elif pos_rad > self.max_angle: pos_rad = self.max_angle 00115 return self.rad_to_raw(pos_rad, self.initial_position_raw, self.flipped, self.ENCODER_TICKS_PER_RADIAN) 00116 00117 def spd_rad_to_raw(self, spd_rad): 00118 if spd_rad < self.MIN_VELOCITY: spd_rad = self.MIN_VELOCITY 00119 elif spd_rad > self.joint_max_speed: spd_rad = self.joint_max_speed 00120 # velocity of 0 means maximum, make sure that doesn't happen 00121 return max(1, int(round(spd_rad / self.VELOCITY_PER_TICK))) 00122 00123 def set_torque_enable(self, torque_enable): 00124 mcv = (self.motor_id, torque_enable) 00125 self.dxl_io.set_multi_torque_enabled([mcv]) 00126 00127 def set_speed(self, speed): 00128 mcv = (self.motor_id, self.spd_rad_to_raw(speed)) 00129 self.dxl_io.set_multi_speed([mcv]) 00130 00131 def set_compliance_slope(self, slope): 00132 if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE 00133 elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE 00134 mcv = (self.motor_id, slope, slope) 00135 self.dxl_io.set_multi_compliance_slopes([mcv]) 00136 00137 def set_compliance_margin(self, margin): 00138 if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN 00139 elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN 00140 else: margin = int(margin) 00141 mcv = (self.motor_id, margin, margin) 00142 self.dxl_io.set_multi_compliance_margins([mcv]) 00143 00144 def set_compliance_punch(self, punch): 00145 if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH 00146 elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH 00147 else: punch = int(punch) 00148 mcv = (self.motor_id, punch) 00149 self.dxl_io.set_multi_punch([mcv]) 00150 00151 def set_torque_limit(self, max_torque): 00152 if max_torque > 1: max_torque = 1.0 # use all torque motor can provide 00153 elif max_torque < 0: max_torque = 0.0 # turn off motor torque 00154 raw_torque_val = int(DXL_MAX_TORQUE_TICK * max_torque) 00155 mcv = (self.motor_id, raw_torque_val) 00156 self.dxl_io.set_multi_torque_limit([mcv]) 00157 00158 def process_motor_states(self, state_list): 00159 if self.running: 00160 state = filter(lambda state: state.id == self.motor_id, state_list.motor_states) 00161 if state: 00162 state = state[0] 00163 self.joint_state.motor_temps = [state.temperature] 00164 self.joint_state.goal_pos = self.raw_to_rad(state.goal, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK) 00165 self.joint_state.current_pos = self.raw_to_rad(state.position, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK) 00166 self.joint_state.error = state.error * self.RADIANS_PER_ENCODER_TICK 00167 self.joint_state.velocity = (state.speed / DXL_MAX_SPEED_TICK) * self.MAX_VELOCITY 00168 self.joint_state.load = state.load 00169 self.joint_state.is_moving = state.moving 00170 self.joint_state.header.stamp = rospy.Time.from_sec(state.timestamp) 00171 00172 self.joint_state_pub.publish(self.joint_state) 00173 00174 def process_command(self, msg): 00175 angle = msg.data 00176 mcv = (self.motor_id, self.pos_rad_to_raw(angle)) 00177 self.dxl_io.set_multi_position([mcv]) 00178