4 from py_binding_tools
import roscpp_init
6 from moveit_commander
import PlanningSceneInterface
7 from geometry_msgs.msg
import PoseStamped, TwistStamped
8 from moveit_msgs.msg
import Constraints, OrientationConstraint
11 roscpp_init(
"mtc_tutorial")
21 object_name =
"object"
25 psi = PlanningSceneInterface(synchronous=
True)
26 psi.remove_world_object()
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
39 psi.add_box(object_name, objectPose, size=[0.1, 0.05, 0.03])
45 task.name =
"pick + place"
50 task.add(stages.CurrentState(
"current"))
55 pipeline = core.PipelinePlanner()
56 pipeline.planner =
"RRTConnectkConfigDefault"
57 planners = [(arm, pipeline)]
60 task.add(stages.Connect(
"connect", planners))
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"])
78 simpleGrasp = stages.SimpleGrasp(grasp_generator,
"Grasp")
80 ik_frame = PoseStamped()
81 ik_frame.header.frame_id =
"panda_hand"
82 ik_frame.pose.position.z = 0.1034
83 ik_frame.pose.orientation.x = 1.0
84 simpleGrasp.setIKFrame(ik_frame)
91 pick = stages.Pick(simpleGrasp,
"Pick")
93 pick.object = object_name
96 approach = TwistStamped()
97 approach.header.frame_id =
"world"
98 approach.twist.linear.z = -1.0
99 pick.setApproachMotion(approach, 0.03, 0.1)
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)
115 oc = OrientationConstraint()
116 oc.parameterization = oc.ROTATION_VECTOR
117 oc.header.frame_id =
"world"
118 oc.link_name =
"object"
120 oc.absolute_x_axis_tolerance = 0.1
121 oc.absolute_y_axis_tolerance = 0.1
122 oc.absolute_z_axis_tolerance = math.pi
125 constraints = Constraints()
126 constraints.name =
"object:upright"
127 constraints.orientation_constraints.append(oc)
131 con = stages.Connect(
"connect", planners)
132 con.path_constraints = constraints
139 placePose = objectPose
140 placePose.pose.position.x = -0.2
141 placePose.pose.position.y = -0.6
142 placePose.pose.position.z = 0.0
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
155 simpleUnGrasp = stages.SimpleUnGrasp(place_generator,
"UnGrasp")
161 place = stages.Place(simpleUnGrasp,
"Place")
163 place.object = object_name
164 place.eef_frame =
"panda_link8"
168 retract = TwistStamped()
169 retract.header.frame_id =
"world"
170 retract.twist.linear.z = 1.0
171 place.setRetractMotion(retract, 0.03, 0.1)
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)
186 task.publish(task.solutions[0])