Template Class FeaturesInterface
Defined in File features_interface.hpp
Inheritance Relationships
Derived Types
public moveit_ros::trajectory_cache::MetadataOnlyFeature< AppendT, FeatureSourceT >
(Template Class MetadataOnlyFeature)public moveit_ros::trajectory_cache::QueryOnlyEqFeature< AppendT, FeatureSourceT >
(Template Class QueryOnlyEqFeature)public moveit_ros::trajectory_cache::QueryOnlyGTEFeature< AppendT, FeatureSourceT >
(Template Class QueryOnlyGTEFeature)public moveit_ros::trajectory_cache::QueryOnlyLTEFeature< AppendT, FeatureSourceT >
(Template Class QueryOnlyLTEFeature)public moveit_ros::trajectory_cache::QueryOnlyRangeInclusiveWithToleranceFeature< AppendT, FeatureSourceT >
(Template Class QueryOnlyRangeInclusiveWithToleranceFeature)
Class Documentation
-
template<typename FeatureSourceT>
class FeaturesInterface Subclassed by moveit_ros::trajectory_cache::MetadataOnlyFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyEqFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyGTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyLTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyRangeInclusiveWithToleranceFeature< AppendT, FeatureSourceT >
Public Functions
-
virtual ~FeaturesInterface() = default
-
virtual std::string getName() const = 0
Gets the name of the features implementation.
-
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.
These parameters will be used key the cache element in a fuzzy manner.
- Parameters:
query. – [inout] The query to add features to.
source. – [in] A FeatureSourceT to extract features from.
move_group. – [in] The manipulator move group, used to get its state.
exact_match_precision. – [in] 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.
-
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.
These parameters will be used key the cache element in an exact manner.
- Parameters:
query. – [inout] The query to add features to.
source. – [in] A FeatureSourceT to extract features from.
move_group. – [in] The manipulator move group, used to get its state.
exact_match_precision. – [in] 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.
-
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.
These parameters will be used key the cache element.
- Parameters:
metadata. – [inout] The metadata to add features to.
source. – [in] A FeatureSourceT to extract features from.
move_group. – [in] 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.
-
virtual ~FeaturesInterface() = default