24#include <warehouse_ros/message_collection.h>
29namespace trajectory_cache
122template <
typename KeyT,
typename ValueT,
typename CacheEntryT>
142 const warehouse_ros::MessageCollection<CacheEntryT>& coll,
const KeyT& key,
143 const ValueT& value) = 0;
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;
183 const typename warehouse_ros::MessageWithMetadata<CacheEntryT>::ConstPtr& matching_entry,
184 std::string* reason) = 0;
198 const ValueT& value, std::string* reason) = 0;
215 const ValueT& value) = 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 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 ~CacheInsertPolicyInterface()=default
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.