5 from py_binding_tools
import roscpp_init
8 roscpp_init(
"mtc_tutorial")
11 planner = core.JointInterpolationPlanner()
18 currentState = stages.CurrentState(
"current state")
19 task.add(currentState)
23 merger = core.Merger(
"Merger")
26 moveTo1 = stages.MoveTo(
"Move To Home", planner)
27 moveTo1.group =
"hand"
28 moveTo1.setGoal(
"close")
29 merger.insert(moveTo1)
32 moveTo2 = stages.MoveTo(
"Move To Ready", planner)
33 moveTo2.group =
"panda_arm"
34 moveTo2.setGoal(
"extended")
35 merger.insert(moveTo2)
42 task.publish(task.solutions[0])