pymoveit_mtc.stages.CurrentState¶
- class CurrentState(self: pymoveit_mtc.stages.CurrentState, name: str = 'current state')¶
Bases:
Stage
Fetch the current PlanningScene / real robot state via the
get_planning_scene
service. Usually, this stage should be used once at the beginning of your pipeline to start from the current state.#! /usr/bin/env python3 # -*- coding: utf-8 -*- from moveit.task_constructor import core, stages from py_binding_tools import roscpp_init import time roscpp_init("mtc_tutorial") # Create a task task = core.Task() task.name = "current state" # Get the current robot state currentState = stages.CurrentState("current state") # Add the stage to the task hierarchy task.add(currentState) if task.plan(): task.publish(task.solutions[0]) time.sleep(1)
Methods
Initialize the stage once before planning.
Reset the Stage.
Overloaded function.
Attributes
Failed Solutions of the stage (read-only)
set of properties forwarded from input to output InterfaceState
Namespace for any markers that are associated to the stage
name of the stage displayed e.g. in rviz.
PropertyMap of the stage (read-only)
Successful Solutions of the stage (read-only)
Maximally allowed time [s] per computation step
- class PropertyInitializerSource(self: pymoveit_mtc.core.Stage.PropertyInitializerSource, value: int)¶
Bases:
pybind11_object
OR-combinable flags defining a source to initialize a specific property from. Used in pymoveit_mtc.core.PropertyMap
configureInitFrom()
.Members:
PARENT : Inherit properties from parent stage
INTERFACE : Inherit properties from the input InterfaceState
- property name¶
- property forwarded_properties¶
set of properties forwarded from input to output InterfaceState
- Type:
- init(self: pymoveit_mtc.core.Stage, robot_model: moveit::core::RobotModel) None ¶
Initialize the stage once before planning. Will setup properties configured for initialization from parent.
- property properties¶
PropertyMap of the stage (read-only)
- Type:
- reset(self: pymoveit_mtc.core.Stage) None ¶
Reset the Stage. Clears all solutions, interfaces and inherited properties
- setCostTerm(*args, **kwargs)¶
Overloaded function.
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: pymoveit_mtc.core.CostTerm) -> None
Specify a CostTerm for calculation of stage costs
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory, str], float]) -> None
Specify a function to calculate trajectory costs
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory], float]) -> None
Specify a function to calculate trajectory costs
- property solutions¶
Successful Solutions of the stage (read-only)