joint_position_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__ = 'Cara Slutter'
41 
42 __license__ = 'BSD'
43 __maintainer__ = 'Antons Rebguns'
44 __email__ = 'anton@email.arizona.edu'
45 
46 
47 import rospy
48 
50 from dynamixel_controllers.joint_controller import JointController
51 
52 from dynamixel_msgs.msg import JointState
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  if rospy.has_param(self.controller_namespace + '/motor/acceleration'):
63  self.acceleration = rospy.get_param(self.controller_namespace + '/motor/acceleration')
64  else:
65  self.acceleration = None
66 
67  self.flipped = self.min_angle_raw > self.max_angle_raw
68 
69  self.joint_state = JointState(name=self.joint_name, motor_ids=[self.motor_id])
70 
71  def initialize(self):
72  # verify that the expected motor is connected and responding
73  available_ids = rospy.get_param('dynamixel/%s/connected_ids' % self.port_namespace, [])
74  if not self.motor_id in available_ids:
75  rospy.logwarn('The specified motor id is not connected and responding.')
76  rospy.logwarn('Available ids: %s' % str(available_ids))
77  rospy.logwarn('Specified id: %d' % self.motor_id)
78  return False
79 
80  self.RADIANS_PER_ENCODER_TICK = rospy.get_param('dynamixel/%s/%d/radians_per_encoder_tick' % (self.port_namespace, self.motor_id))
81  self.ENCODER_TICKS_PER_RADIAN = rospy.get_param('dynamixel/%s/%d/encoder_ticks_per_radian' % (self.port_namespace, self.motor_id))
82 
83  if self.flipped:
86  else:
89 
90  self.ENCODER_RESOLUTION = rospy.get_param('dynamixel/%s/%d/encoder_resolution' % (self.port_namespace, self.motor_id))
92  self.VELOCITY_PER_TICK = rospy.get_param('dynamixel/%s/%d/radians_second_per_encoder_tick' % (self.port_namespace, self.motor_id))
93  self.MAX_VELOCITY = rospy.get_param('dynamixel/%s/%d/max_velocity' % (self.port_namespace, self.motor_id))
95 
96  if self.compliance_slope is not None: self.set_compliance_slope(self.compliance_slope)
97  if self.compliance_margin is not None: self.set_compliance_margin(self.compliance_margin)
98  if self.compliance_punch is not None: self.set_compliance_punch(self.compliance_punch)
99  if self.torque_limit is not None: self.set_torque_limit(self.torque_limit)
100  if self.acceleration is not None:
101  rospy.loginfo("Setting acceleration of %d to %d" % (self.motor_id, self.acceleration))
102  self.dxl_io.set_acceleration(self.motor_id, self.acceleration)
103 
104  self.joint_max_speed = rospy.get_param(self.controller_namespace + '/joint_max_speed', self.MAX_VELOCITY)
105 
106  if self.joint_max_speed < self.MIN_VELOCITY: self.joint_max_speed = self.MIN_VELOCITY
107  elif self.joint_max_speed > self.MAX_VELOCITY: self.joint_max_speed = self.MAX_VELOCITY
108 
109  if self.joint_speed < self.MIN_VELOCITY: self.joint_speed = self.MIN_VELOCITY
110  elif self.joint_speed > self.joint_max_speed: self.joint_speed = self.joint_max_speed
111 
112  self.set_speed(self.joint_speed)
113 
114  return True
115 
116  def pos_rad_to_raw(self, pos_rad):
117  if pos_rad < self.min_angle: pos_rad = self.min_angle
118  elif pos_rad > self.max_angle: pos_rad = self.max_angle
119  return self.rad_to_raw(pos_rad, self.initial_position_raw, self.flipped, self.ENCODER_TICKS_PER_RADIAN)
120 
121  def spd_rad_to_raw(self, spd_rad):
122  if spd_rad < self.MIN_VELOCITY: spd_rad = self.MIN_VELOCITY
123  elif spd_rad > self.joint_max_speed: spd_rad = self.joint_max_speed
124  # velocity of 0 means maximum, make sure that doesn't happen
125  return max(1, int(round(spd_rad / self.VELOCITY_PER_TICK)))
126 
127  def set_torque_enable(self, torque_enable):
128  mcv = (self.motor_id, torque_enable)
129  self.dxl_io.set_multi_torque_enabled([mcv])
130 
131  def set_speed(self, speed):
132  mcv = (self.motor_id, self.spd_rad_to_raw(speed))
133  self.dxl_io.set_multi_speed([mcv])
134 
135  def set_compliance_slope(self, slope):
136  if slope < DXL_MIN_COMPLIANCE_SLOPE: slope = DXL_MIN_COMPLIANCE_SLOPE
137  elif slope > DXL_MAX_COMPLIANCE_SLOPE: slope = DXL_MAX_COMPLIANCE_SLOPE
138  mcv = (self.motor_id, slope, slope)
139  self.dxl_io.set_multi_compliance_slopes([mcv])
140 
141  def set_compliance_margin(self, margin):
142  if margin < DXL_MIN_COMPLIANCE_MARGIN: margin = DXL_MIN_COMPLIANCE_MARGIN
143  elif margin > DXL_MAX_COMPLIANCE_MARGIN: margin = DXL_MAX_COMPLIANCE_MARGIN
144  else: margin = int(margin)
145  mcv = (self.motor_id, margin, margin)
146  self.dxl_io.set_multi_compliance_margins([mcv])
147 
148  def set_compliance_punch(self, punch):
149  if punch < DXL_MIN_PUNCH: punch = DXL_MIN_PUNCH
150  elif punch > DXL_MAX_PUNCH: punch = DXL_MAX_PUNCH
151  else: punch = int(punch)
152  mcv = (self.motor_id, punch)
153  self.dxl_io.set_multi_punch([mcv])
154 
155  def set_torque_limit(self, max_torque):
156  if max_torque > 1: max_torque = 1.0 # use all torque motor can provide
157  elif max_torque < 0: max_torque = 0.0 # turn off motor torque
158  raw_torque_val = int(DXL_MAX_TORQUE_TICK * max_torque)
159  mcv = (self.motor_id, raw_torque_val)
160  self.dxl_io.set_multi_torque_limit([mcv])
161 
162  def set_acceleration_raw(self, acc):
163  if acc < 0: acc = 0
164  elif acc > 254: acc = 254
165  self.dxl_io.set_acceleration(self.motor_id, acc)
166 
167  def process_motor_states(self, state_list):
168  if self.running:
169  state = filter(lambda state: state.id == self.motor_id, state_list.motor_states)
170  if state:
171  state = state[0]
172  self.joint_state.motor_temps = [state.temperature]
173  self.joint_state.goal_pos = self.raw_to_rad(state.goal, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
174  self.joint_state.current_pos = self.raw_to_rad(state.position, self.initial_position_raw, self.flipped, self.RADIANS_PER_ENCODER_TICK)
175  self.joint_state.error = state.error * self.RADIANS_PER_ENCODER_TICK
176  self.joint_state.velocity = state.speed * self.VELOCITY_PER_TICK
177  self.joint_state.load = state.load
178  self.joint_state.is_moving = state.moving
179  self.joint_state.header.stamp = rospy.Time.from_sec(state.timestamp)
180 
181  self.joint_state_pub.publish(self.joint_state)
182 
183  def process_command(self, msg):
184  angle = msg.data
185  mcv = (self.motor_id, self.pos_rad_to_raw(angle))
186  self.dxl_io.set_multi_position([mcv])
187 
def raw_to_rad(self, raw, initial_position_raw, flipped, radians_per_encoder_tick)
def __init__(self, dxl_io, controller_namespace, port_namespace)
def rad_to_raw(self, angle, initial_position_raw, flipped, encoder_ticks_per_radian)


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