moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Static Public Member Functions | List of all members
moveit::core::CartesianInterpolator Class Reference

#include <cartesian_interpolator.h>

Classes

struct  Distance
 
struct  Percentage
 

Static Public Member Functions

static Distance computeCartesianPath (const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &traj, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
 Compute the sequence of joint values that correspond to a straight Cartesian path for a particular link.
 
static Distance computeCartesianPath (const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &traj, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
 Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular link.
 
static Percentage computeCartesianPath (const RobotState *start_state, const JointModelGroup *group, std::vector< RobotStatePtr > &traj, const LinkModel *link, const Eigen::Isometry3d &target, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback, const kinematics::KinematicsQueryOptions &options, const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
 Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular frame.
 
static Percentage computeCartesianPath (const RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &traj, const LinkModel *link, const EigenSTL::vector_Isometry3d &waypoints, bool global_reference_frame, const MaxEEFStep &max_step, const CartesianPrecision &precision, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
 Compute the sequence of joint values that perform a general Cartesian path.
 
static Distance computeCartesianPath (RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &path, const LinkModel *link, const Eigen::Vector3d &translation, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
 Compute the sequence of joint values that correspond to a straight Cartesian path for a particular link.
 
static Distance computeCartesianPath (RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &path, const LinkModel *link, const Eigen::Vector3d &direction, bool global_reference_frame, double distance, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn())
 Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular link.
 
static Percentage computeCartesianPath (RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &path, const LinkModel *link, const Eigen::Isometry3d &target, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
 Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular frame.
 
static Percentage computeCartesianPath (RobotState *start_state, const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &path, const LinkModel *link, const EigenSTL::vector_Isometry3d &waypoints, bool global_reference_frame, const MaxEEFStep &max_step, const JumpThreshold &jump_threshold, const GroupStateValidityCallbackFn &validCallback=GroupStateValidityCallbackFn(), const kinematics::KinematicsQueryOptions &options=kinematics::KinematicsQueryOptions(), const kinematics::KinematicsBase::IKCostFn &cost_function=kinematics::KinematicsBase::IKCostFn(), const Eigen::Isometry3d &link_offset=Eigen::Isometry3d::Identity())
 Compute the sequence of joint values that perform a general Cartesian path.
 
static Percentage checkJointSpaceJump (const JointModelGroup *group, std::vector< std::shared_ptr< RobotState > > &path, const JumpThreshold &jump_threshold)
 Checks if a path has a joint-space jump, and truncates the path at the jump.
 

Detailed Description

Definition at line 105 of file cartesian_interpolator.h.

Member Function Documentation

◆ checkJointSpaceJump()

CartesianInterpolator::Percentage moveit::core::CartesianInterpolator::checkJointSpaceJump ( const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  path,
const JumpThreshold jump_threshold 
)
static

Checks if a path has a joint-space jump, and truncates the path at the jump.

Checks if a path has a jump larger than jump_threshold and truncates the path to the waypoint right before the jump. Returns the percentage of the path that doesn't have jumps.

Parameters
groupThe joint model group of the robot state.
pathThe path that should be tested.
jump_thresholdThe struct holding jump thresholds to determine if a joint space jump has occurred.
Returns
The fraction of the path that passed.

Definition at line 514 of file cartesian_interpolator.cpp.

Here is the call graph for this function:
Here is the caller graph for this function:

◆ computeCartesianPath() [1/8]

CartesianInterpolator::Percentage moveit::core::CartesianInterpolator::computeCartesianPath ( const RobotState start_state,
const JointModelGroup group,
std::vector< RobotStatePtr > &  traj,
const LinkModel link,
const Eigen::Isometry3d &  target,
bool  global_reference_frame,
const MaxEEFStep max_step,
const CartesianPrecision precision,
const GroupStateValidityCallbackFn validCallback,
const kinematics::KinematicsQueryOptions options,
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn(),
const Eigen::Isometry3d &  link_offset = Eigen::Isometry3d::Identity() 
)
static

Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular frame.

In contrast to the previous function, the Cartesian path is specified as a target frame to be reached (target) for a virtual frame attached to the robot link with the given link_offset. The target frame is assumed to be specified either w.r.t. to the global reference frame or the virtual link frame. This function returns the fraction (0..1) of path that was achieved. All other comments from the previous function apply.

Definition at line 206 of file cartesian_interpolator.cpp.

Here is the call graph for this function:

◆ computeCartesianPath() [2/8]

static Distance moveit::core::CartesianInterpolator::computeCartesianPath ( const RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  traj,
const LinkModel link,
const Eigen::Vector3d &  direction,
bool  global_reference_frame,
double  distance,
const MaxEEFStep max_step,
const CartesianPrecision precision,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn() 
)
inlinestatic

Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular link.

In contrast to the previous function, the translation vector is specified as a (unit) direction vector and a distance.

Definition at line 183 of file cartesian_interpolator.h.

Here is the call graph for this function:

◆ computeCartesianPath() [3/8]

static Distance moveit::core::CartesianInterpolator::computeCartesianPath ( const RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  traj,
const LinkModel link,
const Eigen::Vector3d &  translation,
bool  global_reference_frame,
const MaxEEFStep max_step,
const CartesianPrecision precision,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn() 
)
static

Compute the sequence of joint values that correspond to a straight Cartesian path for a particular link.

The Cartesian path to be followed is specified as a translation vector to be followed by the robot link. This vector is assumed to be specified either in the global reference frame or in the local reference frame of the link. The resulting joint values are stored in the vector traj, one by one. The interpolation distance in Cartesian space between consecutive points on the resulting path is specified in the MaxEEFStep struct which provides two fields: translation and rotation. If a validCallback is specified, this is passed to the internal call to setFromIK(). In case of IK failure, the computation of the path stops and the value returned corresponds to the distance that was achieved and for which corresponding states were added to the path.

The struct CartesianPrecision specifies the precision to which the path should follow the Cartesian straight line. If the deviation at the mid point of two consecutive waypoints is larger than the specified precision, another waypoint will be inserted at that mid point. The precision is specified separately for translation and rotation. The maximal resolution to consider (as fraction of the total path length) is specified by max_resolution.

Here is the caller graph for this function:

◆ computeCartesianPath() [4/8]

static Percentage moveit::core::CartesianInterpolator::computeCartesianPath ( const RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  traj,
const LinkModel link,
const EigenSTL::vector_Isometry3d &  waypoints,
bool  global_reference_frame,
const MaxEEFStep max_step,
const CartesianPrecision precision,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn(),
const Eigen::Isometry3d &  link_offset = Eigen::Isometry3d::Identity() 
)
static

Compute the sequence of joint values that perform a general Cartesian path.

In contrast to the previous functions, the Cartesian path is specified as a set of waypoints to be sequentially reached by the virtual frame attached to the robot link. The waypoints are transforms given either w.r.t. the global reference frame or the virtual frame at the immediately preceding waypoint. The virtual frame needs to move in a straight line between two consecutive waypoints. All other comments apply.

◆ computeCartesianPath() [5/8]

static Percentage moveit::core::CartesianInterpolator::computeCartesianPath ( RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  path,
const LinkModel link,
const Eigen::Isometry3d &  target,
bool  global_reference_frame,
const MaxEEFStep max_step,
const JumpThreshold jump_threshold,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn(),
const Eigen::Isometry3d &  link_offset = Eigen::Isometry3d::Identity() 
)
static

Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular frame.

In contrast to the previous function, the Cartesian path is specified as a target frame to be reached (target) for a virtual frame attached to the robot link with the given link_offset. The target frame is assumed to be specified either w.r.t. to the global reference frame or the virtual link frame (global_reference_frame is false). This function returns the percentage (0..1) of the path that was achieved. All other comments from the previous function apply.

◆ computeCartesianPath() [6/8]

static Distance moveit::core::CartesianInterpolator::computeCartesianPath ( RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  path,
const LinkModel link,
const Eigen::Vector3d &  direction,
bool  global_reference_frame,
double  distance,
const MaxEEFStep max_step,
const JumpThreshold jump_threshold,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn() 
)
inlinestatic

Compute the sequence of joint values that correspond to a straight Cartesian path, for a particular link.

In contrast to the previous function, the translation vector is specified as a (unit) direction vector and a distance.

Definition at line 262 of file cartesian_interpolator.h.

Here is the call graph for this function:

◆ computeCartesianPath() [7/8]

static Distance moveit::core::CartesianInterpolator::computeCartesianPath ( RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  path,
const LinkModel link,
const Eigen::Vector3d &  translation,
bool  global_reference_frame,
const MaxEEFStep max_step,
const JumpThreshold jump_threshold,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn() 
)
static

Compute the sequence of joint values that correspond to a straight Cartesian path for a particular link.

The Cartesian path to be followed is specified as a translation vector to be followed by the robot link. This vector is assumed to be specified either in the global reference frame or in the local reference frame of the link (global_reference_frame is false). The resulting joint values are stored in the vector path, one by one. The maximum distance in Cartesian space between consecutive points on the resulting path is specified in the MaxEEFStep struct which provides two fields: translation and rotation. If a validCallback is specified, this is passed to the internal call to setFromIK(). In case of IK failure, the computation of the path stops and the value returned corresponds to the distance that was achieved and for which corresponding states were added to the path. At the end of the function call, the state of the group corresponds to the last attempted Cartesian pose.

During the computation of the path, it is usually preferred if consecutive joint values do not 'jump' by a large amount in joint space, even if the Cartesian distance between the corresponding points is small as expected. To account for this, the jump_threshold struct is provided, which comprises three fields: jump_threshold_factor, revolute_jump_threshold and prismatic_jump_threshold. If either revolute_jump_threshold or prismatic_jump_threshold are non-zero, we test for absolute jumps. If jump_threshold_factor is non-zero, we test for relative jumps. To this end, the average joint-space distance between consecutive points in the trajectory is computed. If any individual joint-space motion delta is larger than this average distance multiplied by jump_threshold_factor, this step is considered a jump.

Otherwise (if all params are zero), jump detection is disabled. If a jump is detected, the path is truncated up to just before the jump.

Kinematics solvers may use cost functions to prioritize certain solutions, which may be specified with cost_function.

◆ computeCartesianPath() [8/8]

static Percentage moveit::core::CartesianInterpolator::computeCartesianPath ( RobotState start_state,
const JointModelGroup group,
std::vector< std::shared_ptr< RobotState > > &  path,
const LinkModel link,
const EigenSTL::vector_Isometry3d &  waypoints,
bool  global_reference_frame,
const MaxEEFStep max_step,
const JumpThreshold jump_threshold,
const GroupStateValidityCallbackFn validCallback = GroupStateValidityCallbackFn(),
const kinematics::KinematicsQueryOptions options = kinematics::KinematicsQueryOptions(),
const kinematics::KinematicsBase::IKCostFn cost_function = kinematics::KinematicsBase::IKCostFn(),
const Eigen::Isometry3d &  link_offset = Eigen::Isometry3d::Identity() 
)
static

Compute the sequence of joint values that perform a general Cartesian path.

In contrast to the previous functions, the Cartesian path is specified as a set of waypoints to be sequentially reached by the virtual frame attached to the robot link. The waypoints are transforms given either w.r.t. the global reference frame or the virtual frame at the immediately preceding waypoint. The virtual frame needs to move in a straight line between two consecutive waypoints. All other comments apply.


The documentation for this class was generated from the following files: