moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
Public Member Functions | List of all members
moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT > Class Template Referenceabstract

#include <features_interface.hpp>

Inheritance diagram for moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >:
Inheritance graph
[legend]

Public Member 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.
 
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 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.
 

Detailed Description

template<typename FeatureSourceT>
class moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >

Definition at line 97 of file features_interface.hpp.

Constructor & Destructor Documentation

◆ ~FeaturesInterface()

template<typename FeatureSourceT >
virtual moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >::~FeaturesInterface ( )
virtualdefault

Member Function Documentation

◆ appendFeaturesAsExactFetchQuery()

template<typename FeatureSourceT >
virtual moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >::appendFeaturesAsExactFetchQuery ( warehouse_ros::Query &  query,
const FeatureSourceT &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
pure virtual

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.

Implemented in moveit_ros::trajectory_cache::MetadataOnlyFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyEqFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyLTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyGTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyRangeInclusiveWithToleranceFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::WorkspaceFeatures, moveit_ros::trajectory_cache::StartStateJointStateFeatures, moveit_ros::trajectory_cache::MaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::GoalConstraintsFeatures, moveit_ros::trajectory_cache::PathConstraintsFeatures, moveit_ros::trajectory_cache::TrajectoryConstraintsFeatures, moveit_ros::trajectory_cache::CartesianWorkspaceFeatures, moveit_ros::trajectory_cache::CartesianStartStateJointStateFeatures, moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::CartesianMaxStepAndJumpThresholdFeatures, moveit_ros::trajectory_cache::CartesianWaypointsFeatures, and moveit_ros::trajectory_cache::CartesianPathConstraintsFeatures.

◆ appendFeaturesAsFuzzyFetchQuery()

template<typename FeatureSourceT >
virtual moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >::appendFeaturesAsFuzzyFetchQuery ( warehouse_ros::Query &  query,
const FeatureSourceT &  source,
const moveit::planning_interface::MoveGroupInterface move_group,
double  exact_match_precision 
) const
pure virtual

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.

Implemented in moveit_ros::trajectory_cache::MetadataOnlyFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyEqFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyLTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyGTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyRangeInclusiveWithToleranceFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::WorkspaceFeatures, moveit_ros::trajectory_cache::StartStateJointStateFeatures, moveit_ros::trajectory_cache::MaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::GoalConstraintsFeatures, moveit_ros::trajectory_cache::PathConstraintsFeatures, moveit_ros::trajectory_cache::TrajectoryConstraintsFeatures, moveit_ros::trajectory_cache::CartesianWorkspaceFeatures, moveit_ros::trajectory_cache::CartesianStartStateJointStateFeatures, moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::CartesianMaxStepAndJumpThresholdFeatures, moveit_ros::trajectory_cache::CartesianWaypointsFeatures, and moveit_ros::trajectory_cache::CartesianPathConstraintsFeatures.

◆ appendFeaturesAsInsertMetadata()

template<typename FeatureSourceT >
virtual moveit::core::MoveItErrorCode moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >::appendFeaturesAsInsertMetadata ( warehouse_ros::Metadata &  metadata,
const FeatureSourceT &  source,
const moveit::planning_interface::MoveGroupInterface move_group 
) const
pure virtual

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.

Implemented in moveit_ros::trajectory_cache::QueryOnlyEqFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyLTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyGTEFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::QueryOnlyRangeInclusiveWithToleranceFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::MetadataOnlyFeature< AppendT, FeatureSourceT >, moveit_ros::trajectory_cache::WorkspaceFeatures, moveit_ros::trajectory_cache::StartStateJointStateFeatures, moveit_ros::trajectory_cache::MaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::GoalConstraintsFeatures, moveit_ros::trajectory_cache::PathConstraintsFeatures, moveit_ros::trajectory_cache::TrajectoryConstraintsFeatures, moveit_ros::trajectory_cache::CartesianWorkspaceFeatures, moveit_ros::trajectory_cache::CartesianStartStateJointStateFeatures, moveit_ros::trajectory_cache::CartesianMaxSpeedAndAccelerationFeatures, moveit_ros::trajectory_cache::CartesianMaxStepAndJumpThresholdFeatures, moveit_ros::trajectory_cache::CartesianWaypointsFeatures, and moveit_ros::trajectory_cache::CartesianPathConstraintsFeatures.

◆ getName()

template<typename FeatureSourceT >
virtual std::string moveit_ros::trajectory_cache::FeaturesInterface< FeatureSourceT >::getName ( ) const
pure virtual

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