21 from sr_robot_msgs.msg
import sendupdate, joint
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. 31 Basic script will look like: 35 from sr_hand.shadowhand_commander import Commander 37 rospy.init_node('basic_example') 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 50 See the examples directory in the package sr_examples. 57 rospy.logwarn(
"The class Commander in package sr_hand is deprecated. " 58 "Please use SrHandCommander from package sr_robot_commander")
73 if self.hand.check_hand_type() ==
"gazebo":
81 This call is non blocking. It will return before the motion has finished. 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) 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. 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. 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. 101 joints = dict(command)
103 interpolation_time = 0.0
104 if 'interpolation_time' in joints:
105 interpolation_time = joints[
'interpolation_time']
106 del joints[
'interpolation_time']
108 if interpolation_time == 0.0:
112 self.hand.sendupdate_from_dict(joints)
115 args=(joints, interpolation_time)).start()
119 Remove the coinciding joints from the currently running interpolators. 120 It actually removes the joints from the 'grasp_to' list of the interpolator. 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. 127 rospy.logdebug(
"call interpolation")
128 thread_name = threading.current_thread().name
134 rospy.logdebug(
"start interpolation")
135 current_grasp =
Grasp()
136 current_grasp.joints_and_positions = self.hand.read_all_current_positions(
138 target_grasp =
Grasp()
139 target_grasp.joints_and_positions = joints
148 targets_to_send = interpolator.interpolate(
151 self.hand.sendupdate_from_dict(targets_to_send)
156 self.grasp_interpolators.pop(thread_name,
None)
158 rospy.logdebug(
"end interpolation")
162 Remove the coinciding joints from the currently running interpolators. 163 It actually removes the joints from the 'grasp_to' list of the interpolator. 165 @param joints - Dictionary of joint names in the keys and angles in 166 degrees in the values. 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():
173 thread_id].grasp_to.joints_and_positions.pop(joint_name,
None)
175 "Prune joint %s thread %s", joint_name, thread_id)
179 Returns a dictionary with the position of each joint in degrees. 181 return dict(self.hand.read_all_current_positions())
185 Returns a dictionary with the velocity of each joint in degrees/s. 187 return dict(self.hand.read_all_current_velocities())
191 Returns a dictionary with the effort of each joint. Currently in ADC units, as no calibration 192 is performed on the strain gauges. 194 return dict(self.hand.read_all_current_efforts())
198 Returns a string indicating the type of tactile sensors present. Possible values are: PST, biotac, UBI0 . 200 return self.hand.get_tactile_type()
204 Returns an object containing tactile data. The structure of the data is different for every tactile_type . 206 return self.hand.get_tactile_state()
def move_hand(self, command)
def get_hand_effort(self)
def get_hand_position(self)
def get_hand_velocity(self)
hand_interpolation_period
def _move_hand_interpolation(self, joints, interpolation_time=1.0)
def _prune_interpolators(self, joints)
def get_tactile_state(self)
def get_tactile_type(self)