moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
moveit_ros::trajectory_cache::WorkspaceFeatures Class Referencefinal

Extracts group name and details of the workspace_parameters field in the plan request. More...

#include <motion_plan_request_features.hpp>

Inheritance diagram for moveit_ros::trajectory_cache::WorkspaceFeatures:
Inheritance graph
[legend]
Collaboration diagram for moveit_ros::trajectory_cache::WorkspaceFeatures:
Collaboration graph
[legend]

Public Member Functions

 WorkspaceFeatures ()
 
std::string getName () const override
 Gets the name of the features implementation.
 
moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery (warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
 Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.
 
moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery (warehouse_ros::Query &query, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const override
 Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
 
moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata (warehouse_ros::Metadata &metadata, const moveit_msgs::msg::MotionPlanRequest &source, const moveit::planning_interface::MoveGroupInterface &move_group) const override
 Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
 
- Public Member Functions inherited from moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >
virtual ~FeaturesInterface ()=default
 

Detailed Description

Extracts group name and details of the workspace_parameters field in the plan request.

A cache hit with this feature is valid if the requested planning constraints has a workspace that completely subsumes a cached entry's workspace.

For example: (We ignore z for simplicity) If workspace is defined by the extrema (x_min, y_min, x_max, y_max),

Potential valid match if other constraints fulfilled: Request: (-1, -1, 1, 1) Plan in cache: (-0.5, -0.5, 0.5, 0.5)

No match, since this plan might cause the end effector to go out of bounds.: Request: (-1, -1, 1, 1) Plan in cache: (-2, -0.5, 0.5, 0.5)

Definition at line 55 of file motion_plan_request_features.hpp.

Constructor & Destructor Documentation

◆ WorkspaceFeatures()

moveit_ros::trajectory_cache::WorkspaceFeatures::WorkspaceFeatures ( )

Definition at line 50 of file motion_plan_request_features.cpp.

Member Function Documentation

◆ appendFeaturesAsExactFetchQuery()

MoveItErrorCode moveit_ros::trajectory_cache::WorkspaceFeatures::appendFeaturesAsExactFetchQuery ( warehouse_ros::Query &  query,
const moveit_msgs::msg::MotionPlanRequest &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
overridevirtual

Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.

These parameters will be used key the cache element in an exact manner.

Parameters
[in,out]query.The query to add features to.
[in]source.A FeatureSourceT to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]exact_match_precision.Tolerance for float precision comparison for what counts as an exact match.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.

Definition at line 66 of file motion_plan_request_features.cpp.

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

◆ appendFeaturesAsFuzzyFetchQuery()

MoveItErrorCode moveit_ros::trajectory_cache::WorkspaceFeatures::appendFeaturesAsFuzzyFetchQuery ( warehouse_ros::Query &  query,
const moveit_msgs::msg::MotionPlanRequest &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
overridevirtual

Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.

These parameters will be used key the cache element in a fuzzy manner.

Parameters
[in,out]query.The query to add features to.
[in]source.A FeatureSourceT to extract features from.
[in]move_group.The manipulator move group, used to get its state.
[in]exact_match_precision.Tolerance for float precision comparison for what counts as an exact match.
Returns
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the query should not be reused.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.

Definition at line 59 of file motion_plan_request_features.cpp.

Here is the call graph for this function:

◆ appendFeaturesAsInsertMetadata()

MoveItErrorCode moveit_ros::trajectory_cache::WorkspaceFeatures::appendFeaturesAsInsertMetadata ( warehouse_ros::Metadata &  metadata,
const moveit_msgs::msg::MotionPlanRequest &  source,
const moveit::planning_interface::MoveGroupInterface move_group 
) const
overridevirtual

Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.

These parameters will be used key the cache element.

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

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.

Definition at line 82 of file motion_plan_request_features.cpp.

Here is the call graph for this function:

◆ getName()

std::string moveit_ros::trajectory_cache::WorkspaceFeatures::getName ( ) const
overridevirtual

Gets the name of the features implementation.

Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.

Definition at line 54 of file motion_plan_request_features.cpp.


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