moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
#include <cartesian_interpolator.h>
Classes | |
struct | Distance |
struct | Percentage |
Static Public Member Functions | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
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. More... | |
Definition at line 97 of file cartesian_interpolator.h.
|
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.
group | The joint model group of the robot state. |
path | The path that should be tested. |
jump_threshold | The struct holding jump thresholds to determine if a joint space jump has occurred. |
Definition at line 340 of file cartesian_interpolator.cpp.
|
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.
|
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 178 of file cartesian_interpolator.h.
|
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 argument is provided. If a jump detection is enabled and a jump is found, 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.
|
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.