19 import moveit_commander
20 import geometry_msgs.msg
23 from tf.transformations
import quaternion_from_euler
24 from control_msgs.msg
import (GripperCommandAction, GripperCommandGoal)
28 rospy.init_node(
"sciurus17_pick_and_place_controller")
29 robot = moveit_commander.RobotCommander()
30 arm = moveit_commander.MoveGroupCommander(
"r_arm_waist_group")
31 arm.set_max_velocity_scaling_factor(0.1)
33 gripper.wait_for_server()
34 gripper_goal = GripperCommandGoal()
35 gripper_goal.command.max_effort = 2.0
40 print(robot.get_group_names())
42 print(
"Current state:")
43 print(robot.get_current_state())
47 arm_initial_pose = arm.get_current_pose().pose
48 print(
"Arm initial pose:")
49 print(arm_initial_pose)
53 gripper_goal.command.position = 0.9
54 gripper.send_goal(gripper_goal)
55 gripper.wait_for_result(rospy.Duration(1.0))
59 arm.set_named_target(
"r_arm_waist_init_pose")
61 gripper_goal.command.position = 0.0
62 gripper.send_goal(gripper_goal)
63 gripper.wait_for_result(rospy.Duration(1.0))
67 target_pose = geometry_msgs.msg.Pose()
68 target_pose.position.x = 0.25
69 target_pose.position.y = 0.0
70 target_pose.position.z = 0.3
72 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
73 target_pose.orientation.x = q[0]
74 target_pose.orientation.y = q[1]
75 target_pose.orientation.z = q[2]
76 target_pose.orientation.w = q[3]
77 arm.set_pose_target(target_pose)
82 gripper_goal.command.position = 0.7
83 gripper.send_goal(gripper_goal)
84 gripper.wait_for_result(rospy.Duration(1.0))
88 target_pose = geometry_msgs.msg.Pose()
89 target_pose.position.x = 0.25
90 target_pose.position.y = 0.0
91 target_pose.position.z = 0.13
93 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
94 target_pose.orientation.x = q[0]
95 target_pose.orientation.y = q[1]
96 target_pose.orientation.z = q[2]
97 target_pose.orientation.w = q[3]
98 arm.set_pose_target(target_pose)
103 gripper_goal.command.position = 0.4
104 gripper.send_goal(gripper_goal)
105 gripper.wait_for_result(rospy.Duration(1.0))
109 target_pose = geometry_msgs.msg.Pose()
110 target_pose.position.x = 0.25
111 target_pose.position.y = 0.0
112 target_pose.position.z = 0.3
114 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
115 target_pose.orientation.x = q[0]
116 target_pose.orientation.y = q[1]
117 target_pose.orientation.z = q[2]
118 target_pose.orientation.w = q[3]
119 arm.set_pose_target(target_pose)
124 target_pose = geometry_msgs.msg.Pose()
125 target_pose.position.x = 0.4
126 target_pose.position.y = 0.0
127 target_pose.position.z = 0.3
129 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
130 target_pose.orientation.x = q[0]
131 target_pose.orientation.y = q[1]
132 target_pose.orientation.z = q[2]
133 target_pose.orientation.w = q[3]
134 arm.set_pose_target(target_pose)
139 target_pose = geometry_msgs.msg.Pose()
140 target_pose.position.x = 0.4
141 target_pose.position.y = 0.0
142 target_pose.position.z = 0.13
144 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
145 target_pose.orientation.x = q[0]
146 target_pose.orientation.y = q[1]
147 target_pose.orientation.z = q[2]
148 target_pose.orientation.w = q[3]
149 arm.set_pose_target(target_pose)
154 gripper_goal.command.position = 0.7
155 gripper.send_goal(gripper_goal)
156 gripper.wait_for_result(rospy.Duration(1.0))
160 target_pose = geometry_msgs.msg.Pose()
161 target_pose.position.x = 0.4
162 target_pose.position.y = 0.0
163 target_pose.position.z = 0.2
165 q = quaternion_from_euler(3.14/2.0, 0.0, 0.0)
166 target_pose.orientation.x = q[0]
167 target_pose.orientation.y = q[1]
168 target_pose.orientation.z = q[2]
169 target_pose.orientation.w = q[3]
170 arm.set_pose_target(target_pose)
175 arm.set_named_target(
"r_arm_waist_init_pose")
181 if __name__ ==
'__main__':
184 if not rospy.is_shutdown():
186 except rospy.ROSInterruptException: