alternatives.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 # Use the joint interpolation planner
11 jointPlanner = core.JointInterpolationPlanner()
12 
13 # Create a task
14 task = core.Task()
15 task.name = "alternatives"
16 
17 # Start from current robot state
18 currentState = stages.CurrentState("current state")
19 
20 # Add the current state to the task hierarchy
21 task.add(currentState)
22 
23 # [initAndConfigAlternatives]
24 # The alternatives stage supports multiple execution paths
25 alternatives = core.Alternatives("Alternatives")
26 
27 # goal 1
28 goalConfig1 = {
29  "panda_joint1": 1.0,
30  "panda_joint2": -1.0,
31  "panda_joint3": 0.0,
32  "panda_joint4": -2.5,
33  "panda_joint5": 1.0,
34  "panda_joint6": 1.0,
35  "panda_joint7": 1.0,
36 }
37 
38 # goal 2
39 goalConfig2 = {
40  "panda_joint1": -3.0,
41  "panda_joint2": -1.0,
42  "panda_joint3": 0.0,
43  "panda_joint4": -2.0,
44  "panda_joint5": 1.0,
45  "panda_joint6": 2.0,
46  "panda_joint7": 0.5,
47 }
48 
49 # First motion plan to compare
50 moveTo1 = stages.MoveTo("Move To Goal Configuration 1", jointPlanner)
51 moveTo1.group = "panda_arm"
52 moveTo1.setGoal(goalConfig1)
53 alternatives.insert(moveTo1)
54 
55 # Second motion plan to compare
56 moveTo2 = stages.MoveTo("Move To Goal Configuration 2", jointPlanner)
57 moveTo2.group = "panda_arm"
58 moveTo2.setGoal(goalConfig2)
59 alternatives.insert(moveTo2)
60 
61 # Add the alternatives stage to the task hierarchy
62 task.add(alternatives)
63 # [initAndConfigAlternatives]
64 
65 if task.plan():
66  task.publish(task.solutions[0])
67 time.sleep(1)
moveit::task_constructor


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