joint_torque_controller.py
Go to the documentation of this file.
1 # -*- coding: utf-8 -*-
2 #
3 # Software License Agreement (BSD License)
4 #
5 # Copyright (c) 2010-2011, Antons Rebguns.
6 # All rights reserved.
7 #
8 # Redistribution and use in source and binary forms, with or without
9 # modification, are permitted provided that the following conditions
10 # are met:
11 #
12 # * Redistributions of source code must retain the above copyright
13 # notice, this list of conditions and the following disclaimer.
14 # * Redistributions in binary form must reproduce the above
15 # copyright notice, this list of conditions and the following
16 # disclaimer in the documentation and/or other materials provided
17 # with the distribution.
18 # * Neither the name of University of Arizona nor the names of its
19 # contributors may be used to endorse or promote products derived
20 # from this software without specific prior written permission.
21 #
22 # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23 # "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24 # LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25 # FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26 # COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27 # INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28 # BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29 # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30 # CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31 # LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32 # ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33 # POSSIBILITY OF SUCH DAMAGE.
34 
35 from __future__ import division
36 
37 
38 __author__ = 'Antons Rebguns'
39 __copyright__ = 'Copyright (c) 2010-2011 Antons Rebguns'
40 __credits__ = 'Cody Jorgensen'
41 
42 __license__ = 'BSD'
43 __maintainer__ = 'Antons Rebguns'
44 __email__ = 'anton@email.arizona.edu'
45 
46 
47 import rospy
49 from dynamixel_controllers.joint_controller import JointController
50 
51 from dynamixel_msgs.msg import JointState
52 from std_msgs.msg import Float64
53 
55  def __init__(self, dxl_io, controller_namespace, port_namespace):
56  JointController.__init__(self, dxl_io, controller_namespace, port_namespace)
57 
58  self.motor_id = rospy.get_param(self.controller_namespace + '/motor/id')
59  self.initial_position_raw = rospy.get_param(self.controller_namespace + '/motor/init')
60  self.min_angle_raw = rospy.get_param(self.controller_namespace + '/motor/min')
61  self.max_angle_raw = rospy.get_param(self.controller_namespace + '/motor/max')
62 
63  self.flipped = self.min_angle_raw > self.max_angle_raw
65 
66  self.joint_state = JointState(name=self.joint_name, motor_ids=[self.motor_id])
67 
68  def initialize(self):
69  # verify that the expected motor is connected and responding
70  available_ids = rospy.get_param('dynamixel/%s/connected_ids' % self.port_namespace, [])
71 
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)
76  return False
77 
78  self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.motor_id))
79  self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.motor_id))
80 
81  if self.flipped:
84  else:
87 
88  self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.motor_id))
90  self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.motor_id))
91  self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.motor_id))
93 
94  if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope)
95  if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin)
96  if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch)
97  if self.torque_limit is not None: self.set_torque_limit(self.torque_limit)
98 
99  self.joint_max_speed = rospy.get_param(self.controller_namespace + '/joint_max_speed', self.MAX_VELOCITY)
100 
101  if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY
102  elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY
103 
104  if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY
105  elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed
106 
107  self.set_speed(0.0)
108 
109  return True
110 
111  def spd_rad_to_raw(self, spd_rad):
112  if spd_rad < -self.joint_max_speed: spd_rad = -self.joint_max_speed
113  elif spd_rad > self.joint_max_speed: spd_rad = self.joint_max_speed
114  self.last_commanded_torque = spd_rad
115  return int(round(spd_rad / self.VELOCITY_PER_TICK))
116 
117  def set_torque_enable(self, torque_enable):
118  mcv = (self.motor_id, torque_enable)
119  self.dxl_io.set_multi_torque_enabled([mcv])
120 
121  def set_speed(self, speed):
122  mcv = (self.motor_id, self.spd_rad_to_raw(speed))
123  self.dxl_io.set_multi_speed([mcv])
124 
125  def set_compliance_slope(self, slope):
126  if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
127  elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
128  mcv = (self.motor_id, slope, slope)
129  self.dxl_io.set_multi_compliance_slopes([mcv])
130 
131  def set_compliance_margin(self, margin):
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])
137 
138  def set_compliance_punch(self, punch):
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)
142  mcv = (self.motor_id, punch)
143  self.dxl_io.set_multi_punch([mcv])
144 
145  def set_torque_limit(self, max_torque):
146  if max_torque > 1: max_torque = 1.0 # use all torque motor can provide
147  elif max_torque < 0: max_torque = 0.0 # turn off motor torque
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])
151 
152  def process_motor_states(self, state_list):
153  if self.running:
154  state = filter(lambda state: state.id == self.motor_id, state_list.motor_states)
155  if state:
156  state = state[0]
157  self.joint_state.motor_temps = [state.temperature]
158  self.joint_state.goal_pos = self.last_commanded_torque
159  self.joint_state.current_pos = self.raw_to_rad(state.position, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
160  self.joint_state.error = 0.0
161  self.joint_state.velocity = state.speed * self.VELOCITY_PER_TICK
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)
165 
166  self.joint_state_pub.publish(self.joint_state)
167 
168  def process_command(self, msg):
169  self.set_speed(msg.data)
170 
def __init__(self, dxl_io, controller_namespace, port_namespace)
def raw_to_rad(self, raw, initial_position_raw, flipped, radians_per_encoder_tick)


dynamixel_controllers
Author(s): Antons Rebguns, Cody Jorgensen, Cara Slutter
autogenerated on Tue May 12 2020 03:10:59