multi_planner.py
Go to the documentation of this file.
1 #! /usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
4 from moveit.task_constructor import core, stages
5 from py_binding_tools import roscpp_init
6 import time
7 
8 roscpp_init("mtc_tutorial")
9 
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)
16 
17 # Create a task
18 task = core.Task()
19 task.name = "multi planner"
20 
21 # Start from current robot state
22 currentState = stages.CurrentState("current state")
23 
24 # Add the current state to the task hierarchy
25 task.add(currentState)
26 
27 # The alternatives stage supports multiple execution paths
28 alternatives = core.Alternatives("Alternatives")
29 
30 # goal 1
31 goalConfig1 = {
32  "panda_joint1": 1.0,
33  "panda_joint2": -1.0,
34  "panda_joint3": 0.0,
35  "panda_joint4": -2.5,
36  "panda_joint5": 1.0,
37  "panda_joint6": 1.0,
38  "panda_joint7": 1.0,
39 }
40 
41 # goal 2
42 goalConfig2 = {
43  "panda_joint1": -3.0,
44  "panda_joint2": -1.0,
45  "panda_joint3": 0.0,
46  "panda_joint4": -2.0,
47  "panda_joint5": 1.0,
48  "panda_joint6": 2.0,
49  "panda_joint7": 0.5,
50 }
51 
52 # First motion plan to compare
53 moveTo1 = stages.MoveTo("Move To Goal Configuration 1", multiPlanner)
54 moveTo1.group = "panda_arm"
55 moveTo1.setGoal(goalConfig1)
56 alternatives.insert(moveTo1)
57 
58 # Second motion plan to compare
59 moveTo2 = stages.MoveTo("Move To Goal Configuration 2", multiPlanner)
60 moveTo2.group = "panda_arm"
61 moveTo2.setGoal(goalConfig2)
62 alternatives.insert(moveTo2)
63 
64 # Add the alternatives stage to the task hierarchy
65 task.add(alternatives)
66 
67 if task.plan():
68  task.publish(task.solutions[0])
69 time.sleep(1)
moveit::task_constructor


demo
Author(s): Robert Haschke , Simon Goldstein , Henning Kayser
autogenerated on Sat May 3 2025 02:40:30