sr_right_hand_arm_ef_pos.py
Go to the documentation of this file.
1 #!/usr/bin/env python
2 # Copyright 2020 Shadow Robot Company Ltd.
3 #
4 # This program is free software: you can redistribute it and/or modify it
5 # under the terms of the GNU General Public License as published by the Free
6 # Software Foundation version 2 of the License.
7 #
8 # This program is distributed in the hope that it will be useful, but WITHOUT
9 # ANY WARRANTY; without even the implied warranty of MERCHANTABILITY or
10 # FITNESS FOR A PARTICULAR PURPOSE. See the GNU General Public License for
11 # more details.
12 #
13 # You should have received a copy of the GNU General Public License along
14 # with this program. If not, see <http://www.gnu.org/licenses/>.
15 
16 # This example demonstrates some of the functions of the arm commander using poses.
17 # The arm is moved through a sequence of goals generated via different pose functions in the commander.
18 # A pose can be a PoseStamped message,
19 # or a list of 6 floats: [x, y, z, rot_x, rot_y, rot_z],
20 # or a list of 7 floats [x, y, z, qx, qy, qz, qw]
21 # PLEASE NOTE: move_to_joint_value_target_unsafe is used in this script, so collision checks
22 # between the hand and arm are not made!
23 
24 # For more information, please see:
25 # https://dexterous-hand.readthedocs.io/en/latest/user_guide/2_software_description.html#robot-commander
26 
27 # roslaunch commands used with this script to launch the robot:
28 # real robot with a NUC (or a separate computer with an RT kernel):
29 # roslaunch sr_robot_launch sr_right_ur10arm_hand.launch
30 # external_control_loop:=true sim:=false scene:=true
31 # simulated robot:
32 # roslaunch sr_robot_launch sr_right_ur10arm_hand.launch sim:=true scene:=true
33 
34 # It is recommended to run this script in simulation first.
35 
36 import rospy
37 import sys
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
41 
42 rospy.init_node("right_hand_arm_ef_pos", anonymous=True)
43 
44 # The constructors for the SrArmCommander, SrHandCommander and SrRobotCommander
45 # take a name parameter that should match the group name of the robot to be used.
46 # How to command the arm separately
47 arm_commander = SrArmCommander(name="right_arm")
48 # How to command the arm and hand together
49 robot_commander = SrRobotCommander(name="right_arm_and_hand")
50 arm_commander.set_max_velocity_scaling_factor(0.1)
51 
52 rospy.sleep(2.0)
53 
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}
57 
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}
67 
68 example_goal_1 = [0.9, 0.16, 0.95, -0.99, 8.27, -0.0, 1.4]
69 
70 example_goal_2 = [0.7, 0.16, 0.95, -0.99, 8.27, -0.0, 1.4]
71 
72 # Evaluate the plan quality from starting position of robot.
73 # https://github.com/shadow-robot/sr_interface/blob/melodic-devel/sr_robot_commander/src/sr_robot_commander/sr_robot_commander.py#L263-L310
74 # This is to confirm that the arm is in a safe place to move to the home joints goal,
75 # if the outcome is poor please refer to the readthedocs of where the start arm home position is.
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)
79 
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 ...")
86 
87 # Execute arm to home plan
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)
90 rospy.sleep(2.0)
91 
92 # The arm commander generates a plan to a new pose before the pose is executed.
93 # https://github.com/shadow-robot/sr_interface/blob/melodic-devel/sr_robot_commander/src/sr_robot_commander/sr_robot_commander.py#L668
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.")
98 # Can only execute if a plan has been generated.
99 arm_commander.execute()
100 rospy.sleep(2.0)
101 
102 # Here a pose is provided and the arm commander moves the arm to it
103 # https://github.com/shadow-robot/sr_interface/blob/melodic-devel/sr_robot_commander/src/sr_robot_commander/sr_robot_commander.py#L655
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)
107 rospy.sleep(2.0)
108 
109 # Finish arm at home and hand at pack
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)
113 rospy.sleep(3.0)


sr_example
Author(s): Ugo Cupcic
autogenerated on Mon Feb 28 2022 23:52:10