pymoveit_mtc.core.Fallbacks¶
- class Fallbacks(self: pymoveit_mtc.core.Fallbacks, name: str = 'Fallbacks')¶
Bases:
ParallelContainerBase
Plan for different alternatives in sequence Try to find feasible solutions using the children in sequence. The behaviour slightly differs for the indivual stage types:
Generator: Proceed to next child if currently active one exhausted its solution, i.e. returns
canCompute() == False
.Propagator: Forward an incoming
InterfaceState
to the next child if the current one ultimately failed on it.Connect: Only
Connect
stages are supported. Pairs ofInterfaceStates
are forward to the next child on failure of the current child.
See How-To-Guides for an example.
Methods
Insert a stage at the end of the current children list
Remove all stages from the container
Initialize the stage once before planning.
Insert a stage before the given index into the children list
Overloaded function.
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.
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¶
- __getitem__(*args, **kwargs)¶
Overloaded function.
__getitem__(self: pymoveit_mtc.core.ContainerBase, arg0: str) -> pymoveit_mtc.core.Stage
__getitem__(self: pymoveit_mtc.core.ContainerBase, arg0: int) -> pymoveit_mtc.core.Stage
- __iter__(self: pymoveit_mtc.core.ContainerBase) Iterator[pymoveit_mtc.core.Stage] ¶
- __len__(self: pymoveit_mtc.core.ContainerBase) int ¶
- add(self: pymoveit_mtc.core.ContainerBase, *args) None ¶
Insert a stage at the end of the current children list
- clear(self: pymoveit_mtc.core.ContainerBase) None ¶
Remove all stages from the container
- 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.
- insert(self: pymoveit_mtc.core.ContainerBase, stage: pymoveit_mtc.core.Stage, before: int = -1) None ¶
Insert a stage before the given index into the children list
- property properties¶
PropertyMap of the stage (read-only)
- Type:
- remove(*args, **kwargs)¶
Overloaded function.
remove(self: pymoveit_mtc.core.ContainerBase, pos: int) -> pymoveit_mtc.core.Stage
Remove child stage by index
remove(self: pymoveit_mtc.core.ContainerBase, child: pymoveit_mtc.core.Stage) -> pymoveit_mtc.core.Stage
Remove child stage by instance
- 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)