pymoveit_mtc.stages.GeneratePlacePose¶
- class GeneratePlacePose(self: pymoveit_mtc.stages.GeneratePlacePose, name: str = 'Generate Place Pose')¶
Bases:
MonitoringGenerator
GeneratePlacePose stage derives from monitoring generator and generates poses for the place pipeline. Notice that whilst GenerateGraspPose spawns poses with an
angle_delta
intervall, GeneratePlacePose samples a fixed amount, which is dependent on the objects shape.Take a look at the How-To-Guides for a snippet that demonstrates usage of the GeneratePlacePose stage.
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.
Set the monitored
Stage
Spawn an
InterfaceState
to both, start and end interfaceAttributes
Name of the end effector that should be used for grasping
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.
Name of the object in the planning scene, attached to the robot which should be placed
The pose where the object should be placed, i.e. states should be sampled.
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 object¶
Name of the object in the planning scene, attached to the robot which should be placed
- Type:
- property pose¶
The pose where the object should be placed, i.e. states should be sampled
- 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: 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
- 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: float) None ¶
Spawn an
InterfaceState
to both, start and end interface