pymoveit_mtc.stages.Connect

class Connect(self: pymoveit_mtc.stages.Connect, name: str = 'connect', planners: list[tuple[str, pymoveit_mtc.core.PlannerInterface]])

Bases: Stage

Connect arbitrary InterfaceStates by motion planning. You can specify the planning groups and the planners you want to utilize.

The states may differ in various planning groups. To connect both states, the planners provided for individual sub groups are applied in the specified order. Each planner only plan for joints within the corresponding planning group. Finally, an attempt is made to merge the sub trajectories of individual planning results. If this fails, the sequential planning result is returned.

For an example, see How-To-Guides.

Methods

init

Initialize the stage once before planning.

reset

Reset the Stage.

setCostTerm

Overloaded function.

Attributes

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

max_distance

maximally accepted distance between end and goal sate

merge_mode

Defines the merge strategy to use

name

name of the stage displayed e.g.

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

property marker_ns

Namespace for any markers that are associated to the stage

Type:

str

property max_distance

maximally accepted distance between end and goal sate

property merge_mode

Defines the merge strategy to use

property name

name of the stage displayed e.g. in rviz

Type:

str

property properties

PropertyMap of the stage (read-only)

Type:

PropertyMap

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

property solutions

Successful Solutions of the stage (read-only)

property timeout

Maximally allowed time [s] per computation step

Type:

float