pymoveit_mtc.stages.SimpleUnGrasp¶
- class SimpleUnGrasp(self: pymoveit_mtc.stages.SimpleUnGrasp, pose_generator: pymoveit_mtc.core.Stage, name: str = 'ungrasp')¶
Bases:
SimpleGraspBase
Specialization of SimpleGraspBase to realize ungrasping
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
SimpleUnGrasp
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.
Overloaded function.
Overloaded function.
Set the maximum number of inverse kinematics solutions that should be computed.
Attributes
The end effector of the robot
Failed Solutions of the stage (read-only)
set of properties forwarded from input to output InterfaceState
Name of the grasp pose
Set the frame for which the inverse kinematics is calculated with respect to each pose generated by the pose_generator.
Namespace for any markers that are associated to the stage
name of the stage displayed e.g.
The object to grasp (Must be present in the planning scene)
Name of the pre-grasp pose
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:
- property ik_frame¶
Set the frame for which the inverse kinematics is calculated with respect to each pose generated by the pose_generator.
- 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
- setIKFrame(*args, **kwargs)¶
Overloaded function.
setIKFrame(self: pymoveit_mtc.stages.SimpleGraspBase, transform: geometry_msgs::PoseStamped_<std::allocator<void> >) -> None
Set the frame as a PoseStamped for which the inverse kinematics are calculated with respect to each pose generated by the pose_generator.
setIKFrame(self: pymoveit_mtc.stages.SimpleGraspBase, pose: Eigen::Transform<double, 3, 1, 0>, link: str) -> None
Set the frame as a PoseStamped for which the inverse kinematics are calculated with respect to each pose generated by the pose_generator.
setIKFrame(self: pymoveit_mtc.stages.SimpleGraspBase, link: str) -> None
Set the frame for which the inverse kinematics are calculated with respect to each pose generated by the pose_generator.
- setMaxIKSolutions(self: pymoveit_mtc.stages.SimpleGraspBase, max_ik_solutions: int) None ¶
Set the maximum number of inverse kinematics solutions that should be computed.
- property solutions¶
Successful Solutions of the stage (read-only)