38 from trajectory_msgs.msg
import JointTrajectory, JointTrajectoryPoint
39 from sr_robot_commander.sr_robot_commander
import SrRobotCommander
40 from sr_robot_commander.sr_arm_commander
import SrArmCommander
42 rospy.init_node(
"right_hand_arm_ef_pos", anonymous=
True)
47 arm_commander = SrArmCommander(name=
"right_arm")
49 robot_commander = SrRobotCommander(name=
"right_arm_and_hand")
50 arm_commander.set_max_velocity_scaling_factor(0.1)
54 arm_home_joints_goal = {
'ra_shoulder_pan_joint': 0.00,
'ra_elbow_joint': 2.00,
55 'ra_shoulder_lift_joint': -1.25,
'ra_wrist_1_joint': -0.733,
56 'ra_wrist_2_joint': 1.5708,
'ra_wrist_3_joint': 0.00}
58 arm_hand_home_joints_goal = {
'ra_shoulder_pan_joint': 0.00,
'ra_elbow_joint': 2.00,
59 'ra_shoulder_lift_joint': -1.25,
'ra_wrist_1_joint': -0.733,
60 'ra_wrist_2_joint': 1.5708,
'ra_wrist_3_joint': 0.00,
61 'rh_THJ1': 0.52,
'rh_THJ2': 0.61,
'rh_THJ3': 0.0,
'rh_THJ4': 1.20,
62 'rh_THJ5': 0.17,
'rh_FFJ1': 1.5707,
'rh_FFJ2': 1.5707,
'rh_FFJ3': 1.5707,
63 'rh_FFJ4': 0.0,
'rh_MFJ1': 1.5707,
'rh_MFJ2': 1.5707,
'rh_MFJ3': 1.5707,
64 'rh_MFJ4': 0.0,
'rh_RFJ1': 1.5707,
'rh_RFJ2': 1.5707,
'rh_RFJ3': 1.5707,
65 'rh_RFJ4': 0.0,
'rh_LFJ1': 1.5707,
'rh_LFJ2': 1.5707,
'rh_LFJ3': 1.5707,
66 'rh_LFJ4': 0.0,
'rh_LFJ5': 0.0,
'rh_WRJ1': 0.0,
'rh_WRJ2': 0.0}
68 example_goal_1 = [0.9, 0.16, 0.95, -0.99, 8.27, -0.0, 1.4]
70 example_goal_2 = [0.7, 0.16, 0.95, -0.99, 8.27, -0.0, 1.4]
76 arm_to_home_plan = arm_commander.plan_to_joint_value_target(arm_home_joints_goal)
77 arm_to_home_plan_quality = arm_commander.evaluate_given_plan(arm_to_home_plan)
78 eval_arm_home_plan_quality = arm_commander.evaluate_plan_quality(arm_to_home_plan_quality)
80 if eval_arm_home_plan_quality !=
'good':
81 rospy.logfatal(
"Plan quality to the home position is poor! " +
82 "For safety please refer to the hand and arm documentation " +
83 "for where to start the arm " +
84 "to ensure no unexpected movements during plan and execute.")
85 sys.exit(
"Exiting script to allow for the arm to be manually moved to better start position ...")
88 rospy.loginfo(
"Planning and moving arm to home joint states\n" + str(arm_home_joints_goal) +
"\n")
89 arm_commander.execute_plan(arm_to_home_plan)
94 raw_input(
"Press Enter to continue...")
95 rospy.loginfo(
"Planning the move to the first pose:\n" + str(example_goal_1) +
"\n")
96 arm_commander.plan_to_pose_target(example_goal_1)
97 rospy.loginfo(
"Finished planning, moving the arm now.")
99 arm_commander.execute()
104 raw_input(
"Press Enter to continue...")
105 rospy.loginfo(
"Moving arm to pose:\n" + str(example_goal_2) +
"\n")
106 arm_commander.move_to_pose_target(example_goal_2, wait=
True)
110 raw_input(
"Press Enter to continue...")
111 rospy.loginfo(
"Moving arm to joint states\n" + str(arm_hand_home_joints_goal) +
"\n")
112 robot_commander.move_to_joint_value_target_unsafe(arm_hand_home_joints_goal, 6.0,
True)