moveit2
The MoveIt Motion Planning Framework for ROS 2.
always_insert_never_prune_policy.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 
24 #pragma once
25 
26 #include <memory>
27 
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>
33 
36 
37 namespace moveit_ros
38 {
39 namespace trajectory_cache
40 {
41 
42 // =================================================================================================
43 // AlwaysInsertNeverPrunePolicy.
44 // =================================================================================================
45 // moveit_msgs::msg::MotionPlanRequest <=> moveit::planning_interface::MoveGroupInterface::Plan
46 
76  : public CacheInsertPolicyInterface<moveit_msgs::msg::MotionPlanRequest,
77  moveit::planning_interface::MoveGroupInterface::Plan,
78  moveit_msgs::msg::RobotTrajectory>
79 {
80 public:
82  static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>
83  getSupportedFeatures(double start_tolerance, double goal_tolerance);
84 
86 
87  std::string getName() const override;
88 
91  const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
94 
95  std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
97  const warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>& coll,
100  double exact_match_precision) override;
101 
105  const warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr& matching_entry,
106  std::string* reason = nullptr) override;
107 
111  std::string* reason = nullptr) override;
112 
114  appendInsertMetadata(warehouse_ros::Metadata& metadata,
118 
119  void reset() override;
120 
121 private:
122  const std::string name_;
123  std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>> exact_matching_supported_features_;
124 };
125 
126 // =================================================================================================
127 // CartesianAlwaysInsertNeverPrunePolicy.
128 // =================================================================================================
129 // moveit_msgs::srv::GetCartesianPath::Request <=> moveit_msgs::srv::GetCartesianPath::Response
130 
166  : public CacheInsertPolicyInterface<moveit_msgs::srv::GetCartesianPath::Request,
167  moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory>
168 {
169 public:
171  static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>
172  getSupportedFeatures(double start_tolerance, double goal_tolerance, double min_fraction);
173 
175 
176  std::string getName() const override;
177 
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;
183 
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;
190 
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;
196 
198  const moveit_msgs::srv::GetCartesianPath::Request& key,
199  const moveit_msgs::srv::GetCartesianPath::Response& value, std::string* reason = nullptr) override;
200 
201  moveit::core::MoveItErrorCode appendInsertMetadata(warehouse_ros::Metadata& metadata,
203  const moveit_msgs::srv::GetCartesianPath::Request& key,
204  const moveit_msgs::srv::GetCartesianPath::Response& value) override;
205 
206  void reset() override;
207 
208 private:
209  const std::string name_;
210  std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>
211  exact_matching_supported_features_;
212 };
213 
214 } // namespace trajectory_cache
215 } // namespace moveit_ros
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.
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.
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
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.
Abstract template class for extracting features from some FeatureSourceT.
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
The representation of a motion plan (as ROS messages)