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


sr_hand
Author(s): Ugo Cupcic
autogenerated on Tue Oct 13 2020 03:55:53