5 from py_binding_tools
import roscpp_init
8 roscpp_init(
"mtc_tutorial")
11 cartesianPlanner = core.CartesianPath()
12 jointPlanner = core.JointInterpolationPlanner()
16 task.name =
"fallbacks"
19 currentState = stages.CurrentState(
"Current State")
20 task.add(currentState)
25 fallbacks = core.Fallbacks(
"Fallbacks")
28 moveTo1 = stages.MoveTo(
"Move To Goal Configuration 1", cartesianPlanner)
29 moveTo1.group =
"panda_arm"
30 moveTo1.setGoal(
"extended")
31 fallbacks.insert(moveTo1)
34 moveTo2 = stages.MoveTo(
"Move To Goal Configuration 2", jointPlanner)
35 moveTo2.group =
"panda_arm"
36 moveTo2.setGoal(
"extended")
37 fallbacks.insert(moveTo2)
44 task.publish(task.solutions[0])