28#include <warehouse_ros/message_collection.h>
30#include <moveit_msgs/msg/motion_plan_request.hpp>
31#include <moveit_msgs/msg/robot_trajectory.hpp>
32#include <moveit_msgs/srv/get_cartesian_path.hpp>
39namespace trajectory_cache
77 moveit::planning_interface::MoveGroupInterface::Plan,
78 moveit_msgs::msg::RobotTrajectory>
82 static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>
87 std::string
getName()
const override;
91 const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
92 const moveit_msgs::msg::MotionPlanRequest& key,
95 std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
97 const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
98 const moveit_msgs::msg::MotionPlanRequest& key,
100 double exact_match_precision)
override;
105 const warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr& matching_entry,
106 std::string* reason =
nullptr)
override;
109 const moveit_msgs::msg::MotionPlanRequest& key,
111 std::string* reason =
nullptr)
override;
116 const moveit_msgs::msg::MotionPlanRequest& key,
119 void reset()
override;
122 const std::string name_;
123 std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>> exact_matching_supported_features_;
167 moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory>
171 static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>
176 std::string
getName()
const override;
180 const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
181 const moveit_msgs::srv::GetCartesianPath::Request& key,
182 const moveit_msgs::srv::GetCartesianPath::Response& value)
override;
184 std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
186 const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
187 const moveit_msgs::srv::GetCartesianPath::Request& key,
188 const moveit_msgs::srv::GetCartesianPath::Response& value,
189 double exact_match_precision)
override;
193 const moveit_msgs::srv::GetCartesianPath::Request& key,
const moveit_msgs::srv::GetCartesianPath::Response& value,
194 const warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr& matching_entry,
195 std::string* reason =
nullptr)
override;
198 const moveit_msgs::srv::GetCartesianPath::Request& key,
199 const moveit_msgs::srv::GetCartesianPath::Response& value, std::string* reason =
nullptr)
override;
203 const moveit_msgs::srv::GetCartesianPath::Request& key,
204 const moveit_msgs::srv::GetCartesianPath::Response& value)
override;
206 void reset()
override;
209 const std::string name_;
210 std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>
211 exact_matching_supported_features_;
Abstract template class for injecting logic for determining when to prune and insert a cache entry,...
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.
A cache insertion policy that always decides to insert and never decides to prune for motion plan req...
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, double exact_match_precision) override
Fetches all "matching" cache entries for comparison for pruning.
moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value) override
Checks inputs to the cache insert call to see if we should abort instead.
AlwaysInsertNeverPrunePolicy()
bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, const warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr &matching_entry, std::string *reason=nullptr) override
bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value, std::string *reason=nullptr) override
Returns whether the insertion candidate should be inserted into the cache.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest > > > getSupportedFeatures(double start_tolerance, double goal_tolerance)
Configures and returns a vector of feature extractors that can be used with this policy.
std::string getName() const override
Gets the name of the cache insert policy.
void reset() override
Resets the state of the policy.
moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::msg::MotionPlanRequest &key, const moveit::planning_interface::MoveGroupInterface::Plan &value) override
Appends the insert metadata with the features supported by the policy.
A cache insertion policy that always decides to insert and never decides to prune for cartesian path ...
std::string getName() const override
Gets the name of the cache insert policy.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request > > > getSupportedFeatures(double start_tolerance, double goal_tolerance, double min_fraction)
Configures and returns a vector of feature extractors that can be used with this policy.
bool shouldInsert(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, std::string *reason=nullptr) override
Returns whether the insertion candidate should be inserted into the cache.
moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata &metadata, const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Appends the insert metadata with the features supported by the policy.
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchMatchingEntries(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, double exact_match_precision) override
Fetches all "matching" cache entries for comparison for pruning.
bool shouldPruneMatchingEntry(const moveit::planning_interface::MoveGroupInterface &move_group, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value, const warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr &matching_entry, std::string *reason=nullptr) override
CartesianAlwaysInsertNeverPrunePolicy()
moveit::core::MoveItErrorCode checkCacheInsertInputs(const moveit::planning_interface::MoveGroupInterface &move_group, const warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory > &coll, const moveit_msgs::srv::GetCartesianPath::Request &key, const moveit_msgs::srv::GetCartesianPath::Response &value) override
Checks inputs to the cache insert call to see if we should abort instead.
void reset() override
Resets the state of the policy.
Abstract template class for extracting features from some FeatureSourceT.
The representation of a motion plan (as ROS messages)