35 from __future__
import division
38 __author__ =
'Antons Rebguns' 39 __copyright__ =
'Copyright (c) 2010-2011 Antons Rebguns' 40 __credits__ =
'Cody Jorgensen' 43 __maintainer__ =
'Antons Rebguns' 44 __email__ =
'anton@email.arizona.edu' 51 from dynamixel_msgs.msg
import JointState
52 from std_msgs.msg
import Float64
55 def __init__(self, dxl_io, controller_namespace, port_namespace):
56 JointController.__init__(self, dxl_io, controller_namespace, port_namespace)
70 available_ids = rospy.get_param(
'dynamixel/%s/connected_ids' % self.
port_namespace, [])
72 if not self.
motor_id in available_ids:
73 rospy.logwarn(
'The specified motor id is not connected and responding.')
74 rospy.logwarn(
'Available ids: %s' % str(available_ids))
75 rospy.logwarn(
'Specified id: %d' % self.
motor_id)
118 mcv = (self.
motor_id, torque_enable)
119 self.dxl_io.set_multi_torque_enabled([mcv])
123 self.dxl_io.set_multi_speed([mcv])
126 if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
127 elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
129 self.dxl_io.set_multi_compliance_slopes([mcv])
132 if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN
133 elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN
134 else: margin = int(margin)
135 mcv = (self.
motor_id, margin, margin)
136 self.dxl_io.set_multi_compliance_margins([mcv])
139 if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH
140 elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH
141 else: punch = int(punch)
143 self.dxl_io.set_multi_punch([mcv])
146 if max_torque > 1: max_torque = 1.0
147 elif max_torque < 0: max_torque = 0.0
148 raw_torque_val = int(DXL_MAX_TORQUE_TICK * max_torque)
149 mcv = (self.
motor_id, raw_torque_val)
150 self.dxl_io.set_multi_torque_limit([mcv])
154 state = filter(
lambda state: state.id == self.
motor_id, state_list.motor_states)
157 self.joint_state.motor_temps = [state.temperature]
160 self.joint_state.error = 0.0
162 self.joint_state.load = state.load
163 self.joint_state.is_moving = state.moving
164 self.joint_state.header.stamp = rospy.Time.from_sec(state.timestamp)
def set_compliance_slope(self, slope)
def __init__(self, dxl_io, controller_namespace, port_namespace)
def raw_to_rad(self, raw, initial_position_raw, flipped, radians_per_encoder_tick)
def set_compliance_slope(self, slope)
def process_command(self, msg)
def set_compliance_punch(self, punch)
def set_speed(self, speed)
def spd_rad_to_raw(self, spd_rad)
def process_motor_states(self, state_list)
def set_compliance_margin(self, margin)
def set_torque_limit(self, max_torque)
def set_compliance_margin(self, margin)
def set_torque_enable(self, torque_enable)
def set_speed(self, speed)
def set_compliance_punch(self, punch)
def set_torque_limit(self, max_torque)