moveit2
The MoveIt Motion Planning Framework for ROS 2.
features_interface.hpp
Go to the documentation of this file.
1 // Copyright 2024 Intrinsic Innovation LLC.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
20 #pragma once
21 
22 #include <warehouse_ros/message_collection.h>
24 
25 namespace moveit_ros
26 {
27 namespace trajectory_cache
28 {
29 
96 template <typename FeatureSourceT>
98 {
99 public:
100  virtual ~FeaturesInterface() = default;
101 
103  virtual std::string getName() const = 0;
104 
118  appendFeaturesAsFuzzyFetchQuery(warehouse_ros::Query& query, const FeatureSourceT& source,
120  double exact_match_precision) const = 0;
121 
135  appendFeaturesAsExactFetchQuery(warehouse_ros::Query& query, const FeatureSourceT& source,
137  double exact_match_precision) const = 0;
138 
151  appendFeaturesAsInsertMetadata(warehouse_ros::Metadata& metadata, const FeatureSourceT& source,
153 };
154 
155 } // namespace trajectory_cache
156 } // namespace moveit_ros
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 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.