pymoveit_mtc.stages.GeneratePose¶
- class GeneratePose(self: pymoveit_mtc.stages.GeneratePose, name: str)¶
- Bases: - MonitoringGenerator- Monitoring generator stage which can be used to generate a pose, based on solutions provided by the monitored stage. - Take a look at the How-To-Guides for an implementation of a task hierarchy that makes use of the - GeneratePosestage.- Methods - Return - Trueif the stage can still produce solutions.- Compute an actual solution and - spawnan- InterfaceState- Initialize the stage once before planning. - Reset the Stage. - Overloaded function. - Set the monitored - Stage- Spawn an - InterfaceStateto both, start and end interface- 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. - Set the pose, which should be spawned on each new solution of the monitored stage. - 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: SupportsInt)¶
- 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 - Trueif the stage can still produce solutions.
 - compute(self: pymoveit_mtc.core.Generator) None¶
- Compute an actual solution and - spawnan- InterfaceState
 - 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 pose¶
- Set the pose, which should be spawned on each new solution of the monitored stage. - Type:
 
 - 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: collections.abc.Callable[[pymoveit_mtc.core.SubTrajectory, str], float]) -> None 
 - Specify a function to calculate trajectory costs - setCostTerm(self: pymoveit_mtc.core.Stage, arg0: collections.abc.Callable[[pymoveit_mtc.core.SubTrajectory], float]) -> None 
 - Specify a function to calculate trajectory costs 
 - setMonitoredStage(self: pymoveit_mtc.core.MonitoringGenerator, stage: pymoveit_mtc.core.Stage) None¶
- Set the monitored - Stage
 - property solutions¶
- Successful Solutions of the stage (read-only) 
 - spawn(self: pymoveit_mtc.core.Generator, state: pymoveit_mtc.core.InterfaceState, cost: SupportsFloat) None¶
- Spawn an - InterfaceStateto both, start and end interface