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 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 rospy
00048
00049 from dynamixel_driver.dynamixel_const import *
00050 from dynamixel_controllers.joint_controller import JointController
00051
00052 from dynamixel_msgs.msg import JointState
00053
00054 class JointPositionController(JointController):
00055 def __init__(self, dxl_io, controller_namespace, port_namespace):
00056 JointController.__init__(self, dxl_io, controller_namespace, port_namespace)
00057
00058 self.motor_id = rospy.get_param(self.controller_namespace + '/motor/id')
00059 self.initial_position_raw = rospy.get_param(self.controller_namespace + '/motor/init')
00060 self.min_angle_raw = rospy.get_param(self.controller_namespace + '/motor/min')
00061 self.max_angle_raw = rospy.get_param(self.controller_namespace + '/motor/max')
00062 if rospy.has_param(self.controller_namespace + '/motor/acceleration'):
00063 self.acceleration = rospy.get_param(self.controller_namespace + '/motor/acceleration')
00064 else:
00065 self.acceleration = None
00066
00067 self.flipped = self.min_angle_raw > self.max_angle_raw
00068
00069 self.joint_state = JointState(name=self.joint_name, motor_ids=[self.motor_id])
00070
00071 def initialize(self):
00072
00073 available_ids = rospy.get_param('dynamixel/%s/connected_ids' % self.port_namespace, [])
00074 if not self.motor_id in available_ids:
00075 rospy.logwarn('The specified motor id is not connected and responding.')
00076 rospy.logwarn('Available ids: %s' % str(available_ids))
00077 rospy.logwarn('Specified id: %d' % self.motor_id)
00078 return False
00079
00080 self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.motor_id))
00081 self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.motor_id))
00082
00083 if self.flipped:
00084 self.min_angle = (self.initial_position_raw - self.min_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00085 self.max_angle = (self.initial_position_raw - self.max_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00086 else:
00087 self.min_angle = (self.min_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00088 self.max_angle = (self.max_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00089
00090 self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.motor_id))
00091 self.MAX_POSITION = self.ENCODER_RESOLUTION - 1
00092 self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.motor_id))
00093 self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.motor_id))
00094 self.MIN_VELOCITY = self.VELOCITY_PER_TICK
00095
00096 if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope)
00097 if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin)
00098 if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch)
00099 if self.torque_limit is not None: self.set_torque_limit(self.torque_limit)
00100 if self.acceleration is not None:
00101 rospy.loginfo("Setting acceleration of %d to %d" % (self.motor_id, self.acceleration))
00102 self.dxl_io.set_acceleration(self.motor_id, self.acceleration)
00103
00104 self.joint_max_speed = rospy.get_param(self.controller_namespace + '/joint_max_speed', self.MAX_VELOCITY)
00105
00106 if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY
00107 elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY
00108
00109 if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY
00110 elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed
00111
00112 self.set_speed(self.joint_speed)
00113
00114 return True
00115
00116 def pos_rad_to_raw(self, pos_rad):
00117 if pos_rad < self.min_angle: pos_rad = self.min_angle
00118 elif pos_rad > self.max_angle: pos_rad = self.max_angle
00119 return self.rad_to_raw(pos_rad, self.initial_position_raw, self.flipped, self.ENCODER_TICKS_PER_RADIAN)
00120
00121 def spd_rad_to_raw(self, spd_rad):
00122 if spd_rad < self.MIN_VELOCITY: spd_rad = self.MIN_VELOCITY
00123 elif spd_rad > self.joint_max_speed: spd_rad = self.joint_max_speed
00124
00125 return max(1, int(round(spd_rad / self.VELOCITY_PER_TICK)))
00126
00127 def set_torque_enable(self, torque_enable):
00128 mcv = (self.motor_id, torque_enable)
00129 self.dxl_io.set_multi_torque_enabled([mcv])
00130
00131 def set_speed(self, speed):
00132 mcv = (self.motor_id, self.spd_rad_to_raw(speed))
00133 self.dxl_io.set_multi_speed([mcv])
00134
00135 def set_compliance_slope(self, slope):
00136 if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
00137 elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
00138 mcv = (self.motor_id, slope, slope)
00139 self.dxl_io.set_multi_compliance_slopes([mcv])
00140
00141 def set_compliance_margin(self, margin):
00142 if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN
00143 elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN
00144 else: margin = int(margin)
00145 mcv = (self.motor_id, margin, margin)
00146 self.dxl_io.set_multi_compliance_margins([mcv])
00147
00148 def set_compliance_punch(self, punch):
00149 if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH
00150 elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH
00151 else: punch = int(punch)
00152 mcv = (self.motor_id, punch)
00153 self.dxl_io.set_multi_punch([mcv])
00154
00155 def set_torque_limit(self, max_torque):
00156 if max_torque > 1: max_torque = 1.0
00157 elif max_torque < 0: max_torque = 0.0
00158 raw_torque_val = int(DXL_MAX_TORQUE_TICK * max_torque)
00159 mcv = (self.motor_id, raw_torque_val)
00160 self.dxl_io.set_multi_torque_limit([mcv])
00161
00162 def set_acceleration_raw(self, acc):
00163 if acc < 0: acc = 0
00164 elif acc > 254: acc = 254
00165 self.dxl_io.set_acceleration(self.motor_id, acc)
00166
00167 def process_motor_states(self, state_list):
00168 if self.running:
00169 state = filter(lambda state: state.id == self.motor_id, state_list.motor_states)
00170 if state:
00171 state = state[0]
00172 self.joint_state.motor_temps = [state.temperature]
00173 self.joint_state.goal_pos = self.raw_to_rad(state.goal, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
00174 self.joint_state.current_pos = self.raw_to_rad(state.position, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
00175 self.joint_state.error = state.error * self.RADIANS_PER_ENCODER_TICK
00176 self.joint_state.velocity = state.speed * self.VELOCITY_PER_TICK
00177 self.joint_state.load = state.load
00178 self.joint_state.is_moving = state.moving
00179 self.joint_state.header.stamp = rospy.Time.from_sec(state.timestamp)
00180
00181 self.joint_state_pub.publish(self.joint_state)
00182
00183 def process_command(self, msg):
00184 angle = msg.data
00185 mcv = (self.motor_id, self.pos_rad_to_raw(angle))
00186 self.dxl_io.set_multi_position([mcv])
00187