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 roslib
00048 roslib.load_manifest('dynamixel_controllers')
00049
00050 import rospy
00051
00052 from dynamixel_driver.dynamixel_const import *
00053 from dynamixel_driver.dynamixel_ros_commands import *
00054 from dynamixel_controllers.joint_controller import JointController
00055
00056 from dynamixel_msgs.msg import JointState
00057
00058 class JointPositionControllerDual(JointController):
00059 def __init__(self, out_cb, param_path, port_name):
00060 JointController.__init__(self, out_cb, param_path, port_name)
00061
00062 self.master_id = rospy.get_param(self.topic_name + '/motor_master/id')
00063 self.master_initial_position_raw = rospy.get_param(self.topic_name + '/motor_master/init')
00064 self.master_min_angle_raw = rospy.get_param(self.topic_name + '/motor_master/min')
00065 self.master_max_angle_raw = rospy.get_param(self.topic_name + '/motor_master/max')
00066
00067 self.slave_id = rospy.get_param(self.topic_name + '/motor_slave/id')
00068 self.slave_offset = rospy.get_param(self.topic_name + '/motor_slave/calibration_offset', 0)
00069
00070 self.flipped = self.master_min_angle_raw > self.master_max_angle_raw
00071
00072 self.joint_state = JointState(name=self.joint_name, motor_ids=[self.master_id, self.slave_id])
00073
00074 def initialize(self):
00075
00076 available_ids = rospy.get_param('dynamixel/%s/connected_ids' % self.port_namespace, [])
00077 if not (self.master_id in available_ids and
00078 self.slave_id in available_ids):
00079 rospy.logwarn('The specified motor id is not connected and responding.')
00080 rospy.logwarn('Available ids: %s' % str(available_ids))
00081 rospy.logwarn('Specified ids: %d %d' % (self.master_id, self.slave_id))
00082 return False
00083
00084 self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.master_id))
00085 self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.master_id))
00086
00087 if self.flipped:
00088 self.master_min_angle = (self.master_initial_position_raw - self.master_min_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00089 self.master_max_angle = (self.master_initial_position_raw - self.master_max_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00090 else:
00091 self.master_min_angle = (self.master_min_angle_raw - self.master_initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00092 self.master_max_angle = (self.master_max_angle_raw - self.master_initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00093
00094 self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.master_id))
00095 self.MAX_POSITION = self.ENCODER_RESOLUTION - 1
00096 self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.master_id))
00097 self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.master_id))
00098 self.MIN_VELOCITY = self.VELOCITY_PER_TICK
00099
00100 if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope)
00101 if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin)
00102 if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch)
00103 if self.torque_limit is not None: self.set_torque_limit(self.torque_limit)
00104
00105 self.joint_max_speed = rospy.get_param(self.topic_name + '/joint_max_speed', self.MAX_VELOCITY)
00106
00107 if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY
00108 elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY
00109
00110 if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY
00111 elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed
00112
00113 self.set_speed(self.joint_speed)
00114
00115 return True
00116
00117 def set_torque_enable(self, torque_enable):
00118 mcv_master = (self.master_id, torque_enable)
00119 mcv_slave = (self.slave_id, torque_enable)
00120 self.send_packet_callback((DXL_SET_TORQUE_ENABLE, [mcv_master, mcv_slave]))
00121
00122 def set_speed(self, speed):
00123 if speed < self.MIN_VELOCITY: speed = self.MIN_VELOCITY
00124 elif speed > self.joint_max_speed: speed = self.joint_max_speed
00125 speed_raw = int(round(speed / self.VELOCITY_PER_TICK))
00126 mcv_master = (self.master_id, speed_raw if speed_raw > 0 else 1)
00127 mcv_slave = (self.slave_id, mcv_master[1])
00128 self.send_packet_callback((DXL_SET_GOAL_SPEED, [mcv_master, mcv_slave]))
00129
00130 def set_compliance_slope(self, slope):
00131 if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
00132 elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
00133 slope2 = (slope << 8) + slope
00134 mcv_master = (self.master_id, slope2)
00135 mcv_slave = (self.slave_id, slope2)
00136 self.send_packet_callback((DXL_SET_COMPLIANCE_SLOPES, [mcv_master, mcv_slave]))
00137
00138 def set_compliance_margin(self, margin):
00139 if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN
00140 elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN
00141 else: margin = int(margin)
00142 margin2 = (margin << 8) + margin
00143 mcv_master = (self.master_id, margin2)
00144 mcv_slave = (self.slave_id, margin2)
00145 self.send_packet_callback((DXL_SET_COMPLIANCE_MARGINS, [mcv_master, mcv_slave]))
00146
00147 def set_compliance_punch(self, punch):
00148 if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH
00149 elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH
00150 else: punch = int(punch)
00151 mcv_master = (self.master_id, punch)
00152 mcv_slave = (self.slave_id, punch)
00153 self.send_packet_callback((DXL_SET_PUNCH, [mcv_master, mcv_slave]))
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_master = (self.master_id, raw_torque_val)
00160 mcv_slave = (self.slave_id, raw_torque_val)
00161 self.send_packet_callback((DXL_SET_TORQUE_LIMIT, [mcv_master, mcv_slave]))
00162
00163 def process_motor_states(self, state_list):
00164 if self.running:
00165 states = {}
00166
00167 for state in state_list.motor_states:
00168 if state.id in [self.master_id, self.slave_id]: states[state.id] = state
00169
00170 if states:
00171 state = states[self.master_id]
00172 self.joint_state.motor_temps = [state.temperature, states[self.slave_id].temperature]
00173 self.joint_state.goal_pos = self.raw_to_rad(state.goal, self.master_initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
00174 self.joint_state.current_pos = self.raw_to_rad(state.position, self.master_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 / DXL_MAX_SPEED_TICK) * self.MAX_VELOCITY
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 if angle < self.master_min_angle: angle = self.master_min_angle
00186 elif angle > self.master_max_angle: angle = self.master_max_angle
00187 mcv_master = (self.master_id, self.rad_to_raw(angle, self.master_initial_position_raw, self.flipped, self.ENCODER_TICKS_PER_RADIAN))
00188 mcv_slave = [self.slave_id, self.MAX_POSITION - mcv_master[1] + self.slave_offset]
00189 if mcv_slave[1] < 0: mcv_slave[1] = 0
00190 elif mcv_slave[1] > self.MAX_POSITION: mcv_slave[1] = self.MAX_POSITION
00191 self.send_packet_callback((DXL_SET_GOAL_POSITION, [mcv_master, mcv_slave]))
00192