pymoveit_mtc.stages.Place

class Place(self: pymoveit_mtc.stages.Place, place_generator: pymoveit_mtc.core.Stage, name: str = 'place')

Bases: SerialContainer

The Place stage is a specialization of the PickPlaceBase class, which wraps the pipeline to pick or place an object with a given end effector.

Placing consist of the inverse order of stages:

  • Place down along a given direction

  • Detach the object

  • Linearly retract end effector

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 Place stage.

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.

setPlaceMotion

Overloaded function.

setRetractMotion

The retract motion towards the final state is represented by a Twist message.

Attributes

eef

The End effector name

eef_frame

Name of the end effector frame

eef_group

Joint model group of the end effector

eef_parent_group

Joint model group of the eef's parent

failures

Failed Solutions of the stage (read-only)

forwarded_properties

set of properties forwarded from input to output InterfaceState

marker_ns

Namespace for any markers that are associated to the stage

name

name of the stage displayed e.g.

object

Name of object to pick

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 name

Type:

str

property eef_frame

Name of the end effector frame

Type:

str

property eef_group

Joint model group of the end effector

Type:

str

property eef_parent_group

Joint model group of the eef’s parent

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

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

Name of object to pick

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

setPlaceMotion(*args, **kwargs)

Overloaded function.

  1. setPlaceMotion(self: pymoveit_mtc.stages.Place, motion: geometry_msgs::TwistStamped_<std::allocator<void> >, min_distance: float, max_distance: float) -> None

    The object-placing motion towards the final state is represented by a twist message. Additionally specify the minimum and maximum allowed distances to travel.

  2. setPlaceMotion(self: pymoveit_mtc.stages.Place, joints: dict[str, float]) -> None

    The placing motion to the final state is represented by its destination as joint-value pairs

setRetractMotion(self: pymoveit_mtc.stages.Place, motion: geometry_msgs::TwistStamped_<std::allocator<void> >, min_distance: float, max_distance: float) None

The retract motion towards the final state is represented by a Twist message. Additionally specify the minimum and maximum allowed distances to travel.

property solutions

Successful Solutions of the stage (read-only)

property timeout

Maximally allowed time [s] per computation step

Type:

float