5 from py_binding_tools
import roscpp_init
8 roscpp_init(
"mtc_tutorial")
10 ompl_planner = core.PipelinePlanner(
"ompl")
11 ompl_planner.planner =
"RRTConnectkConfigDefault"
12 pilz_planner = core.PipelinePlanner(
"pilz_industrial_motion_planner")
13 pilz_planner.planner =
"PTP"
14 multiPlanner = core.MultiPlanner()
15 multiPlanner.add(pilz_planner, ompl_planner)
19 task.name =
"multi planner"
22 currentState = stages.CurrentState(
"current state")
25 task.add(currentState)
28 alternatives = core.Alternatives(
"Alternatives")
53 moveTo1 = stages.MoveTo(
"Move To Goal Configuration 1", multiPlanner)
54 moveTo1.group =
"panda_arm"
55 moveTo1.setGoal(goalConfig1)
56 alternatives.insert(moveTo1)
59 moveTo2 = stages.MoveTo(
"Move To Goal Configuration 2", multiPlanner)
60 moveTo2.group =
"panda_arm"
61 moveTo2.setGoal(goalConfig2)
62 alternatives.insert(moveTo2)
65 task.add(alternatives)
68 task.publish(task.solutions[0])