pymoveit_mtc.stages.ComputeIK

class ComputeIK(self: pymoveit_mtc.stages.ComputeIK, name: str, stage: pymoveit_mtc.core.Stage)

Bases: Stage

Wrapper for any pose generator stage to compute the inverse kinematics for a pose in Cartesian space.

The wrapper reads a target_pose from the interface state of solutions provided by the wrapped stage. This cartesian pose (PoseStamped msg) is used as a goal pose for inverse kinematics.

Usually, the end effector’s parent link or the group’s tip link is used as the inverse kinematics frame, which should be moved to the goal frame. However, any other inverse kinematics frame can be defined (which is linked to the tip of the group).

Properties of the internally received InterfaceState can be forwarded to the newly generated, externally exposed InterfaceState.

Take a look at the How-To-Guides for an implementation of a task hierarchy that makes use of the ComputeIK stage.

Methods

init

Initialize the stage once before planning.

reset

Reset the Stage.

setCostTerm

Overloaded function.

Attributes

constraints

additional constraints to obey

default_pose

Default joint pose of the active group (defines cost of the inverse kinematics).

eef

Specify which end effector of the active planning group should be used.

failures

Failed Solutions of the stage (read-only)

forwarded_properties

set of properties forwarded from input to output InterfaceState

group

Specify which planning group should be used.

ignore_collisions

Specify if collisions with other members of the planning scene are allowed.

ik_frame

Specify the frame with respect to which the inverse kinematics should be calculated.

marker_ns

Namespace for any markers that are associated to the stage

max_ik_solutions

max number of solutions to return

min_solution_distance

reject solution that are closer than this to previously found solutions

name

name of the stage displayed e.g.

properties

PropertyMap of the stage (read-only)

solutions

Successful Solutions of the stage (read-only)

target_pose

Specify the pose on which the inverse kinematics should be calculated on.

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 constraints

additional constraints to obey

property default_pose

Default joint pose of the active group (defines cost of the inverse kinematics).

Type:

str

property eef

Specify which end effector of the active planning group should be used.

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 group

Specify which planning group should be used.

Type:

str

property ignore_collisions

Specify if collisions with other members of the planning scene are allowed.

Type:

bool

property ik_frame

Specify the frame with respect to which the inverse kinematics should be calculated.

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.

property marker_ns

Namespace for any markers that are associated to the stage

Type:

str

property max_ik_solutions

max number of solutions to return

Type:

uint

property min_solution_distance

reject solution that are closer than this to previously found solutions

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 target_pose

Specify the pose on which the inverse kinematics should be calculated on. Since this property should almost always be set in the Interface State which is sent by the child, if possible, avoid setting it manually.

Type:

PoseStamped

property timeout

Maximally allowed time [s] per computation step

Type:

float