pymoveit_mtc.stages.MoveTo

class MoveTo(self: pymoveit_mtc.stages.MoveTo, name: str, planner: pymoveit_mtc.core.PlannerInterface)

Bases: PropagatingEitherWay

Compute a trajectory between the robot state from the interface state of the preceeding stage and a specified goal.

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

Methods

computeBackward

Compute backward

computeForward

Compute forward

init

Initialize the stage once before planning.

reset

Reset the Stage.

restrictDirection

Explicitly specify computation direction

setCostTerm

Overloaded function.

setGoal

Overloaded function.

Attributes

failures

Failed Solutions of the stage (read-only)

forwarded_properties

set of properties forwarded from input to output InterfaceState

group

Planning group which should be utilized for planning and execution.

ik_frame

IK reference frame for the goal pose

marker_ns

Namespace for any markers that are associated to the stage

name

name of the stage displayed e.g.

path_constraints

Set path constraints via the corresponding moveit message type

properties

PropertyMap of the stage (read-only)

solutions

Successful Solutions of the stage (read-only)

timeout

Maximally allowed time [s] per computation step

class Direction(self: pymoveit_mtc.core.PropagatingEitherWay.Direction, value: int)

Bases: pybind11_object

Propagation direction

Members:

AUTO

FORWARD : Propagating forwards from start to end

BACKWARD : Propagating backwards from end to start

property name
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
computeBackward(self: pymoveit_mtc.core.PropagatingEitherWay, arg0: pymoveit_mtc.core.InterfaceState) None

Compute backward

computeForward(self: pymoveit_mtc.core.PropagatingEitherWay, arg0: pymoveit_mtc.core.InterfaceState) None

Compute forward

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

Planning group which should be utilized for planning and execution.

Type:

str

property ik_frame

IK reference frame for the goal pose

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 name

name of the stage displayed e.g. in rviz

Type:

str

property path_constraints

Set path constraints via the corresponding moveit message type

Type:

Constraints

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

restrictDirection(self: pymoveit_mtc.core.PropagatingEitherWay, arg0: moveit::task_constructor::PropagatingEitherWay::Direction) None

Explicitly specify computation direction

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

setGoal(*args, **kwargs)

Overloaded function.

  1. setGoal(self: pymoveit_mtc.stages.MoveTo, goal: geometry_msgs::PoseStamped_<std::allocator<void> >) -> None

    Move link to a given PoseStamped

  2. setGoal(self: pymoveit_mtc.stages.MoveTo, goal: geometry_msgs::PointStamped_<std::allocator<void> >) -> None

    Move link to given PointStamped, keeping current orientation

  3. setGoal(self: pymoveit_mtc.stages.MoveTo, goal: moveit_msgs::RobotState_<std::allocator<void> >) -> None

    Move joints specified in RobotState to their target values

  4. setGoal(self: pymoveit_mtc.stages.MoveTo, goal: dict[str, float]) -> None

    Move joints by name to their mapped target value provided by dict goal argument

  5. setGoal(self: pymoveit_mtc.stages.MoveTo, goal: str) -> None

    Move joint model group to given named pose provided as a str argument

property solutions

Successful Solutions of the stage (read-only)

property timeout

Maximally allowed time [s] per computation step

Type:

float