cartesian.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 TwistStamped, Twist, Vector3Stamped, Vector3
6 from moveit.task_constructor import core, stages
7 from math import pi
8 import time
9 
10 from py_binding_tools import roscpp_init
11 
12 roscpp_init("mtc_tutorial")
13 
14 # [cartesianTut1]
15 group = "panda_arm"
16 # [cartesianTut1]
17 
18 # [cartesianTut2]
19 # Cartesian and joint-space interpolation planners
20 cartesian = core.CartesianPath()
21 jointspace = core.JointInterpolationPlanner()
22 # [cartesianTut2]
23 
24 # [cartesianTut3]
25 task = core.Task()
26 task.name = "cartesian"
27 
28 # start from current robot state
29 task.add(stages.CurrentState("current state"))
30 # [cartesianTut3]
31 
32 # [initAndConfigMoveRelative]
33 # move along x
34 move = stages.MoveRelative("x +0.2", cartesian)
35 move.group = group
36 header = Header(frame_id="world")
37 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0.2, 0, 0)))
38 task.add(move)
39 # [initAndConfigMoveRelative]
40 
41 # [cartesianTut4]
42 # move along y
43 move = stages.MoveRelative("y -0.3", cartesian)
44 move.group = group
45 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0, -0.3, 0)))
46 task.add(move)
47 # [cartesianTut4]
48 
49 # [cartesianTut5]
50 # rotate about z
51 move = stages.MoveRelative("rz +45°", cartesian)
52 move.group = group
53 move.setDirection(TwistStamped(header=header, twist=Twist(angular=Vector3(0, 0, pi / 4.0))))
54 task.add(move)
55 # [cartesianTut5]
56 
57 # [cartesianTut6]
58 # Cartesian motion, defined as joint-space offset
59 move = stages.MoveRelative("joint offset", cartesian)
60 move.group = group
61 move.setDirection(dict(panda_joint1=pi / 6, panda_joint3=-pi / 6))
62 task.add(move)
63 # [cartesianTut6]
64 
65 # [initAndConfigMoveTo]
66 # moveTo named posture, using joint-space interplation
67 move = stages.MoveTo("moveTo ready", jointspace)
68 move.group = group
69 move.setGoal("ready")
70 task.add(move)
71 # [initAndConfigMoveTo]
72 
73 if task.plan():
74  task.publish(task.solutions[0])
75 time.sleep(100)
moveit::task_constructor


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