5 import moveit_commander
6 import geometry_msgs.msg
9 from tf.transformations
import quaternion_from_euler
10 from control_msgs.msg
import (GripperCommandAction, GripperCommandGoal)
14 rospy.init_node(
"sciurus17_pick_and_place_controller")
15 robot = moveit_commander.RobotCommander()
16 arm = moveit_commander.MoveGroupCommander(
"l_arm_group")
17 arm.set_max_velocity_scaling_factor(0.1)
19 gripper.wait_for_server()
20 gripper_goal = GripperCommandGoal()
21 gripper_goal.command.max_effort = 2.0
26 print(robot.get_group_names())
28 print(
"Current state:")
29 print(robot.get_current_state())
32 arm_initial_pose = arm.get_current_pose().pose
33 print(
"Arm initial pose:")
34 print(arm_initial_pose)
37 gripper_goal.command.position = -0.9
38 gripper.send_goal(gripper_goal)
39 gripper.wait_for_result(rospy.Duration(1.0))
42 arm.set_named_target(
"l_arm_init_pose")
44 gripper_goal.command.position = 0.0
45 gripper.send_goal(gripper_goal)
46 gripper.wait_for_result(rospy.Duration(1.0))
49 target_pose = geometry_msgs.msg.Pose()
50 target_pose.position.x = 0.25
51 target_pose.position.y = 0.0
52 target_pose.position.z = 0.3
53 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
54 target_pose.orientation.x = q[0]
55 target_pose.orientation.y = q[1]
56 target_pose.orientation.z = q[2]
57 target_pose.orientation.w = q[3]
58 arm.set_pose_target(target_pose)
62 gripper_goal.command.position = -0.7
63 gripper.send_goal(gripper_goal)
64 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.13
71 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
72 target_pose.orientation.x = q[0]
73 target_pose.orientation.y = q[1]
74 target_pose.orientation.z = q[2]
75 target_pose.orientation.w = q[3]
76 arm.set_pose_target(target_pose)
80 gripper_goal.command.position = -0.4
81 gripper.send_goal(gripper_goal)
82 gripper.wait_for_result(rospy.Duration(1.0))
85 target_pose = geometry_msgs.msg.Pose()
86 target_pose.position.x = 0.25
87 target_pose.position.y = 0.0
88 target_pose.position.z = 0.3
89 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
90 target_pose.orientation.x = q[0]
91 target_pose.orientation.y = q[1]
92 target_pose.orientation.z = q[2]
93 target_pose.orientation.w = q[3]
94 arm.set_pose_target(target_pose)
98 target_pose = geometry_msgs.msg.Pose()
99 target_pose.position.x = 0.4
100 target_pose.position.y = 0.0
101 target_pose.position.z = 0.3
102 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
103 target_pose.orientation.x = q[0]
104 target_pose.orientation.y = q[1]
105 target_pose.orientation.z = q[2]
106 target_pose.orientation.w = q[3]
107 arm.set_pose_target(target_pose)
111 target_pose = geometry_msgs.msg.Pose()
112 target_pose.position.x = 0.4
113 target_pose.position.y = 0.0
114 target_pose.position.z = 0.13
115 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
116 target_pose.orientation.x = q[0]
117 target_pose.orientation.y = q[1]
118 target_pose.orientation.z = q[2]
119 target_pose.orientation.w = q[3]
120 arm.set_pose_target(target_pose)
124 gripper_goal.command.position = -0.7
125 gripper.send_goal(gripper_goal)
126 gripper.wait_for_result(rospy.Duration(1.0))
129 target_pose = geometry_msgs.msg.Pose()
130 target_pose.position.x = 0.4
131 target_pose.position.y = 0.0
132 target_pose.position.z = 0.2
133 q = quaternion_from_euler(-3.14/2.0, 0.0, 0.0)
134 target_pose.orientation.x = q[0]
135 target_pose.orientation.y = q[1]
136 target_pose.orientation.z = q[2]
137 target_pose.orientation.w = q[3]
138 arm.set_pose_target(target_pose)
142 arm.set_named_target(
"l_arm_init_pose")
148 if __name__ ==
'__main__':
151 if not rospy.is_shutdown():
153 except rospy.ROSInterruptException: