24 from sr_robot_commander.sr_arm_commander
import SrArmCommander
25 from sr_robot_commander.sr_hand_commander
import SrHandCommander
28 rospy.init_node(
"basic_hand_arm_example", anonymous=
True)
30 hand_commander = SrHandCommander()
31 arm_commander = SrArmCommander()
35 rospy.loginfo(
"Set arm teach mode ON")
36 arm_commander.set_teach_mode(
True)
39 rospy.loginfo(
"Set arm teach mode OFF")
40 arm_commander.set_teach_mode(
False)
43 hand_joints_goal_1 = {
'rh_FFJ1': 0.35,
'rh_FFJ2': 0.0,
'rh_FFJ3': 0.0,
'rh_FFJ4': 0.0,
44 'rh_MFJ1': 0.35,
'rh_MFJ2': 0.0,
'rh_MFJ3': 0.0,
'rh_MFJ4': 0.0,
45 'rh_RFJ1': 0.35,
'rh_RFJ2': 0.0,
'rh_RFJ3': 0.0,
'rh_RFJ4': 0.0,
46 'rh_LFJ1': 0.35,
'rh_LFJ2': 0.0,
'rh_LFJ3': 0.0,
'rh_LFJ4': 0.0,
47 'rh_THJ1': 0.35,
'rh_THJ2': 0.0,
'rh_THJ3': 0.0,
'rh_THJ4': 0.0,
'rh_THJ5': 0.0}
49 hand_joints_goal_2 = {
'rh_FFJ1': 0.35,
'rh_FFJ2': 1.5707,
'rh_FFJ3': 1.5707,
'rh_FFJ4': 0.0,
50 'rh_MFJ1': 0.35,
'rh_MFJ2': 1.5707,
'rh_MFJ3': 1.5707,
'rh_MFJ4': 0.0,
51 'rh_RFJ1': 0.35,
'rh_RFJ2': 1.5707,
'rh_RFJ3': 1.5707,
'rh_RFJ4': 0.0,
52 'rh_LFJ1': 0.35,
'rh_LFJ2': 1.5707,
'rh_LFJ3': 1.5707,
'rh_LFJ4': 0.0,
53 'rh_THJ1': 0.35,
'rh_THJ2': 0.0,
'rh_THJ3': 0.0,
'rh_THJ4': 0.0,
'rh_THJ5': 0.0}
55 hand_joints_goal_3 = {
'rh_FFJ1': 0.35,
'rh_FFJ2': 0.0,
'rh_MFJ3': 0.0}
57 arm_joints_goal_1 = {
'ra_shoulder_pan_joint': 0.43,
'ra_elbow_joint': 2.12,
58 'ra_wrist_1_joint': -1.71,
'ra_wrist_2_joint': 1.48,
59 'ra_shoulder_lift_joint': -2.58,
'ra_wrist_3_joint': 1.62,
60 'rh_WRJ1': 0.0,
'rh_WRJ2': 0.0}
62 arm_joints_goal_2 = {
'ra_shoulder_pan_joint': 0.42,
'ra_elbow_joint': 1.97,
63 'ra_wrist_1_joint': -0.89,
'ra_wrist_2_joint': -0.92,
64 'ra_shoulder_lift_joint': -1.93,
'ra_wrist_3_joint': 0.71,
65 'rh_WRJ1': 0.0,
'rh_WRJ2': 0.0}
72 joint_goals = hand_joints_goal_1
73 rospy.loginfo(
"Moving hand to joint states\n" + str(joint_goals) +
"\n")
74 hand_commander.move_to_joint_value_target_unsafe(joint_goals, 1.0,
False)
77 joint_goals = arm_joints_goal_1
78 rospy.loginfo(
"Moving arm to joint states\n" + str(joint_goals) +
"\n")
79 arm_commander.move_to_joint_value_target_unsafe(joint_goals, 3.0,
True)
83 joint_goals = hand_joints_goal_2
84 rospy.loginfo(
"Moving hand to joint states\n" + str(joint_goals) +
"\n")
85 hand_commander.move_to_joint_value_target_unsafe(joint_goals, 3.0,
True)
89 joint_goals = hand_joints_goal_3
90 rospy.loginfo(
"Moving hand to joint states\n" + str(joint_goals) +
"\n")
91 hand_commander.move_to_joint_value_target_unsafe(joint_goals, 3.0,
False)
94 joint_goals = arm_joints_goal_2
95 rospy.loginfo(
"Moving arm to joint states\n" + str(joint_goals) +
"\n")
96 arm_commander.move_to_joint_value_target_unsafe(joint_goals, 3.0,
True)
99 hand_commander.set_teach_mode(
True)
102 rospy.loginfo(
"Set hand teach mode OFF")
103 hand_commander.set_teach_mode(
False)