19 import moveit_commander
20 import geometry_msgs.msg
22 from tf.transformations
import quaternion_from_euler
26 rospy.init_node(
"crane_x7_pick_and_place_controller")
27 robot = moveit_commander.RobotCommander()
28 arm = moveit_commander.MoveGroupCommander(
"arm")
29 arm.set_max_velocity_scaling_factor(0.1)
30 arm.set_max_acceleration_scaling_factor(1.0)
31 gripper = moveit_commander.MoveGroupCommander(
"gripper")
33 while len([s
for s
in rosnode.get_node_names()
if 'rviz' in s]) == 0:
38 print(robot.get_group_names())
40 print(
"Current state:")
41 print(robot.get_current_state())
44 arm_initial_pose = arm.get_current_pose().pose
45 print(
"Arm initial pose:")
46 print(arm_initial_pose)
49 gripper.set_joint_value_target([0.9, 0.9])
53 arm.set_named_target(
"home")
55 gripper.set_joint_value_target([0.7, 0.7])
59 target_pose = geometry_msgs.msg.Pose()
60 target_pose.position.x = 0.2
61 target_pose.position.y = 0.0
62 target_pose.position.z = 0.3
63 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
64 target_pose.orientation.x = q[0]
65 target_pose.orientation.y = q[1]
66 target_pose.orientation.z = q[2]
67 target_pose.orientation.w = q[3]
68 arm.set_pose_target(target_pose)
72 gripper.set_joint_value_target([0.7, 0.7])
76 target_pose = geometry_msgs.msg.Pose()
77 target_pose.position.x = 0.2
78 target_pose.position.y = 0.0
79 target_pose.position.z = 0.13
80 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
81 target_pose.orientation.x = q[0]
82 target_pose.orientation.y = q[1]
83 target_pose.orientation.z = q[2]
84 target_pose.orientation.w = q[3]
85 arm.set_pose_target(target_pose)
89 gripper.set_joint_value_target([0.4, 0.4])
93 target_pose = geometry_msgs.msg.Pose()
94 target_pose.position.x = 0.2
95 target_pose.position.y = 0.0
96 target_pose.position.z = 0.3
97 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
98 target_pose.orientation.x = q[0]
99 target_pose.orientation.y = q[1]
100 target_pose.orientation.z = q[2]
101 target_pose.orientation.w = q[3]
102 arm.set_pose_target(target_pose)
106 target_pose = geometry_msgs.msg.Pose()
107 target_pose.position.x = 0.2
108 target_pose.position.y = 0.2
109 target_pose.position.z = 0.3
110 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
111 target_pose.orientation.x = q[0]
112 target_pose.orientation.y = q[1]
113 target_pose.orientation.z = q[2]
114 target_pose.orientation.w = q[3]
115 arm.set_pose_target(target_pose)
119 target_pose = geometry_msgs.msg.Pose()
120 target_pose.position.x = 0.2
121 target_pose.position.y = 0.2
122 target_pose.position.z = 0.13
123 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
124 target_pose.orientation.x = q[0]
125 target_pose.orientation.y = q[1]
126 target_pose.orientation.z = q[2]
127 target_pose.orientation.w = q[3]
128 arm.set_pose_target(target_pose)
132 gripper.set_joint_value_target([0.7, 0.7])
136 target_pose = geometry_msgs.msg.Pose()
137 target_pose.position.x = 0.2
138 target_pose.position.y = 0.2
139 target_pose.position.z = 0.2
140 q = quaternion_from_euler(-3.14, 0.0, -3.14/2.0)
141 target_pose.orientation.x = q[0]
142 target_pose.orientation.y = q[1]
143 target_pose.orientation.z = q[2]
144 target_pose.orientation.w = q[3]
145 arm.set_pose_target(target_pose)
149 arm.set_named_target(
"home")
155 if __name__ ==
'__main__':
158 if not rospy.is_shutdown():
160 except rospy.ROSInterruptException: