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 exposedInterfaceState
.Take a look at the How-To-Guides for an implementation of a task hierarchy that makes use of the
ComputeIK
stage.Methods
Initialize the stage once before planning.
Reset the Stage.
Overloaded function.
Attributes
additional constraints to obey
Default joint pose of the active group (defines cost of the inverse kinematics).
Specify which end effector of the active planning group should be used.
Failed Solutions of the stage (read-only)
set of properties forwarded from input to output InterfaceState
Specify which planning group should be used.
Specify if collisions with other members of the planning scene are allowed.
Specify the frame with respect to which the inverse kinematics should be calculated.
Namespace for any markers that are associated to the stage
max number of solutions to return
reject solution that are closer than this to previously found solutions
name of the stage displayed e.g.
PropertyMap of the stage (read-only)
Successful Solutions of the stage (read-only)
Specify the pose on which the inverse kinematics should be calculated on.
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:
- property forwarded_properties¶
set of properties forwarded from input to output InterfaceState
- Type:
- property ignore_collisions¶
Specify if collisions with other members of the planning scene are allowed.
- Type:
- property ik_frame¶
Specify the frame with respect to which the inverse kinematics should be calculated.
- 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 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 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
- 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
- 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: