|
5 | 5 | from moveit.task_constructor import core, stages |
6 | 6 | from moveit_commander import PlanningSceneInterface |
7 | 7 | from geometry_msgs.msg import PoseStamped, TwistStamped |
8 | | -import time |
| 8 | +from moveit_msgs.msg import Constraints, OrientationConstraint |
| 9 | +import math, time |
9 | 10 |
|
10 | 11 | roscpp_init("mtc_tutorial") |
11 | 12 |
|
|
17 | 18 |
|
18 | 19 | # [pickAndPlaceTut2] |
19 | 20 | # Specify object parameters |
20 | | -object_name = "grasp_object" |
| 21 | +object_name = "object" |
21 | 22 | object_radius = 0.02 |
22 | 23 |
|
23 | 24 | # Start with a clear planning scene |
|
28 | 29 | # Grasp object properties |
29 | 30 | objectPose = PoseStamped() |
30 | 31 | objectPose.header.frame_id = "world" |
31 | | -objectPose.pose.orientation.x = 1.0 |
| 32 | +objectPose.pose.orientation.w = 1.0 |
32 | 33 | objectPose.pose.position.x = 0.30702 |
33 | 34 | objectPose.pose.position.y = 0.0 |
34 | 35 | objectPose.pose.position.z = 0.285 |
|
56 | 57 | planners = [(arm, pipeline)] |
57 | 58 |
|
58 | 59 | # Connect the two stages |
59 | | -task.add(stages.Connect("connect1", planners)) |
| 60 | +task.add(stages.Connect("connect", planners)) |
60 | 61 | # [initAndConfigConnect] |
61 | 62 | # [pickAndPlaceTut4] |
62 | 63 |
|
63 | 64 | # [pickAndPlaceTut5] |
64 | 65 | # [initAndConfigGenerateGraspPose] |
65 | 66 | # The grasp generator spawns a set of possible grasp poses around the object |
66 | 67 | grasp_generator = stages.GenerateGraspPose("Generate Grasp Pose") |
67 | | -grasp_generator.angle_delta = 0.2 |
| 68 | +grasp_generator.angle_delta = math.pi / 2 |
68 | 69 | grasp_generator.pregrasp = "open" |
69 | 70 | grasp_generator.grasp = "close" |
70 | 71 | grasp_generator.setMonitoredStage(task["current"]) # Generate solutions for all initial states |
|
78 | 79 | # Set frame for IK calculation in the center between the fingers |
79 | 80 | ik_frame = PoseStamped() |
80 | 81 | ik_frame.header.frame_id = "panda_hand" |
81 | | -ik_frame.pose.position.z = 0.1034 |
| 82 | +ik_frame.pose.position.z = 0.1034 # tcp between fingers |
| 83 | +ik_frame.pose.orientation.x = 1.0 # grasp from top |
82 | 84 | simpleGrasp.setIKFrame(ik_frame) |
83 | 85 | # [initAndConfigSimpleGrasp] |
84 | 86 | # [pickAndPlaceTut6] |
|
109 | 111 | # [initAndConfigPick] |
110 | 112 | # [pickAndPlaceTut8] |
111 | 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 | + |
112 | 129 | # [pickAndPlaceTut9] |
113 | 130 | # Connect the Pick stage with the following Place stage |
114 | | -task.add(stages.Connect("connect2", planners)) |
| 131 | +con = stages.Connect("connect", planners) |
| 132 | +con.path_constraints = constraints |
| 133 | +task.add(con) |
115 | 134 | # [pickAndPlaceTut9] |
116 | 135 |
|
117 | 136 | # [pickAndPlaceTut10] |
118 | 137 | # [initAndConfigGeneratePlacePose] |
119 | 138 | # Define the pose that the object should have after placing |
120 | 139 | placePose = objectPose |
121 | | -placePose.pose.position.y += 0.2 # shift object by 20cm along y axis |
| 140 | +placePose.pose.position.x = -0.2 |
| 141 | +placePose.pose.position.y = -0.6 |
| 142 | +placePose.pose.position.z = 0.0 |
122 | 143 |
|
123 | 144 | # Generate Cartesian place poses for the object |
124 | 145 | place_generator = stages.GeneratePlacePose("Generate Place Pose") |
|
0 commit comments