moveit2
The MoveIt Motion Planning Framework for ROS 2.
|
Extracts group name and details of the workspace_parameters
field in the plan request.
More...
#include <motion_plan_request_features.hpp>
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 |
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.
moveit_ros::trajectory_cache::WorkspaceFeatures::WorkspaceFeatures | ( | ) |
Definition at line 50 of file motion_plan_request_features.cpp.
|
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.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.
Definition at line 66 of file motion_plan_request_features.cpp.
|
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.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.
Definition at line 59 of file motion_plan_request_features.cpp.
|
overridevirtual |
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
These parameters will be used key the cache element.
[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. |
Implements moveit_ros::trajectory_cache::FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >.
Definition at line 82 of file motion_plan_request_features.cpp.
|
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.