shadowhand_commander.py
Go to the documentation of this file.
1 #!/usr/bin/python
2 
3 # Copyright 2014 Shadow Robot Company Ltd.
4 #
5 # This program is free software: you can redistribute it and/or modify it
6 # under the terms of the GNU General Public License as published by the Free
7 # Software Foundation version 2 of the License.
8 #
9 # This program is distributed in the hope that it will be useful, but WITHOUT
10 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
11 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
12 # more details.
13 #
14 # You should have received a copy of the GNU General Public License along
15 # with this program. If not, see <http://www.gnu.org/licenses/>.
16 
17 import rospy
18 import threading
19 
20 from sr_robot_msgs.msg import sendupdate, joint
21 from sr_hand.shadowhand_ros import ShadowHand_ROS
22 from sr_hand.grasps_interpoler import GraspInterpoler
23 from sr_hand.Grasp import Grasp
24 
25 """
26 Module to provide a quick and easy way to script the Shadow Hand.
27 This is done via creating a short script with a Commander object then calling
28 methods on the commander to script the motion.
29 
30 Basic script will look like:
31 
32  #!/usr/bin/python
33  import rospy
34  from sr_hand.shadowhand_commander import Commander
35 
36  rospy.init_node('basic_example')
37  c = Commander()
38 
39  c.move_hand({
40  "THJ1": 0, "THJ2": 6, "THJ3": 10, "THJ4": 37, "THJ5": 9,
41  "FFJ0": 21, "FFJ3": 26, "FFJ4": 0,
42  "MFJ0": 18, "MFJ3": 24, "MFJ4": 0,
43  "RFJ0": 30, "RFJ3": 16, "RFJ4": 0,
44  "LFJ0": 30, "LFJ3": 0, "LFJ4": -10, "LFJ5": 10
45  })
46  rospy.sleep(3.0)
47 
48 
49 See the examples directory in the package sr_examples.
50 """
51 
52 
53 class Commander(object):
54 
55  def __init__(self):
56  rospy.logwarn("The class Commander in package sr_hand is deprecated. "
57  "Please use SrHandCommander from package sr_robot_commander")
58 
59  # Mutex to control thread access to certain operations
60  self.mutex = threading.Lock()
61 
62  # This is used to store the grasp interpolators for the different
63  # threads.
65 
66  # Shadow hand setup
68 
69  # Period in seconds between interpolated commands (e.g. if we want an interpolation
70  # time of 1s and have a period of 0.1, the interpoler will use 10 steps
72  if self.hand.check_hand_type() == "gazebo":
73  # Interpolation is slower under simulation compared to real hand
74  self.hand_interpolation_period = 0.1
75 
76  def move_hand(self, command):
77  """
78  Move the Shadow Hand.
79 
80  This call is non blocking. It will return before the motion has finished.
81 
82  If called with interpolation time of 0.0 the joints will move to the target position
83  at maximum velocity (i.e. the max. vel. allowed by the position controller for that joint)
84 
85  If called with interpolation time greater than self.hand_interpolation_period,
86  a separate thread will deal with the interpolation time and will keep
87  sending targets to the hand until the last target is sent.
88 
89  If move_hand() is called again before the previous movements have finished,
90  the new call will override only the conciding joints. The others will keep moving
91  to their previous targets at their previous velocity.
92 
93  @param command - Dictionary of joint names in the keys and angles in
94  degrees in the values. The key interpolation_time gives the time in seconds that
95  the movement will last.
96  """
97 
98  # Copy the dictionary, so that we will not affect the original user
99  # command
100  joints = dict(command)
101 
102  interpolation_time = 0.0
103  if 'interpolation_time' in joints:
104  interpolation_time = joints['interpolation_time']
105  del joints['interpolation_time']
106 
107  if interpolation_time == 0.0:
108  self.mutex.acquire()
109  self._prune_interpolators(joints)
110  self.mutex.release()
111  self.hand.sendupdate_from_dict(joints)
112  else:
113  threading.Thread(target=self._move_hand_interpolation,
114  args=(joints, interpolation_time)).start()
115 
116  def _move_hand_interpolation(self, joints, interpolation_time=1.0):
117  """
118  Remove the coinciding joints from the currently running interpolators.
119  It actually removes the joints from the 'grasp_to' list of the interpolator.
120 
121  @param joints - Dictionary of joint names in the keys and angles in
122  degrees in the values.
123  @param interpolation_time - A float. Interpolation time in seconds.
124  """
125 
126  rospy.logdebug("call interpolation")
127  thread_name = threading.current_thread().name
128  try:
129  self.mutex.acquire()
130  self._prune_interpolators(joints)
131  self.mutex.release()
132 
133  rospy.logdebug("start interpolation")
134  current_grasp = Grasp()
135  current_grasp.joints_and_positions = self.hand.read_all_current_positions(
136  )
137  target_grasp = Grasp()
138  target_grasp.joints_and_positions = joints
139 
140  interpolator = GraspInterpoler(current_grasp, target_grasp)
141  self.grasp_interpolators[thread_name] = interpolator
142 
143  r = rospy.Rate(1.0 / self.hand_interpolation_period)
144 
145  for interpolation in range(1, int(interpolation_time / self.hand_interpolation_period) + 1):
146  self.mutex.acquire()
147  targets_to_send = interpolator.interpolate(
148  100.0 * interpolation * self.hand_interpolation_period / interpolation_time)
149  self.mutex.release()
150  self.hand.sendupdate_from_dict(targets_to_send)
151  # rospy.loginfo("sent cmd n: %s" %(str(interpolation), ))
152  r.sleep()
153  finally:
154  self.mutex.acquire()
155  self.grasp_interpolators.pop(thread_name, None)
156  self.mutex.release()
157  rospy.logdebug("end interpolation")
158 
159  def _prune_interpolators(self, joints):
160  """
161  Remove the coinciding joints from the currently running interpolators.
162  It actually removes the joints from the 'grasp_to' list of the interpolator.
163 
164  @param joints - Dictionary of joint names in the keys and angles in
165  degrees in the values.
166  """
167  rospy.logdebug(
168  "Call prune from thread %s", threading.current_thread().name)
169  for thread_id in self.grasp_interpolators.keys():
170  for joint_name in joints.keys():
171  self.grasp_interpolators[
172  thread_id].grasp_to.joints_and_positions.pop(joint_name, None)
173  rospy.logdebug(
174  "Prune joint %s thread %s", joint_name, thread_id)
175 
176  def get_hand_position(self):
177  """
178  Returns a dictionary with the position of each joint in degrees.
179  """
180  return dict(self.hand.read_all_current_positions())
181 
182  def get_hand_velocity(self):
183  """
184  Returns a dictionary with the velocity of each joint in degrees/s.
185  """
186  return dict(self.hand.read_all_current_velocities())
187 
188  def get_hand_effort(self):
189  """
190  Returns a dictionary with the effort of each joint. Currently in ADC units, as no calibration
191  is performed on the strain gauges.
192  """
193  return dict(self.hand.read_all_current_efforts())
194 
195  def get_tactile_type(self):
196  """
197  Returns a string indicating the type of tactile sensors present. Possible values are: PST, biotac, UBI0 .
198  """
199  return self.hand.get_tactile_type()
200 
201  def get_tactile_state(self):
202  """
203  Returns an object containing tactile data. The structure of the data is different for every tactile_type .
204  """
205  return self.hand.get_tactile_state()
def _move_hand_interpolation(self, joints, interpolation_time=1.0)


sr_hand
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:24