pymoveit_mtc.stages.SimpleGraspBase

class SimpleGraspBase

Bases: SerialContainer

Abstract base class for grasping and releasing

Methods

add

Insert a stage at the end of the current children list

clear

Remove all stages from the container

init

Initialize the stage once before planning.

insert

Insert a stage before the given index into the children list

remove

Overloaded function.

reset

Reset the Stage.

setCostTerm

Overloaded function.

setIKFrame

Overloaded function.

setMaxIKSolutions

Set the maximum number of inverse kinematics solutions that should be computed.

Attributes

eef

The end effector of the robot

failures

Failed Solutions of the stage (read-only)

forwarded_properties

set of properties forwarded from input to output InterfaceState

ik_frame

Set the frame for which the inverse kinematics is calculated with respect to each pose generated by the pose_generator.

marker_ns

Namespace for any markers that are associated to the stage

name

name of the stage displayed e.g.

object

The object to grasp (Must be present in the planning scene)

properties

PropertyMap of the stage (read-only)

solutions

Successful Solutions of the stage (read-only)

timeout

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.

  1. __getitem__(self: pymoveit_mtc.core.ContainerBase, arg0: str) -> pymoveit_mtc.core.Stage

  2. __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 eef

The end effector of the robot

Type:

str

property failures

Failed Solutions of the stage (read-only)

Type:

Solutions

property forwarded_properties

set of properties forwarded from input to output InterfaceState

Type:

list

property ik_frame

Set the frame for which the inverse kinematics is calculated with respect to each pose generated by the pose_generator.

Type:

PoseStamped

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 marker_ns

Namespace for any markers that are associated to the stage

Type:

str

property name

name of the stage displayed e.g. in rviz

Type:

str

property object

The object to grasp (Must be present in the planning scene)

Type:

str

property properties

PropertyMap of the stage (read-only)

Type:

PropertyMap

remove(*args, **kwargs)

Overloaded function.

  1. remove(self: pymoveit_mtc.core.ContainerBase, pos: int) -> pymoveit_mtc.core.Stage

Remove child stage by index

  1. 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.

  1. setCostTerm(self: pymoveit_mtc.core.Stage, arg0: pymoveit_mtc.core.CostTerm) -> None

Specify a CostTerm for calculation of stage costs

  1. setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory, str], float]) -> None

Specify a function to calculate trajectory costs

  1. 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.

  1. 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.

  2. 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.

  3. 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)

property timeout

Maximally allowed time [s] per computation step

Type:

float