Program Listing for File cache_insert_policy_interface.hpp
↰ Return to documentation for file (include/moveit/trajectory_cache/cache_insert_policies/cache_insert_policy_interface.hpp
)
// Copyright 2024 Intrinsic Innovation LLC.
//
// Licensed under the Apache License, Version 2.0 (the "License");
// you may not use this file except in compliance with the License.
// You may obtain a copy of the License at
//
// http://www.apache.org/licenses/LICENSE-2.0
//
// Unless required by applicable law or agreed to in writing, software
// distributed under the License is distributed on an "AS IS" BASIS,
// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
// See the License for the specific language governing permissions and
// limitations under the License.
#pragma once
#include <warehouse_ros/message_collection.h>
#include <moveit/move_group_interface/move_group_interface.hpp>
namespace moveit_ros
{
namespace trajectory_cache
{
template <typename KeyT, typename ValueT, typename CacheEntryT>
class CacheInsertPolicyInterface
{
public:
virtual ~CacheInsertPolicyInterface() = default;
virtual std::string getName() const = 0;
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;
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;
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;
virtual bool shouldInsert(const moveit::planning_interface::MoveGroupInterface& move_group, const KeyT& key,
const ValueT& value, std::string* reason) = 0;
virtual moveit::core::MoveItErrorCode
appendInsertMetadata(warehouse_ros::Metadata& metadata,
const moveit::planning_interface::MoveGroupInterface& move_group, const KeyT& key,
const ValueT& value) = 0;
virtual void reset() = 0;
};
} // namespace trajectory_cache
} // namespace moveit_ros