4 from std_msgs.msg
import Header
5 from geometry_msgs.msg
import TwistStamped, Twist, Vector3Stamped, Vector3
10 from py_binding_tools
import roscpp_init
12 roscpp_init(
"mtc_tutorial")
20 cartesian = core.CartesianPath()
21 jointspace = core.JointInterpolationPlanner()
26 task.name =
"cartesian"
29 task.add(stages.CurrentState(
"current state"))
34 move = stages.MoveRelative(
"x +0.2", cartesian)
36 header = Header(frame_id=
"world")
37 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0.2, 0, 0)))
43 move = stages.MoveRelative(
"y -0.3", cartesian)
45 move.setDirection(Vector3Stamped(header=header, vector=Vector3(0, -0.3, 0)))
51 move = stages.MoveRelative(
"rz +45°", cartesian)
53 move.setDirection(TwistStamped(header=header, twist=Twist(angular=Vector3(0, 0, pi / 4.0))))
59 move = stages.MoveRelative(
"joint offset", cartesian)
61 move.setDirection(dict(panda_joint1=pi / 6, panda_joint3=-pi / 6))
67 move = stages.MoveTo(
"moveTo ready", jointspace)
74 task.publish(task.solutions[0])