moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Classes | Functions
moveit_ros::trajectory_cache Namespace Reference

Classes

class  AlwaysInsertNeverPrunePolicy
 A cache insertion policy that always decides to insert and never decides to prune for motion plan requests. More...
 
class  BestSeenExecutionTimePolicy
 A cache insertion policy that only decides to insert if the motion plan is the one with the shortest execution time seen so far amongst exactly matching MotionPlanRequests. More...
 
class  CacheInsertPolicyInterface
 
class  CartesianAlwaysInsertNeverPrunePolicy
 A cache insertion policy that always decides to insert and never decides to prune for cartesian path requests. More...
 
class  CartesianBestSeenExecutionTimePolicy
 A cache insertion policy that only decides to insert if the motion plan is the one with the shortest execution time seen so far amongst exactly matching GetCartesianPath requests. More...
 
class  CartesianMaxSpeedAndAccelerationFeatures
 Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request. More...
 
class  CartesianMaxStepAndJumpThresholdFeatures
 Extracts max step and jump thresholds from the plan request. More...
 
class  CartesianPathConstraintsFeatures
 Extracts features from the path_constraints field in the plan request. More...
 
class  CartesianStartStateJointStateFeatures
 Extracts details of the joint state from the start_state field in the plan request. More...
 
class  CartesianWaypointsFeatures
 Extracts features from the waypoints and link_name field in the plan request. More...
 
class  CartesianWorkspaceFeatures
 Extracts group name and frame ID from the plan request. More...
 
class  FeaturesInterface
 
class  GoalConstraintsFeatures
 Extracts features from the goal_constraints field in the plan request. More...
 
class  MaxSpeedAndAccelerationFeatures
 Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request. More...
 
class  MetadataOnlyFeature
 
class  PathConstraintsFeatures
 Extracts features from the path_constraints field in the plan request. More...
 
class  QueryOnlyEqFeature
 
class  QueryOnlyGTEFeature
 
class  QueryOnlyLTEFeature
 
class  QueryOnlyRangeInclusiveWithToleranceFeature
 
class  StartStateJointStateFeatures
 Extracts details of the joint state from the start_state field in the plan request. More...
 
class  TrajectoryCache
 Trajectory Cache manager for MoveIt. More...
 
class  TrajectoryConstraintsFeatures
 Extracts features from the trajectory_constraints field in the plan request. More...
 
class  WorkspaceFeatures
 Extracts group name and details of the workspace_parameters field in the plan request. More...
 

Functions

std::string getWorkspaceFrameId (const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::WorkspaceParameters &workspace_parameters)
 Gets workspace frame ID. If workspace_parameters has no frame ID, fetch it from move_group.
 
std::string getCartesianPathRequestFrameId (const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &path_request)
 Gets cartesian path request frame ID. If path_request has no frame ID, fetch it from move_group.
 
moveit::core::MoveItErrorCode restateInNewFrame (const std::shared_ptr< tf2_ros::Buffer > &tf, const std::string &target_frame, const std::string &source_frame, geometry_msgs::msg::Point *translation, geometry_msgs::msg::Quaternion *rotation, const tf2::TimePoint &lookup_time=tf2::TimePointZero)
 Restates a translation and rotation in a new frame.
 
double getExecutionTime (const moveit_msgs::msg::RobotTrajectory &trajectory)
 Returns the execution time of the trajectory in double seconds.
 
moveit_msgs::srv::GetCartesianPath::Request constructGetCartesianPathRequest (moveit::planning_interface::MoveGroupInterface &move_group, const std::vector< geometry_msgs::msg::Pose > &waypoints, double max_step, double jump_threshold, bool avoid_collisions=true)
 Constructs a GetCartesianPath request.
 
void queryAppendCenterWithTolerance (warehouse_ros::Query &query, const std::string &name, double center, double tolerance)
 Appends a range inclusive query with some tolerance about some center value.
 
void sortJointConstraints (std::vector< moveit_msgs::msg::JointConstraint > &joint_constraints)
 Sorts a vector of joint constraints in-place by joint name.
 
void sortPositionConstraints (std::vector< moveit_msgs::msg::PositionConstraint > &position_constraints)
 Sorts a vector of position constraints in-place by link name.
 
void sortOrientationConstraints (std::vector< moveit_msgs::msg::OrientationConstraint > &orientation_constraints)
 Sorts a vector of orientation constraints in-place by link name.
 
moveit::core::MoveItErrorCode appendConstraintsAsFetchQueryWithTolerance (warehouse_ros::Query &query, std::vector< moveit_msgs::msg::Constraints > constraints, const moveit::planning_interface::MoveGroupInterface &move_group, double match_tolerance, const std::string &reference_frame_id, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.
 
moveit::core::MoveItErrorCode appendConstraintsAsInsertMetadata (warehouse_ros::Metadata &metadata, std::vector< moveit_msgs::msg::Constraints > constraints, const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &reference_frame_id, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.
 
moveit::core::MoveItErrorCode appendRobotStateJointStateAsFetchQueryWithTolerance (warehouse_ros::Query &query, const moveit_msgs::msg::RobotState &robot_state, const moveit::planning_interface::MoveGroupInterface &move_group, double match_tolerance, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.
 
moveit::core::MoveItErrorCode appendRobotStateJointStateAsInsertMetadata (warehouse_ros::Metadata &metadata, const moveit_msgs::msg::RobotState &robot_state, const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &prefix)
 Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.
 
std::string getWorkspaceFrameId (const MoveGroupInterface &move_group, const moveit_msgs::msg::WorkspaceParameters &workspace_parameters)
 
std::string getCartesianPathRequestFrameId (const MoveGroupInterface &move_group, const GetCartesianPath::Request &path_request)
 
GetCartesianPath::Request constructGetCartesianPathRequest (MoveGroupInterface &move_group, const std::vector< geometry_msgs::msg::Pose > &waypoints, double max_step, double jump_threshold, bool avoid_collisions)
 
void queryAppendCenterWithTolerance (Query &query, const std::string &name, double center, double tolerance)
 
moveit::core::MoveItErrorCode appendConstraintsAsFetchQueryWithTolerance (Query &query, std::vector< moveit_msgs::msg::Constraints > constraints, const MoveGroupInterface &move_group, double match_tolerance, const std::string &reference_frame_id, const std::string &prefix)
 
moveit::core::MoveItErrorCode appendConstraintsAsInsertMetadata (Metadata &metadata, std::vector< moveit_msgs::msg::Constraints > constraints, const MoveGroupInterface &move_group, const std::string &workspace_frame_id, const std::string &prefix)
 
moveit::core::MoveItErrorCode appendRobotStateJointStateAsFetchQueryWithTolerance (Query &query, const moveit_msgs::msg::RobotState &robot_state, const MoveGroupInterface &move_group, double match_tolerance, const std::string &prefix)
 
moveit::core::MoveItErrorCode appendRobotStateJointStateAsInsertMetadata (Metadata &metadata, const moveit_msgs::msg::RobotState &robot_state, const MoveGroupInterface &move_group, const std::string &prefix)
 

Function Documentation

◆ appendConstraintsAsFetchQueryWithTolerance() [1/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsFetchQueryWithTolerance ( Query &  query,
std::vector< moveit_msgs::msg::Constraints >  constraints,
const MoveGroupInterface &  move_group,
double  match_tolerance,
const std::string &  reference_frame_id,
const std::string &  prefix 
)

Definition at line 212 of file utils.cpp.

Here is the call graph for this function:

◆ appendConstraintsAsFetchQueryWithTolerance() [2/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsFetchQueryWithTolerance ( warehouse_ros::Query &  query,
std::vector< moveit_msgs::msg::Constraints >  constraints,
const moveit::planning_interface::MoveGroupInterface move_group,
double  match_tolerance,
const std::string &  reference_frame_id,
const std::string &  prefix 
)

Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.

This will extract relevant features from the joint, position, and orientation constraints per element. This exists because many keyable messages contain constraints which should be handled similarly.

WARNING: Visibility constraints are not supported.

Additionally, the component constraints within each vector element are sorted to reduce cache cardinality. For the same reason, constraints with frames are restated in terms of the workspace frame.

We copy the input constraints to support this.

Parameters
[in,out]query.The query to add features to.
[in]constraints.The constraints to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]reference_frame_id.The frame to restate constraints in.
[in]prefix.A prefix to add to feature keys.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

◆ appendConstraintsAsInsertMetadata() [1/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsInsertMetadata ( Metadata &  metadata,
std::vector< moveit_msgs::msg::Constraints >  constraints,
const MoveGroupInterface &  move_group,
const std::string &  workspace_frame_id,
const std::string &  prefix 
)

Definition at line 362 of file utils.cpp.

Here is the call graph for this function:

◆ appendConstraintsAsInsertMetadata() [2/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendConstraintsAsInsertMetadata ( warehouse_ros::Metadata &  metadata,
std::vector< moveit_msgs::msg::Constraints >  constraints,
const moveit::planning_interface::MoveGroupInterface move_group,
const std::string &  reference_frame_id,
const std::string &  prefix 
)

Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.

This will extract relevant features from the joint, position, and orientation constraints per element. This exists because many keyable messages contain constraints which should be handled similarly.

WARNING: Visibility constraints and constraint regions are not supported.

Additionally, the component constraints within each vector element are sorted to reduce cache cardinality. For the same reason, constraints with frames are restated in terms of the workspace frame.

We copy the input constraints to support this.

Parameters
[in,out]metadata.The metadata to add features to.
[in]constraints.The constraints to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]reference_frame_id.The frame to restate constraints in.
[in]prefix.A prefix to add to feature keys.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the metadata should not be reused.
Here is the caller graph for this function:

◆ appendRobotStateJointStateAsFetchQueryWithTolerance() [1/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsFetchQueryWithTolerance ( Query &  query,
const moveit_msgs::msg::RobotState &  robot_state,
const MoveGroupInterface &  move_group,
double  match_tolerance,
const std::string &  prefix 
)

Definition at line 514 of file utils.cpp.

Here is the call graph for this function:

◆ appendRobotStateJointStateAsFetchQueryWithTolerance() [2/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsFetchQueryWithTolerance ( warehouse_ros::Query &  query,
const moveit_msgs::msg::RobotState &  robot_state,
const moveit::planning_interface::MoveGroupInterface move_group,
double  match_tolerance,
const std::string &  prefix 
)

Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a fetch query, with tolerance.

This will extract relevant features from the joint, position, and orientation constraints per element. This exists because many keyable messages contain constraints which should be handled similarly.

WARNING: Visibility constraints are not supported.

Additionally, the component constraints within each vector element are sorted to reduce cache cardinality. For the same reason, constraints with frames are restated in terms of the workspace frame.

We copy the input constraints to support this.

Parameters
[in,out]query.The query to add features to.
[in]robot_state.The robot state to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]prefix.A prefix to add to feature keys.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

◆ appendRobotStateJointStateAsInsertMetadata() [1/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsInsertMetadata ( Metadata &  metadata,
const moveit_msgs::msg::RobotState &  robot_state,
const MoveGroupInterface &  move_group,
const std::string &  prefix 
)

Definition at line 583 of file utils.cpp.

◆ appendRobotStateJointStateAsInsertMetadata() [2/2]

moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::appendRobotStateJointStateAsInsertMetadata ( warehouse_ros::Metadata &  metadata,
const moveit_msgs::msg::RobotState &  robot_state,
const moveit::planning_interface::MoveGroupInterface move_group,
const std::string &  prefix 
)

Extracts relevant features from a vector of moveit_msgs::msg::Constraints messages to a cache entry's metadata.

This will extract relevant features from the joint, position, and orientation constraints per element. This exists because many keyable messages contain constraints which should be handled similarly.

WARNING: Visibility constraints and constraint regions are not supported.

Additionally, the component constraints within each vector element are sorted to reduce cache cardinality. For the same reason, constraints with frames are restated in terms of the workspace frame.

We copy the input constraints to support this.

Parameters
[in,out]metadata.The metadata to add features to.
[in]robot_state.The robot state to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]prefix.A prefix to add to feature keys.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the metadata should not be reused.
Here is the caller graph for this function:

◆ constructGetCartesianPathRequest() [1/2]

GetCartesianPath::Request moveit_ros::trajectory_cache::constructGetCartesianPathRequest ( MoveGroupInterface &  move_group,
const std::vector< geometry_msgs::msg::Pose > &  waypoints,
double  max_step,
double  jump_threshold,
bool  avoid_collisions 
)

Definition at line 153 of file utils.cpp.

Here is the call graph for this function:

◆ constructGetCartesianPathRequest() [2/2]

moveit_msgs::srv::GetCartesianPath::Request moveit_ros::trajectory_cache::constructGetCartesianPathRequest ( moveit::planning_interface::MoveGroupInterface move_group,
const std::vector< geometry_msgs::msg::Pose > &  waypoints,
double  max_step,
double  jump_threshold,
bool  avoid_collisions = true 
)

Constructs a GetCartesianPath request.

This is a convenience function. This mimics the move group computeCartesianPath signature (without path constraints).

WARNING: The following fields are not supported, if you want to specify them, add them in yourself.

  • prismatic_jump_threshold
  • revolute_jump_threshold
  • cartesian_speed_limited_link
  • max_cartesian_speed
Parameters
[in]move_group.The manipulator move group, used to get its state, frames, and link.
[in]waypoints.The cartesian waypoints to request the path for.
[in]max_step.The value to populate into the GetCartesianPath request's max_step field.
[in]jump_threshold.The value to populate into the GetCartesianPath request's jump_threshold field.
[in]avoid_collisions.The value to populate into the GetCartesianPath request's avoid_collisions field.
Returns
Here is the call graph for this function:
Here is the caller graph for this function:

◆ getCartesianPathRequestFrameId() [1/2]

std::string moveit_ros::trajectory_cache::getCartesianPathRequestFrameId ( const MoveGroupInterface &  move_group,
const GetCartesianPath::Request &  path_request 
)

Definition at line 75 of file utils.cpp.

◆ getCartesianPathRequestFrameId() [2/2]

std::string moveit_ros::trajectory_cache::getCartesianPathRequestFrameId ( const moveit::planning_interface::MoveGroupInterface move_group,
const moveit_msgs::srv::GetCartesianPath::Request &  path_request 
)

Gets cartesian path request frame ID. If path_request has no frame ID, fetch it from move_group.

It makes sense to use getPoseReferenceFrame() in the absence of a frame ID in the request because the same method is used to populate the header frame ID in the MoveGroupInterface's computeCartesianPath() method, which this function is associated with.

Here is the caller graph for this function:

◆ getExecutionTime()

double moveit_ros::trajectory_cache::getExecutionTime ( const moveit_msgs::msg::RobotTrajectory &  trajectory)

Returns the execution time of the trajectory in double seconds.

Definition at line 146 of file utils.cpp.

Here is the caller graph for this function:

◆ getWorkspaceFrameId() [1/2]

std::string moveit_ros::trajectory_cache::getWorkspaceFrameId ( const MoveGroupInterface &  move_group,
const moveit_msgs::msg::WorkspaceParameters &  workspace_parameters 
)

Definition at line 62 of file utils.cpp.

◆ getWorkspaceFrameId() [2/2]

std::string moveit_ros::trajectory_cache::getWorkspaceFrameId ( const moveit::planning_interface::MoveGroupInterface move_group,
const moveit_msgs::msg::WorkspaceParameters &  workspace_parameters 
)

Gets workspace frame ID. If workspace_parameters has no frame ID, fetch it from move_group.

It makes sense to use getPoseReferenceFrame() in the absence of a frame ID in the request because the same method is used to populate the header frame ID in the MoveGroupInterface's computeCartesianPath() method, which this function is associated with.

Here is the caller graph for this function:

◆ queryAppendCenterWithTolerance() [1/2]

void moveit_ros::trajectory_cache::queryAppendCenterWithTolerance ( Query &  query,
const std::string &  name,
double  center,
double  tolerance 
)

Definition at line 180 of file utils.cpp.

◆ queryAppendCenterWithTolerance() [2/2]

void moveit_ros::trajectory_cache::queryAppendCenterWithTolerance ( warehouse_ros::Query &  query,
const std::string &  name,
double  center,
double  tolerance 
)

Appends a range inclusive query with some tolerance about some center value.

Here is the caller graph for this function:

◆ restateInNewFrame()

MoveItErrorCode moveit_ros::trajectory_cache::restateInNewFrame ( const std::shared_ptr< tf2_ros::Buffer > &  tf,
const std::string &  target_frame,
const std::string &  source_frame,
geometry_msgs::msg::Point *  translation,
geometry_msgs::msg::Quaternion *  rotation,
const tf2::TimePoint &  lookup_time = tf2::TimePointZero 
)

Restates a translation and rotation in a new frame.

Parameters
[in]tf.The transform buffer to use.
[in]target_frame.The frame to restate in.
[in]source_frame.The frame to restate from.
[in,out]translation.The translation to restate. Ignored if nullptr.
[in,out]rotation.The rotation to restate. Ignored if nullptr.
Returns
MoveItErrorCode::SUCCESS if successfully restated. Otherwise, will return return MoveItErrorCode::FRAME_TRANSFORM_FAILURE if the transform could not be retrieved.

Definition at line 88 of file utils.cpp.

Here is the caller graph for this function:

◆ sortJointConstraints()

void moveit_ros::trajectory_cache::sortJointConstraints ( std::vector< moveit_msgs::msg::JointConstraint > &  joint_constraints)

Sorts a vector of joint constraints in-place by joint name.

Definition at line 187 of file utils.cpp.

Here is the caller graph for this function:

◆ sortOrientationConstraints()

void moveit_ros::trajectory_cache::sortOrientationConstraints ( std::vector< moveit_msgs::msg::OrientationConstraint > &  orientation_constraints)

Sorts a vector of orientation constraints in-place by link name.

Definition at line 203 of file utils.cpp.

Here is the caller graph for this function:

◆ sortPositionConstraints()

void moveit_ros::trajectory_cache::sortPositionConstraints ( std::vector< moveit_msgs::msg::PositionConstraint > &  position_constraints)

Sorts a vector of position constraints in-place by link name.

Definition at line 195 of file utils.cpp.

Here is the caller graph for this function: