pymoveit_mtc.core.Generator¶
- class Generator(self: pymoveit_mtc.core.Generator, name: str = 'Generator')¶
Bases:
Stage
Base class for generator-like stages
Derive from this stage to implement a custom generator stage that can produce new seed states w/o prior knowledge. Implement the virtual methods as follows:
class MyGenerator(core.Generator): """Implements a custom 'Generator' stage that produces maximally 3 solutions.""" def __init__(self, name="Generator"): core.Generator.__init__(self, name) self.reset() def init(self, robot_model): self.ps = PlanningScene(robot_model) def reset(self): core.Generator.reset(self) def canCompute(self): return len(self.solutions) < 3 # maximally produce 3 solutions def compute(self): self.spawn(core.InterfaceState(self.ps), cost=len(self.solutions))
Methods
Return
True
if the stage can still produce solutions.Compute an actual solution and
spawn
anInterfaceState
Initialize the stage once before planning.
Reset the Stage.
Overloaded function.
Spawn an
InterfaceState
to both, start and end interfaceAttributes
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¶
- canCompute(self: pymoveit_mtc.core.Generator) bool ¶
Return
True
if the stage can still produce solutions.
- compute(self: pymoveit_mtc.core.Generator) None ¶
Compute an actual solution and
spawn
anInterfaceState
- 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)
- spawn(self: pymoveit_mtc.core.Generator, state: pymoveit_mtc.core.InterfaceState, cost: float) None ¶
Spawn an
InterfaceState
to both, start and end interface