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
Compute backward
Compute forward
Initialize the stage once before planning.
Reset the Stage.
Explicitly specify computation direction
Overloaded function.
Overloaded function.
Attributes
Failed Solutions of the stage (read-only)
set of properties forwarded from input to output InterfaceState
Planning group which should be utilized for planning and execution.
IK reference frame for the goal pose
Namespace for any markers that are associated to the stage
name of the stage displayed e.g.
Set path constraints via the corresponding moveit message type
PropertyMap of the stage (read-only)
Successful Solutions of the stage (read-only)
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 forwarded_properties¶
set of properties forwarded from input to output InterfaceState
- Type:
- property ik_frame¶
IK reference frame for the goal pose
- Type:
- 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 path_constraints¶
Set path constraints via the corresponding moveit message type
- Type:
- property properties¶
PropertyMap of the stage (read-only)
- Type:
- 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.
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: pymoveit_mtc.core.CostTerm) -> None
Specify a CostTerm for calculation of stage costs
setCostTerm(self: pymoveit_mtc.core.Stage, arg0: Callable[[pymoveit_mtc.core.SubTrajectory, str], float]) -> None
Specify a function to calculate trajectory costs
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.
setGoal(self: pymoveit_mtc.stages.MoveTo, goal: geometry_msgs::PoseStamped_<std::allocator<void> >) -> None
Move link to a given PoseStamped
setGoal(self: pymoveit_mtc.stages.MoveTo, goal: geometry_msgs::PointStamped_<std::allocator<void> >) -> None
Move link to given PointStamped, keeping current orientation
setGoal(self: pymoveit_mtc.stages.MoveTo, goal: moveit_msgs::RobotState_<std::allocator<void> >) -> None
Move joints specified in RobotState to their target values
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
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)