Template Class CacheInsertPolicyInterface
Defined in File cache_insert_policy_interface.hpp
Class Documentation
-
template<typename KeyT, typename ValueT, typename CacheEntryT>
class CacheInsertPolicyInterface Public Functions
-
virtual ~CacheInsertPolicyInterface() = default
-
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.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
coll. – [in] The cache database to fetch messages from.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
- Returns:
moveit::core::MoveItErrorCode::SUCCESS if the cache insert should proceed. Otherwise, will return a different error code with the reason why it should not.
-
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.
This method should be assumed to only return the message metadata without the underlying message data.
The policy should also make the decision about how to sort them. The order in which cache entries are presented to the shouldPruneMatchingEntry will be the order of cache entries returned by this function.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
coll. – [in] The cache database to fetch messages from.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
exact_match_precision. – [in] Tolerance for float precision comparison for what counts as an exact match.
- Returns:
A vector of only the metadata of matching cache entries for use by the other methods.
-
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.
NOTE: The TrajectoryCache class also has some top-level logic to preserve cache entries that would have been pruned.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
matching_entry. – [in] The matched cache entry to be possibly pruned.
reason. – [out] The reason for the returned result.
- Returns:
True if the cache entry should be pruned.
-
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.
NOTE: The TrajectoryCache class executes the insert, but this class informs it on whether the insert should happen or not.
- Parameters:
move_group. – [in] The manipulator move group, used to get its state.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
reason. – [out] The reason for the returned result.
- Returns:
True if the insertion candidate should be inserted into the cache.
-
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.
See notes in docstrings regarding the feature contract.
- Parameters:
metadata. – [inout] The metadata to add features to.
move_group. – [in] The manipulator move group, used to get its state.
key. – [in] The object used to key the insertion candidate with.
value. – [in] The object that the TrajectoryCache was passed to insert.
- Returns:
moveit::core::MoveItErrorCode::SUCCESS if successfully appended. Otherwise, will return a different error code, in which case the metadata should not be reused, and the TrajectoryCache will abort the insert.
-
virtual void reset() = 0
Resets the state of the policy.
-
virtual ~CacheInsertPolicyInterface() = default