22#include <warehouse_ros/message_collection.h>
27namespace trajectory_cache
96template <
typename FeatureSourceT>
120 double exact_match_precision)
const = 0;
137 double exact_match_precision)
const = 0;
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.
virtual std::string getName() const =0
Gets the name of the features implementation.
virtual ~FeaturesInterface()=default
virtual moveit::core::MoveItErrorCode appendFeaturesAsInsertMetadata(warehouse_ros::Metadata &metadata, const FeatureSourceT &source, const moveit::planning_interface::MoveGroupInterface &move_group) const =0
Extracts relevant features from FeatureSourceT, to be appended to a cache entry's metadata.
virtual moveit::core::MoveItErrorCode appendFeaturesAsExactFetchQuery(warehouse_ros::Query &query, const FeatureSourceT &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const =0
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with exact matching.
virtual moveit::core::MoveItErrorCode appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query &query, const FeatureSourceT &source, const moveit::planning_interface::MoveGroupInterface &move_group, double exact_match_precision) const =0
Extracts relevant features from FeatureSourceT, to be appended to a fetch query, with fuzzy matching.