20 from sr_robot_msgs.msg
import sendupdate, joint
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. 30 Basic script will look like: 34 from sr_hand.shadowhand_commander import Commander 36 rospy.init_node('basic_example') 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 49 See the examples directory in the package sr_examples. 56 rospy.logwarn(
"The class Commander in package sr_hand is deprecated. " 57 "Please use SrHandCommander from package sr_robot_commander")
72 if self.
hand.check_hand_type() ==
"gazebo":
80 This call is non blocking. It will return before the motion has finished. 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) 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. 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. 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. 100 joints = dict(command)
102 interpolation_time = 0.0
103 if 'interpolation_time' in joints:
104 interpolation_time = joints[
'interpolation_time']
105 del joints[
'interpolation_time']
107 if interpolation_time == 0.0:
111 self.
hand.sendupdate_from_dict(joints)
114 args=(joints, interpolation_time)).start()
118 Remove the coinciding joints from the currently running interpolators. 119 It actually removes the joints from the 'grasp_to' list of the interpolator. 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. 126 rospy.logdebug(
"call interpolation")
127 thread_name = threading.current_thread().name
133 rospy.logdebug(
"start interpolation")
134 current_grasp =
Grasp()
135 current_grasp.joints_and_positions = self.
hand.read_all_current_positions(
137 target_grasp =
Grasp()
138 target_grasp.joints_and_positions = joints
147 targets_to_send = interpolator.interpolate(
150 self.
hand.sendupdate_from_dict(targets_to_send)
157 rospy.logdebug(
"end interpolation")
161 Remove the coinciding joints from the currently running interpolators. 162 It actually removes the joints from the 'grasp_to' list of the interpolator. 164 @param joints - Dictionary of joint names in the keys and angles in 165 degrees in the values. 168 "Call prune from thread %s", threading.current_thread().name)
170 for joint_name
in joints.keys():
172 thread_id].grasp_to.joints_and_positions.pop(joint_name,
None)
174 "Prune joint %s thread %s", joint_name, thread_id)
178 Returns a dictionary with the position of each joint in degrees. 180 return dict(self.
hand.read_all_current_positions())
184 Returns a dictionary with the velocity of each joint in degrees/s. 186 return dict(self.
hand.read_all_current_velocities())
190 Returns a dictionary with the effort of each joint. Currently in ADC units, as no calibration 191 is performed on the strain gauges. 193 return dict(self.
hand.read_all_current_efforts())
197 Returns a string indicating the type of tactile sensors present. Possible values are: PST, biotac, UBI0 . 203 Returns an object containing tactile data. The structure of the data is different for every tactile_type .
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)