23 from sr_robot_commander.sr_hand_commander
import SrHandCommander
25 rospy.init_node(
"open_right_hand", anonymous=
True)
27 hand_commander = SrHandCommander(name=
"right_hand")
29 open_hand = {
'rh_FFJ1': 0.0,
'rh_FFJ2': 0.0,
'rh_FFJ3': 0.0,
'rh_FFJ4': 0.0,
30 'rh_MFJ1': 0.0,
'rh_MFJ2': 0.0,
'rh_MFJ3': 0.0,
'rh_MFJ4': 0.0,
31 'rh_RFJ1': 0.0,
'rh_RFJ2': 0.0,
'rh_RFJ3': 0.0,
'rh_RFJ4': 0.0,
32 'rh_LFJ1': 0.0,
'rh_LFJ2': 0.0,
'rh_LFJ3': 0.0,
'rh_LFJ4': 0.0,
'rh_LFJ5': 0.0,
33 'rh_THJ1': 0.0,
'rh_THJ2': 0.0,
'rh_THJ3': 0.0,
'rh_THJ4': 0.0,
'rh_THJ5': 0.0,
34 'rh_WRJ1': 0.0,
'rh_WRJ2': 0.0}
36 open_thumb = {
'rh_THJ1': 0.0,
'rh_THJ2': 0.0,
'rh_THJ3': 0.0,
'rh_THJ4': 1.2,
'rh_THJ5': 0.0}
39 rospy.loginfo(
"Moving thumb to open position")
40 hand_commander.move_to_joint_value_target_unsafe(open_thumb, 1.0,
False)
44 rospy.loginfo(
"Moving hand to open position")
45 hand_commander.move_to_joint_value_target_unsafe(open_hand, 2.0,
False)