5 from py_binding_tools
import roscpp_init
8 roscpp_init(
"mtc_tutorial")
11 jointPlanner = core.JointInterpolationPlanner()
15 task.name =
"alternatives"
18 currentState = stages.CurrentState(
"current state")
21 task.add(currentState)
25 alternatives = core.Alternatives(
"Alternatives")
50 moveTo1 = stages.MoveTo(
"Move To Goal Configuration 1", jointPlanner)
51 moveTo1.group =
"panda_arm"
52 moveTo1.setGoal(goalConfig1)
53 alternatives.insert(moveTo1)
56 moveTo2 = stages.MoveTo(
"Move To Goal Configuration 2", jointPlanner)
57 moveTo2.group =
"panda_arm"
58 moveTo2.setGoal(goalConfig2)
59 alternatives.insert(moveTo2)
62 task.add(alternatives)
66 task.publish(task.solutions[0])