fixed_state.py
Go to the documentation of this file.
1 #! /usr/bin/env python3
2 # -*- coding: utf-8 -*-
3 
4 from moveit.core import planning_scene
5 from moveit.task_constructor import core, stages
6 from py_binding_tools import roscpp_init
7 from moveit.core.planning_scene import PlanningScene
8 import time
9 
10 roscpp_init("mtc_tutorial")
11 
12 
13 # Create a task
14 task = core.Task()
15 task.name = "fixed state"
16 
17 # [initAndConfigFixedState]
18 # Initialize a PlanningScene for use in a FixedState stage
19 task.loadRobotModel() # load the robot model (usually done in init())
20 planningScene = PlanningScene(task.getRobotModel())
21 
22 # Create a FixedState stage and pass the created PlanningScene as its state
23 fixedState = stages.FixedState("fixed state")
24 fixedState.setState(planningScene)
25 
26 # Add the stage to the task hierarchy
27 task.add(fixedState)
28 # [initAndConfigFixedState]
29 
30 if task.plan():
31  task.publish(task.solutions[0])
32 
33 del planningScene # Avoid ClassLoader warning by destroying the RobotModel
34 time.sleep(1)
moveit::core
moveit::core::planning_scene
moveit::task_constructor


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