moveit2
The MoveIt Motion Planning Framework for ROS 2.
Loading...
Searching...
No Matches
cache_insert_policy_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
22#pragma once
23
24#include <warehouse_ros/message_collection.h>
26
27namespace moveit_ros
28{
29namespace trajectory_cache
30{
31
122template <typename KeyT, typename ValueT, typename CacheEntryT>
124{
125public:
126 virtual ~CacheInsertPolicyInterface() = default;
127
129 virtual std::string getName() const = 0;
130
142 const warehouse_ros::MessageCollection<CacheEntryT>& coll, const KeyT& key,
143 const ValueT& value) = 0;
144
163 virtual std::vector<typename warehouse_ros::MessageWithMetadata<CacheEntryT>::ConstPtr>
165 const warehouse_ros::MessageCollection<CacheEntryT>& coll, const KeyT& key, const ValueT& value,
166 double exact_match_precision) = 0;
167
180 virtual bool
182 const ValueT& value,
183 const typename warehouse_ros::MessageWithMetadata<CacheEntryT>::ConstPtr& matching_entry,
184 std::string* reason) = 0;
185
198 const ValueT& value, std::string* reason) = 0;
199
213 appendInsertMetadata(warehouse_ros::Metadata& metadata,
215 const ValueT& value) = 0;
216
218 virtual void reset() = 0;
219};
220
221} // namespace trajectory_cache
222} // 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 bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const KeyT &key, const ValueT &value, std::string *reason)=0
Returns whether the insertion candidate should be inserted into the cache.
virtual bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const KeyT &key, const ValueT &value, const typename warehouse_ros::MessageWithMetadata< CacheEntryT >::ConstPtr &matching_entry, std::string *reason)=0
Returns whether a matched cache entry should be pruned.
virtual moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const KeyT &key, const ValueT &value)=0
Appends the insert metadata with the features supported by the policy.
virtual void reset()=0
Resets the state of the policy.
virtual std::vector< typename warehouse_ros::MessageWithMetadata< CacheEntryT >::ConstPtr > fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< CacheEntryT > &coll, const KeyT &key, const ValueT &value, double exact_match_precision)=0
Fetches all "matching" cache entries for comparison for pruning.
virtual std::string getName() const =0
Gets the name of the cache insert policy.
virtual moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< CacheEntryT > &coll, const KeyT &key, const ValueT &value)=0
Checks inputs to the cache insert call to see if we should abort instead.