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