4 from std_msgs.msg
import Header
5 from geometry_msgs.msg
import Vector3Stamped, Vector3, Pose
6 from moveit_msgs.msg
import CollisionObject, Constraints, OrientationConstraint
7 from shape_msgs.msg
import SolidPrimitive
11 from py_binding_tools
import roscpp_init
13 roscpp_init(
"mtc_tutorial")
16 planner = core.PipelinePlanner()
19 task.name =
"constrained"
21 task.add(stages.CurrentState(
"current state"))
23 co = CollisionObject()
24 co.header.frame_id =
"world"
26 sphere = SolidPrimitive()
27 sphere.type = sphere.SPHERE
28 sphere.dimensions.insert(sphere.SPHERE_RADIUS, 0.1)
34 pose.orientation.w = 1.0
35 co.primitives.append(sphere)
36 co.primitive_poses.append(pose)
39 mps = stages.ModifyPlanningScene(
"modify planning scene")
43 co.primitives[0].type = SolidPrimitive.BOX
44 co.primitives[0].dimensions = [0.1, 0.05, 0.03]
45 pose = co.primitive_poses[0]
46 pose.position.x = 0.30702
48 pose.position.z = 0.485
49 pose.orientation.x = pose.orientation.w = 0.70711
51 mps.attachObjects([
"object"],
"panda_hand")
55 move = stages.MoveRelative(
"y +0.4", planner)
58 header = Header(frame_id=
"world")
59 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0, 0.4, 0)))
61 constraints = Constraints()
62 oc = OrientationConstraint()
63 oc.parameterization = oc.ROTATION_VECTOR
64 oc.header.frame_id =
"world"
65 oc.link_name =
"object"
66 oc.orientation.x = oc.orientation.w = 0.70711
67 oc.absolute_x_axis_tolerance = 0.1
68 oc.absolute_y_axis_tolerance = 0.1
69 oc.absolute_z_axis_tolerance = 3.14
71 constraints.orientation_constraints.append(oc)
72 move.path_constraints = constraints
77 task.publish(task.solutions[0])