pickplace.py
Go to the documentation of this file.
1 #! /usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
4 from py_binding_tools import roscpp_init
5 from moveit.task_constructor import core, stages
6 from moveit_commander import PlanningSceneInterface
7 from geometry_msgs.msg import PoseStamped, TwistStamped
8 from moveit_msgs.msg import Constraints, OrientationConstraint
9 import math, time
10 
11 roscpp_init("mtc_tutorial")
12 
13 # [pickAndPlaceTut1]
14 # Specify robot parameters
15 arm = "panda_arm"
16 eef = "hand"
17 # [pickAndPlaceTut1]
18 
19 # [pickAndPlaceTut2]
20 # Specify object parameters
21 object_name = "object"
22 object_radius = 0.02
23 
24 # Start with a clear planning scene
25 psi = PlanningSceneInterface(synchronous=True)
26 psi.remove_world_object()
27 
28 # [initCollisionObject]
29 # Grasp object properties
30 objectPose = PoseStamped()
31 objectPose.header.frame_id = "world"
32 objectPose.pose.orientation.w = 1.0
33 objectPose.pose.position.x = 0.30702
34 objectPose.pose.position.y = 0.0
35 objectPose.pose.position.z = 0.285
36 # [initCollisionObject]
37 
38 # Add the grasp object to the planning scene
39 psi.add_box(object_name, objectPose, size=[0.1, 0.05, 0.03])
40 # [pickAndPlaceTut2]
41 
42 # [pickAndPlaceTut3]
43 # Create a task
44 task = core.Task()
45 task.name = "pick + place"
46 # [pickAndPlaceTut3]
47 
48 # [pickAndPlaceTut4]
49 # Start with the current state
50 task.add(stages.CurrentState("current"))
51 
52 # [initAndConfigConnect]
53 # Create a planner instance that is used to connect
54 # the current state to the grasp approach pose
55 pipeline = core.PipelinePlanner()
56 pipeline.planner = "RRTConnectkConfigDefault"
57 planners = [(arm, pipeline)]
58 
59 # Connect the two stages
60 task.add(stages.Connect("connect", planners))
61 # [initAndConfigConnect]
62 # [pickAndPlaceTut4]
63 
64 # [pickAndPlaceTut5]
65 # [initAndConfigGenerateGraspPose]
66 # The grasp generator spawns a set of possible grasp poses around the object
67 grasp_generator = stages.GenerateGraspPose("Generate Grasp Pose")
68 grasp_generator.angle_delta = math.pi / 2
69 grasp_generator.pregrasp = "open"
70 grasp_generator.grasp = "close"
71 grasp_generator.setMonitoredStage(task["current"]) # Generate solutions for all initial states
72 # [initAndConfigGenerateGraspPose]
73 # [pickAndPlaceTut5]
74 
75 # [pickAndPlaceTut6]
76 # [initAndConfigSimpleGrasp]
77 # SimpleGrasp container encapsulates IK calculation of arm pose as well as finger closing
78 simpleGrasp = stages.SimpleGrasp(grasp_generator, "Grasp")
79 # Set frame for IK calculation in the center between the fingers
80 ik_frame = PoseStamped()
81 ik_frame.header.frame_id = "panda_hand"
82 ik_frame.pose.position.z = 0.1034 # tcp between fingers
83 ik_frame.pose.orientation.x = 1.0 # grasp from top
84 simpleGrasp.setIKFrame(ik_frame)
85 # [initAndConfigSimpleGrasp]
86 # [pickAndPlaceTut6]
87 
88 # [pickAndPlaceTut7]
89 # [initAndConfigPick]
90 # Pick container comprises approaching, grasping (using SimpleGrasp stage), and lifting of object
91 pick = stages.Pick(simpleGrasp, "Pick")
92 pick.eef = eef
93 pick.object = object_name
94 
95 # Twist to approach the object
96 approach = TwistStamped()
97 approach.header.frame_id = "world"
98 approach.twist.linear.z = -1.0
99 pick.setApproachMotion(approach, 0.03, 0.1)
100 
101 # Twist to lift the object
102 lift = TwistStamped()
103 lift.header.frame_id = "panda_hand"
104 lift.twist.linear.z = -1.0
105 pick.setLiftMotion(lift, 0.03, 0.1)
106 # [pickAndPlaceTut7]
107 
108 # [pickAndPlaceTut8]
109 # Add the pick stage to the task's stage hierarchy
110 task.add(pick)
111 # [initAndConfigPick]
112 # [pickAndPlaceTut8]
113 
114 # Define orientation constraint to keep the object upright
115 oc = OrientationConstraint()
116 oc.parameterization = oc.ROTATION_VECTOR
117 oc.header.frame_id = "world"
118 oc.link_name = "object"
119 oc.orientation.w = 1
120 oc.absolute_x_axis_tolerance = 0.1
121 oc.absolute_y_axis_tolerance = 0.1
122 oc.absolute_z_axis_tolerance = math.pi
123 oc.weight = 1.0
124 
125 constraints = Constraints()
126 constraints.name = "object:upright"
127 constraints.orientation_constraints.append(oc)
128 
129 # [pickAndPlaceTut9]
130 # Connect the Pick stage with the following Place stage
131 con = stages.Connect("connect", planners)
132 con.path_constraints = constraints
133 task.add(con)
134 # [pickAndPlaceTut9]
135 
136 # [pickAndPlaceTut10]
137 # [initAndConfigGeneratePlacePose]
138 # Define the pose that the object should have after placing
139 placePose = objectPose
140 placePose.pose.position.x = -0.2
141 placePose.pose.position.y = -0.6
142 placePose.pose.position.z = 0.0
143 
144 # Generate Cartesian place poses for the object
145 place_generator = stages.GeneratePlacePose("Generate Place Pose")
146 place_generator.setMonitoredStage(task["Pick"])
147 place_generator.object = object_name
148 place_generator.pose = placePose
149 # [initAndConfigGeneratePlacePose]
150 # [pickAndPlaceTut10]
151 
152 # [initAndConfigSimpleUnGrasp]
153 # The SimpleUnGrasp container encapsulates releasing the object at the given Cartesian pose
154 # [pickAndPlaceTut11]
155 simpleUnGrasp = stages.SimpleUnGrasp(place_generator, "UnGrasp")
156 # [pickAndPlaceTut11]
157 
158 # [pickAndPlaceTut12]
159 # [initAndConfigPlace]
160 # Place container comprises placing, ungrasping, and retracting
161 place = stages.Place(simpleUnGrasp, "Place")
162 place.eef = eef
163 place.object = object_name
164 place.eef_frame = "panda_link8"
165 # [initAndConfigSimpleUnGrasp]
166 
167 # Twist to retract from the object
168 retract = TwistStamped()
169 retract.header.frame_id = "world"
170 retract.twist.linear.z = 1.0
171 place.setRetractMotion(retract, 0.03, 0.1)
172 
173 # Twist to place the object
174 placeMotion = TwistStamped()
175 placeMotion.header.frame_id = "panda_hand"
176 placeMotion.twist.linear.z = 1.0
177 place.setPlaceMotion(placeMotion, 0.03, 0.1)
178 
179 # Add the place pipeline to the task's hierarchy
180 task.add(place)
181 # [initAndConfigPlace]
182 # [pickAndPlaceTut12]
183 
184 # [pickAndPlaceTut13]
185 if task.plan():
186  task.publish(task.solutions[0])
187 
188 # avoid ClassLoader warning
189 del pipeline
190 del planners
191 # [pickAndPlaceTut13]
192 
193 # Prevent the program from exiting, giving you the opportunity to inspect solutions in rviz
194 time.sleep(3600)
moveit::task_constructor


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30