Go to the documentation of this file.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__ = 'Cody Jorgensen'
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 from dynamixel_driver.dynamixel_const import *
00052 from dynamixel_controllers.joint_controller import JointController
00053
00054 from dynamixel_msgs.msg import JointState
00055 from std_msgs.msg import Float64
00056
00057 class JointTorqueController(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 self.last_commanded_torque = 0.0
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
00075 if not self.motor_id in available_ids:
00076 rospy.logwarn('The specified motor id is not connected and responding.')
00077 rospy.logwarn('Available ids: %s' % str(available_ids))
00078 rospy.logwarn('Specified id: %d' % self.motor_id)
00079 return False
00080
00081 self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.motor_id))
00082 self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.motor_id))
00083
00084 if self.flipped:
00085 self.min_angle = (self.initial_position_raw - self.min_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00086 self.max_angle = (self.initial_position_raw - self.max_angle_raw) * self.RADIANS_PER_ENCODER_TICK
00087 else:
00088 self.min_angle = (self.min_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00089 self.max_angle = (self.max_angle_raw - self.initial_position_raw) * self.RADIANS_PER_ENCODER_TICK
00090
00091 self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.motor_id))
00092 self.MAX_POSITION = self.ENCODER_RESOLUTION - 1
00093 self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.motor_id))
00094 self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.motor_id))
00095 self.MIN_VELOCITY = self.VELOCITY_PER_TICK
00096
00097 if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope)
00098 if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin)
00099 if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch)
00100 if self.torque_limit is not None: self.set_torque_limit(self.torque_limit)
00101
00102 self.joint_max_speed = rospy.get_param(self.controller_namespace + '/joint_max_speed', self.MAX_VELOCITY)
00103
00104 if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY
00105 elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY
00106
00107 if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY
00108 elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed
00109
00110 self.set_speed(0.0)
00111
00112 return True
00113
00114 def spd_rad_to_raw(self, spd_rad):
00115 if spd_rad < -self.joint_max_speed: spd_rad = -self.joint_max_speed
00116 elif spd_rad > self.joint_max_speed: spd_rad = self.joint_max_speed
00117 self.last_commanded_torque = spd_rad
00118 return int(round(spd_rad / self.VELOCITY_PER_TICK))
00119
00120 def set_torque_enable(self, torque_enable):
00121 mcv = (self.motor_id, torque_enable)
00122 self.dxl_io.set_multi_torque_enabled([mcv])
00123
00124 def set_speed(self, speed):
00125 mcv = (self.motor_id, self.spd_rad_to_raw(speed))
00126 self.dxl_io.set_multi_speed([mcv])
00127
00128 def set_compliance_slope(self, slope):
00129 if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
00130 elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
00131 mcv = (self.motor_id, slope, slope)
00132 self.dxl_io.set_multi_compliance_slopes([mcv])
00133
00134 def set_compliance_margin(self, margin):
00135 if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN
00136 elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN
00137 else: margin = int(margin)
00138 mcv = (self.motor_id, margin, margin)
00139 self.dxl_io.set_multi_compliance_margins([mcv])
00140
00141 def set_compliance_punch(self, punch):
00142 if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH
00143 elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH
00144 else: punch = int(punch)
00145 mcv = (self.motor_id, punch)
00146 self.dxl_io.set_multi_punch([mcv])
00147
00148 def set_torque_limit(self, max_torque):
00149 if max_torque > 1: max_torque = 1.0
00150 elif max_torque < 0: max_torque = 0.0
00151 raw_torque_val = int(DXL_MAX_TORQUE_TICK * max_torque)
00152 mcv = (self.motor_id, raw_torque_val)
00153 self.dxl_io.set_multi_torque_limit([mcv])
00154
00155 def process_motor_states(self, state_list):
00156 if self.running:
00157 state = filter(lambda state: state.id == self.motor_id, state_list.motor_states)
00158 if state:
00159 state = state[0]
00160 self.joint_state.motor_temps = [state.temperature]
00161 self.joint_state.goal_pos = self.last_commanded_torque
00162 self.joint_state.current_pos = self.raw_to_rad(state.position, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
00163 self.joint_state.error = 0.0
00164 self.joint_state.velocity = (state.speed / DXL_MAX_SPEED_TICK) * self.MAX_VELOCITY
00165 self.joint_state.load = state.load
00166 self.joint_state.is_moving = state.moving
00167 self.joint_state.header.stamp = rospy.Time.from_sec(state.timestamp)
00168
00169 self.joint_state_pub.publish(self.joint_state)
00170
00171 def process_command(self, msg):
00172 self.set_speed(msg.data)
00173