constrained.py
Go to the documentation of this file.
1 #! /usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
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
8 from moveit.task_constructor import core, stages
9 import time
10 
11 from py_binding_tools import roscpp_init
12 
13 roscpp_init("mtc_tutorial")
14 
15 group = "panda_arm"
16 planner = core.PipelinePlanner()
17 
18 task = core.Task()
19 task.name = "constrained"
20 
21 task.add(stages.CurrentState("current state"))
22 
23 co = CollisionObject()
24 co.header.frame_id = "world"
25 co.id = "obstacle"
26 sphere = SolidPrimitive()
27 sphere.type = sphere.SPHERE
28 sphere.dimensions.insert(sphere.SPHERE_RADIUS, 0.1)
29 
30 pose = Pose()
31 pose.position.x = 0.3
32 pose.position.y = 0.2
33 pose.position.z = 0.5
34 pose.orientation.w = 1.0
35 co.primitives.append(sphere)
36 co.primitive_poses.append(pose)
37 co.operation = co.ADD
38 
39 mps = stages.ModifyPlanningScene("modify planning scene")
40 mps.addObject(co)
41 
42 co.id = "object"
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
47 pose.position.y = 0.0
48 pose.position.z = 0.485
49 pose.orientation.x = pose.orientation.w = 0.70711 # 90° about x
50 mps.addObject(co)
51 mps.attachObjects(["object"], "panda_hand")
52 
53 task.add(mps)
54 
55 move = stages.MoveRelative("y +0.4", planner)
56 move.timeout = 5
57 move.group = group
58 header = Header(frame_id="world")
59 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0, 0.4, 0)))
60 
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 # 90° about x
67 oc.absolute_x_axis_tolerance = 0.1
68 oc.absolute_y_axis_tolerance = 0.1
69 oc.absolute_z_axis_tolerance = 3.14
70 oc.weight = 1.0
71 constraints.orientation_constraints.append(oc)
72 move.path_constraints = constraints
73 
74 task.add(move)
75 
76 if task.plan():
77  task.publish(task.solutions[0])
78 time.sleep(100)
moveit::task_constructor


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