pymoveit_mtc.stages.Pick¶
- class Pick(self: pymoveit_mtc.stages.Pick, grasp_generator: pymoveit_mtc.core.Stage, name: str = 'pick')¶
Bases:
SerialContainer
The Pick stage is a specialization of the PickPlaceBase class, which wraps the pipeline to pick or place an object with a given end effector.
Picking consist of the following sub stages:
Linearly approaching the object along an approach direction/twist “grasp” end effector posture
Attach the object
Lift along a given direction/twist
The end effector postures corresponding to pre-grasp and grasp as well as the end effector’s cartesian pose needs to be provided by an external grasp stage.
Take a look at the Pick and Place Tutorial for an in-depth look, as well as the How-To Guide for a minimal implementation of a task hierarchy that makes use of the
Pick
stage.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.
The approaching motion towards the grasping state is represented by a twist message.
Overloaded function.
Overloaded function.
Attributes
The End effector name
Name of the end effector frame
Joint model group of the end effector
Joint model group of the eef's parent
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 object to pick
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
- setApproachMotion(self: pymoveit_mtc.stages.Pick, motion: geometry_msgs::TwistStamped_<std::allocator<void> >, min_distance: float, max_distance: float) None ¶
The approaching motion towards the grasping state is represented by a twist message. Additionally specify the minimum and maximum allowed distances to travel.
- 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
- setLiftMotion(*args, **kwargs)¶
Overloaded function.
setLiftMotion(self: pymoveit_mtc.stages.Pick, motion: geometry_msgs::TwistStamped_<std::allocator<void> >, min_distance: float, max_distance: float) -> None
The lifting motion away from the grasping state is represented by a twist message. Additionally specify the minimum and maximum allowed distances to travel.
setLiftMotion(self: pymoveit_mtc.stages.Pick, place: dict[str, float]) -> None
The lifting motion away from the grasping state is represented by its destination as joint-value pairs
- property solutions¶
Successful Solutions of the stage (read-only)