24#include <warehouse_ros/message_collection.h>
26#include <moveit_msgs/msg/robot_trajectory.hpp>
27#include <moveit_msgs/msg/motion_plan_request.hpp>
33namespace trajectory_cache
60 std::string
getName()
const override;
65 double exact_match_precision)
const override;
70 double exact_match_precision)
const override;
77 const std::string name_;
96 std::string
getName()
const override;
101 double exact_match_precision)
const override;
106 double exact_match_precision)
const override;
114 warehouse_ros::Query& query,
const moveit_msgs::msg::MotionPlanRequest& source,
117 const std::string name_;
118 const double match_tolerance_;
137 std::string
getName()
const override;
142 double exact_match_precision)
const override;
147 double exact_match_precision)
const override;
154 const std::string name_;
168 std::string
getName()
const override;
173 double exact_match_precision)
const override;
178 double exact_match_precision)
const override;
186 warehouse_ros::Query& query,
const moveit_msgs::msg::MotionPlanRequest& source,
189 const std::string name_;
190 const double match_tolerance_;
204 std::string
getName()
const override;
209 double exact_match_precision)
const override;
214 double exact_match_precision)
const override;
222 warehouse_ros::Query& query,
const moveit_msgs::msg::MotionPlanRequest& source,
225 const std::string name_;
226 const double match_tolerance_;
240 std::string
getName()
const override;
245 double exact_match_precision)
const override;
250 double exact_match_precision)
const override;
258 warehouse_ros::Query& query,
const moveit_msgs::msg::MotionPlanRequest& source,
261 const std::string name_;
262 const double match_tolerance_;
a wrapper around moveit_msgs::MoveItErrorCodes to make it easier to return an error code message from...
Client class to conveniently use the ROS interfaces provided by the move_group node.
Extracts features from the goal_constraints field in the plan request.
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 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 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.
std::string getName() const override
Gets the name of the features implementation.
Extracts max velocity and acceleration scaling, and cartesian speed limits from the plan request.
MaxSpeedAndAccelerationFeatures()
std::string getName() const override
Gets the name of the features implementation.
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 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 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.
Extracts features from the path_constraints field in the plan request.
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 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.
std::string getName() const override
Gets the name of the features implementation.
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.
Extracts details of the joint state from the start_state field in the plan request.
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 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 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.
std::string getName() const override
Gets the name of the features implementation.
Extracts features from the trajectory_constraints field in the plan request.
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 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.
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.
std::string getName() const override
Gets the name of the features implementation.
Extracts group name and details of the workspace_parameters field in the plan request.
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.
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.
std::string getName() const override
Gets the name of the features implementation.
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.
Abstract template class for extracting features from some FeatureSourceT.