moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_cache.cpp
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 
20 #include <chrono>
21 #include <memory>
22 #include <vector>
23 
24 #include <rclcpp/rclcpp.hpp>
25 #include <rclcpp/logging.hpp>
26 
27 #include <warehouse_ros/message_collection.h>
28 #include <warehouse_ros/database_connection.h>
29 
30 #include <geometry_msgs/msg/pose.hpp>
31 #include <geometry_msgs/msg/pose_stamped.hpp>
32 
33 #include <moveit_msgs/msg/motion_plan_request.hpp>
34 #include <moveit_msgs/msg/robot_trajectory.hpp>
35 #include <moveit_msgs/srv/get_cartesian_path.hpp>
36 
43 
44 // Cache insert policies.
47 
48 // Features.
53 
55 
56 namespace moveit_ros
57 {
58 namespace trajectory_cache
59 {
60 
61 using ::warehouse_ros::MessageCollection;
62 using ::warehouse_ros::MessageWithMetadata;
63 using ::warehouse_ros::Metadata;
64 using ::warehouse_ros::Query;
65 
66 using ::moveit::core::MoveItErrorCode;
67 using ::moveit::planning_interface::MoveGroupInterface;
68 
70 using ::moveit_msgs::msg::RobotTrajectory;
71 using ::moveit_msgs::srv::GetCartesianPath;
72 
73 using ::moveit_ros::trajectory_cache::BestSeenExecutionTimePolicy;
74 using ::moveit_ros::trajectory_cache::CacheInsertPolicyInterface;
75 using ::moveit_ros::trajectory_cache::CartesianBestSeenExecutionTimePolicy;
76 
77 using ::moveit_ros::trajectory_cache::FeaturesInterface;
78 
79 namespace
80 {
81 
82 const std::string EXECUTION_TIME = "execution_time_s";
83 const std::string FRACTION = "fraction";
84 const std::string PLANNING_TIME = "planning_time_s";
85 
86 } // namespace
87 
88 // =================================================================================================
89 // Default Behavior Helpers.
90 // =================================================================================================
91 
92 std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>>
93 TrajectoryCache::getDefaultFeatures(double start_tolerance, double goal_tolerance)
94 {
95  return BestSeenExecutionTimePolicy::getSupportedFeatures(start_tolerance, goal_tolerance);
96 }
97 
98 std::unique_ptr<CacheInsertPolicyInterface<MotionPlanRequest, MoveGroupInterface::Plan, RobotTrajectory>>
100 {
101  return std::make_unique<BestSeenExecutionTimePolicy>();
102 }
103 
104 std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>>
105 TrajectoryCache::getDefaultCartesianFeatures(double start_tolerance, double goal_tolerance, double min_fraction)
106 {
107  return CartesianBestSeenExecutionTimePolicy::getSupportedFeatures(start_tolerance, goal_tolerance, min_fraction);
108 }
109 
110 std::unique_ptr<CacheInsertPolicyInterface<GetCartesianPath::Request, GetCartesianPath::Response, RobotTrajectory>>
112 {
113  return std::make_unique<CartesianBestSeenExecutionTimePolicy>();
114 }
115 
117 {
118  return EXECUTION_TIME;
119 }
120 
121 // =================================================================================================
122 // Cache Configuration.
123 // =================================================================================================
124 
125 TrajectoryCache::TrajectoryCache(const rclcpp::Node::SharedPtr& node)
126  : node_(node), logger_(moveit::getLogger("moveit.ros.trajectory_cache"))
127 {
128 }
129 
131 {
132  RCLCPP_DEBUG(logger_, "Opening trajectory cache database at: %s (Port: %d, Precision: %f)", options.db_path.c_str(),
133  options.db_port, options.exact_match_precision);
134 
135  // If the `warehouse_plugin` parameter isn't set, defaults to warehouse_ros'
136  // default.
137  db_ = moveit_warehouse::loadDatabase(node_);
138  options_ = options;
139 
140  db_->setParams(options.db_path, options.db_port);
141  return db_->connect();
142 }
143 
144 // =================================================================================================
145 // Getters and Setters.
146 // =================================================================================================
147 
148 unsigned TrajectoryCache::countTrajectories(const std::string& cache_namespace)
149 {
150  MessageCollection<RobotTrajectory> coll =
151  db_->openCollection<RobotTrajectory>("move_group_trajectory_cache", cache_namespace);
152  return coll.count();
153 }
154 
155 unsigned TrajectoryCache::countCartesianTrajectories(const std::string& cache_namespace)
156 {
157  MessageCollection<RobotTrajectory> coll =
158  db_->openCollection<RobotTrajectory>("move_group_cartesian_trajectory_cache", cache_namespace);
159  return coll.count();
160 }
161 
162 std::string TrajectoryCache::getDbPath() const
163 {
164  return options_.db_path;
165 }
166 
168 {
169  return options_.db_port;
170 }
171 
173 {
174  return options_.exact_match_precision;
175 }
176 
177 void TrajectoryCache::setExactMatchPrecision(double exact_match_precision)
178 {
179  options_.exact_match_precision = exact_match_precision;
180 }
181 
183 {
185 }
186 
188  size_t num_additional_trajectories_to_preserve_when_pruning_worse)
189 {
191  num_additional_trajectories_to_preserve_when_pruning_worse;
192 }
193 
194 // =================================================================================================
195 // Motion Plan Trajectory Caching.
196 // =================================================================================================
197 
198 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> TrajectoryCache::fetchAllMatchingTrajectories(
199  const MoveGroupInterface& move_group, const std::string& cache_namespace, const MotionPlanRequest& plan_request,
200  const std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>>& features, const std::string& sort_by,
201  bool ascending, bool metadata_only) const
202 {
203  MessageCollection<RobotTrajectory> coll =
204  db_->openCollection<RobotTrajectory>("move_group_trajectory_cache", cache_namespace);
205 
206  Query::Ptr query = coll.createQuery();
207  for (const auto& feature : features)
208  {
209  if (MoveItErrorCode ret =
210  feature->appendFeaturesAsFuzzyFetchQuery(*query, plan_request, move_group,
211  /*exact_match_precision=*/options_.exact_match_precision);
212  !ret)
213  {
214  RCLCPP_ERROR_STREAM(logger_, "Could not construct trajectory query: " << ret.message);
215  return {};
216  }
217  }
218  return coll.queryList(query, metadata_only, sort_by, ascending);
219 }
220 
221 MessageWithMetadata<RobotTrajectory>::ConstPtr TrajectoryCache::fetchBestMatchingTrajectory(
222  const MoveGroupInterface& move_group, const std::string& cache_namespace, const MotionPlanRequest& plan_request,
223  const std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>>& features, const std::string& sort_by,
224  bool ascending, bool metadata_only) const
225 {
226  // Find all matching, with metadata only. We'll use the ID of the best trajectory to pull it.
227  std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> matching_trajectories =
228  this->fetchAllMatchingTrajectories(move_group, cache_namespace, plan_request, features, sort_by, ascending,
229  /*metadata_only=*/true);
230  if (matching_trajectories.empty())
231  {
232  RCLCPP_DEBUG(logger_, "No matching trajectories found.");
233  return nullptr;
234  }
235 
236  MessageCollection<RobotTrajectory> coll =
237  db_->openCollection<RobotTrajectory>("move_group_trajectory_cache", cache_namespace);
238 
239  // Best trajectory is at first index, since the lookup query was sorted.
240  int best_trajectory_id = matching_trajectories.at(0)->lookupInt("id");
241  Query::Ptr best_query = coll.createQuery();
242  best_query->append("id", best_trajectory_id);
243 
244  return coll.findOne(best_query, metadata_only);
245 }
246 
248  const MoveGroupInterface& move_group, const std::string& cache_namespace, const MotionPlanRequest& plan_request,
249  const MoveGroupInterface::Plan& plan,
251  bool prune_worse_trajectories,
252  const std::vector<std::unique_ptr<FeaturesInterface<MotionPlanRequest>>>& additional_features)
253 {
254  MessageCollection<RobotTrajectory> coll =
255  db_->openCollection<RobotTrajectory>("move_group_trajectory_cache", cache_namespace);
256 
257  // Check pre-preconditions.
258  if (MoveItErrorCode ret = cache_insert_policy.checkCacheInsertInputs(move_group, coll, plan_request, plan); !ret)
259  {
260  RCLCPP_ERROR_STREAM(logger_, "Skipping trajectory insert, invalid inputs: " << ret.message);
261  cache_insert_policy.reset();
262  return false;
263  }
264 
265  std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> matching_entries =
266  cache_insert_policy.fetchMatchingEntries(move_group, coll, plan_request, plan, options_.exact_match_precision);
267 
268  // Prune.
269  if (prune_worse_trajectories)
270  {
271  size_t preserved_count = 0;
272  for (const auto& matching_entry : matching_entries)
273  {
274  std::string prune_reason;
275  if (++preserved_count > options_.num_additional_trajectories_to_preserve_when_pruning_worse &&
276  cache_insert_policy.shouldPruneMatchingEntry(move_group, plan_request, plan, matching_entry, &prune_reason))
277  {
278  int delete_id = matching_entry->lookupInt("id");
279  RCLCPP_DEBUG_STREAM(logger_, "Pruning plan (id: `" << delete_id << "`): " << prune_reason);
280 
281  Query::Ptr delete_query = coll.createQuery();
282  delete_query->append("id", delete_id);
283  coll.removeMessages(delete_query);
284  }
285  }
286  }
287 
288  // Insert.
289  std::string insert_reason;
290  if (cache_insert_policy.shouldInsert(move_group, plan_request, plan, &insert_reason))
291  {
292  Metadata::Ptr insert_metadata = coll.createMetadata();
293 
294  if (MoveItErrorCode ret = cache_insert_policy.appendInsertMetadata(*insert_metadata, move_group, plan_request, plan);
295  !ret)
296  {
297  RCLCPP_ERROR_STREAM(logger_,
298  "Skipping trajectory insert: Could not construct insert metadata from cache_insert_policy: "
299  << cache_insert_policy.getName() << ": " << ret.message);
300  cache_insert_policy.reset();
301  return false;
302  }
303 
304  for (const auto& additional_feature : additional_features)
305  {
306  if (MoveItErrorCode ret =
307  additional_feature->appendFeaturesAsInsertMetadata(*insert_metadata, plan_request, move_group);
308  !ret)
309  {
310  RCLCPP_ERROR_STREAM(logger_,
311  "Skipping trajectory insert: Could not construct insert metadata additional_feature: "
312  << additional_feature->getName() << ": " << ret.message);
313  cache_insert_policy.reset();
314  return false;
315  }
316  }
317 
318  RCLCPP_DEBUG_STREAM(logger_, "Inserting trajectory:" << insert_reason);
319  coll.insert(plan.trajectory, insert_metadata);
320  cache_insert_policy.reset();
321  return true;
322  }
323  else
324  {
325  RCLCPP_DEBUG_STREAM(logger_, "Skipping trajectory insert:" << insert_reason);
326  cache_insert_policy.reset();
327  return false;
328  }
329 }
330 
331 // =================================================================================================
332 // Cartesian Trajectory Caching.
333 // =================================================================================================
334 
335 std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> TrajectoryCache::fetchAllMatchingCartesianTrajectories(
336  const MoveGroupInterface& move_group, const std::string& cache_namespace,
337  const GetCartesianPath::Request& plan_request,
338  const std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>>& features,
339  const std::string& sort_by, bool ascending, bool metadata_only) const
340 {
341  MessageCollection<RobotTrajectory> coll =
342  db_->openCollection<RobotTrajectory>("move_group_cartesian_trajectory_cache", cache_namespace);
343 
344  Query::Ptr query = coll.createQuery();
345  for (const auto& feature : features)
346  {
347  if (MoveItErrorCode ret =
348  feature->appendFeaturesAsFuzzyFetchQuery(*query, plan_request, move_group,
349  /*exact_match_precision=*/options_.exact_match_precision);
350  !ret)
351  {
352  RCLCPP_ERROR_STREAM(logger_, "Could not construct cartesian trajectory query: " << ret.message);
353  return {};
354  }
355  }
356  return coll.queryList(query, metadata_only, sort_by, ascending);
357 }
358 
359 MessageWithMetadata<RobotTrajectory>::ConstPtr TrajectoryCache::fetchBestMatchingCartesianTrajectory(
360  const MoveGroupInterface& move_group, const std::string& cache_namespace,
361  const GetCartesianPath::Request& plan_request,
362  const std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>>& features,
363  const std::string& sort_by, bool ascending, bool metadata_only) const
364 {
365  // Find all matching, with metadata only. We'll use the ID of the best trajectory to pull it.
366  std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> matching_trajectories =
367  this->fetchAllMatchingCartesianTrajectories(move_group, cache_namespace, plan_request, features, sort_by,
368  ascending, /*metadata_only=*/true);
369  if (matching_trajectories.empty())
370  {
371  RCLCPP_DEBUG(logger_, "No matching cartesian trajectories found.");
372  return nullptr;
373  }
374 
375  MessageCollection<RobotTrajectory> coll =
376  db_->openCollection<RobotTrajectory>("move_group_cartesian_trajectory_cache", cache_namespace);
377 
378  // Best trajectory is at first index, since the lookup query was sorted.
379  int best_trajectory_id = matching_trajectories.at(0)->lookupInt("id");
380  Query::Ptr best_query = coll.createQuery();
381  best_query->append("id", best_trajectory_id);
382 
383  return coll.findOne(best_query, metadata_only);
384 }
385 
387  const MoveGroupInterface& move_group, const std::string& cache_namespace,
388  const GetCartesianPath::Request& plan_request, const GetCartesianPath::Response& plan,
390  cache_insert_policy,
391  bool prune_worse_trajectories,
392  const std::vector<std::unique_ptr<FeaturesInterface<GetCartesianPath::Request>>>& additional_features)
393 {
394  MessageCollection<RobotTrajectory> coll =
395  db_->openCollection<RobotTrajectory>("move_group_cartesian_trajectory_cache", cache_namespace);
396 
397  // Check pre-preconditions.
398  if (MoveItErrorCode ret = cache_insert_policy.checkCacheInsertInputs(move_group, coll, plan_request, plan); !ret)
399  {
400  RCLCPP_ERROR_STREAM(logger_, "Skipping cartesian trajectory insert, invalid inputs: " << ret.message);
401  cache_insert_policy.reset();
402  return false;
403  }
404 
405  std::vector<MessageWithMetadata<RobotTrajectory>::ConstPtr> matching_entries =
406  cache_insert_policy.fetchMatchingEntries(move_group, coll, plan_request, plan, options_.exact_match_precision);
407 
408  // Prune.
409  if (prune_worse_trajectories)
410  {
411  size_t preserved_count = 0;
412  for (const auto& matching_entry : matching_entries)
413  {
414  std::string prune_reason;
415  if (++preserved_count > options_.num_additional_trajectories_to_preserve_when_pruning_worse &&
416  cache_insert_policy.shouldPruneMatchingEntry(move_group, plan_request, plan, matching_entry, &prune_reason))
417  {
418  int delete_id = matching_entry->lookupInt("id");
419  RCLCPP_DEBUG_STREAM(logger_, "Pruning cartesian trajectory (id: `" << delete_id << "`): " << prune_reason);
420 
421  Query::Ptr delete_query = coll.createQuery();
422  delete_query->append("id", delete_id);
423  coll.removeMessages(delete_query);
424  }
425  }
426  }
427 
428  // Insert.
429  std::string insert_reason;
430  if (cache_insert_policy.shouldInsert(move_group, plan_request, plan, &insert_reason))
431  {
432  Metadata::Ptr insert_metadata = coll.createMetadata();
433 
434  if (MoveItErrorCode ret = cache_insert_policy.appendInsertMetadata(*insert_metadata, move_group, plan_request, plan);
435  !ret)
436  {
437  RCLCPP_ERROR_STREAM(logger_, "Skipping cartesian trajectory insert: Could not construct insert metadata from "
438  "cache_insert_policy: "
439  << cache_insert_policy.getName() << ": " << ret.message);
440  cache_insert_policy.reset();
441  return false;
442  }
443 
444  for (const auto& additional_feature : additional_features)
445  {
446  if (MoveItErrorCode ret =
447  additional_feature->appendFeaturesAsInsertMetadata(*insert_metadata, plan_request, move_group);
448  !ret)
449  {
450  RCLCPP_ERROR_STREAM(
451  logger_, "Skipping cartesian trajectory insert: Could not construct insert metadata additional_feature: "
452  << additional_feature->getName() << ": " << ret.message);
453  cache_insert_policy.reset();
454  return false;
455  }
456  }
457 
458  RCLCPP_DEBUG_STREAM(logger_, "Inserting cartesian trajectory:" << insert_reason);
459  coll.insert(plan.solution, insert_metadata);
460  cache_insert_policy.reset();
461  return true;
462  }
463  else
464  {
465  RCLCPP_DEBUG_STREAM(logger_, "Skipping cartesian insert:" << insert_reason);
466  cache_insert_policy.reset();
467  return false;
468  }
469 }
470 
471 } // namespace trajectory_cache
472 } // namespace moveit_ros
A cache insertion policy that only decides to insert if the motion plan is the one with the shortest ...
Abstract template class for injecting logic for determining when to prune and insert a cache entry,...
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.
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 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 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 void reset()=0
Resets the state of the policy.
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.
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.
unsigned countCartesianTrajectories(const std::string &cache_namespace)
Count the number of cartesian trajectories for a particular cache namespace.
static std::unique_ptr< CacheInsertPolicyInterface< moveit_msgs::msg::MotionPlanRequest, moveit::planning_interface::MoveGroupInterface::Plan, moveit_msgs::msg::RobotTrajectory > > getDefaultCacheInsertPolicy()
Gets the default cache insert policy for MotionPlanRequest messages.
size_t getNumAdditionalTrajectoriesToPreserveWhenPruningWorse() const
Get the number of trajectories to preserve when pruning worse trajectories.
unsigned countTrajectories(const std::string &cache_namespace)
Count the number of non-cartesian trajectories for a particular cache namespace.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request > > > getDefaultCartesianFeatures(double start_tolerance, double goal_tolerance, double min_fraction)
Gets the default features for GetCartesianPath requests.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr fetchBestMatchingTrajectory(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::msg::MotionPlanRequest &plan_request, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >>> &features, const std::string &sort_by, bool ascending=true, bool metadata_only=false) const
Fetches the best trajectory keyed on user-specified features, with respect to some cache feature.
TrajectoryCache(const rclcpp::Node::SharedPtr &node)
Constructs a TrajectoryCache.
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchAllMatchingCartesianTrajectories(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::srv::GetCartesianPath::Request &plan_request, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >>> &features, const std::string &sort_by, bool ascending=true, bool metadata_only=false) const
Fetches all cartesian trajectories keyed on user-specified features, returning them as a vector,...
static std::string getDefaultSortFeature()
Gets the default sort feature.
double getExactMatchPrecision() const
Gets the exact match precision.
bool insertCartesianTrajectory(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::srv::GetCartesianPath::Request &plan_request, const moveit_msgs::srv::GetCartesianPath::Response &plan, CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory > &cache_insert_policy, bool prune_worse_trajectories=true, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >>> &additional_features={})
Inserts a cartesian trajectory into the database, with user-specified insert policy.
void setNumAdditionalTrajectoriesToPreserveWhenPruningWorse(size_t num_additional_trajectories_to_preserve_when_pruning_worse)
Set the number of additional trajectories to preserve when pruning worse trajectories.
bool insertTrajectory(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::msg::MotionPlanRequest &plan_request, const moveit::planning_interface::MoveGroupInterface::Plan &plan, CacheInsertPolicyInterface< moveit_msgs::msg::MotionPlanRequest, moveit::planning_interface::MoveGroupInterface::Plan, moveit_msgs::msg::RobotTrajectory > &cache_insert_policy, bool prune_worse_trajectories=true, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >>> &additional_features={})
Inserts a trajectory into the database, with user-specified insert policy.
static std::unique_ptr< CacheInsertPolicyInterface< moveit_msgs::srv::GetCartesianPath::Request, moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory > > getDefaultCartesianCacheInsertPolicy()
Gets the default cache insert policy for GetCartesianPath requests.
void setExactMatchPrecision(double exact_match_precision)
Sets the exact match precision.
std::vector< warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr > fetchAllMatchingTrajectories(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::msg::MotionPlanRequest &plan_request, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest >>> &features, const std::string &sort_by, bool ascending=true, bool metadata_only=false) const
Fetches all trajectories keyed on user-specified features, returning them as a vector,...
std::string getDbPath() const
Gets the database path.
static std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::msg::MotionPlanRequest > > > getDefaultFeatures(double start_tolerance, double goal_tolerance)
Gets the default features for MotionPlanRequest messages.
bool init(const Options &options)
Initializes the TrajectoryCache.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr fetchBestMatchingCartesianTrajectory(const moveit::planning_interface::MoveGroupInterface &move_group, const std::string &cache_namespace, const moveit_msgs::srv::GetCartesianPath::Request &plan_request, const std::vector< std::unique_ptr< FeaturesInterface< moveit_msgs::srv::GetCartesianPath::Request >>> &features, const std::string &sort_by, bool ascending=true, bool metadata_only=false) const
Fetches the best cartesian trajectory keyed on user-specified features, with respect to some cache fe...
uint32_t getDbPort() const
Gets the database port.
User-specified constant features to key the trajectory cache on.
Abstract template class for extracting features from some FeatureSourceT.
moveit_msgs::srv::GetCartesianPath::Request features to key the trajectory cache on.
moveit_msgs::msg::MotionPlanRequest features to key the trajectory cache on.
Utilities used by the trajectory_cache package.
planning_interface::MotionPlanResponse plan(std::shared_ptr< moveit_cpp::PlanningComponent > &planning_component, std::shared_ptr< moveit_cpp::PlanningComponent::PlanRequestParameters > &single_plan_parameters, std::shared_ptr< moveit_cpp::PlanningComponent::MultiPipelinePlanRequestParameters > &multi_plan_parameters, std::shared_ptr< planning_scene::PlanningScene > &planning_scene, std::optional< const moveit::planning_pipeline_interfaces::SolutionSelectionFunction > solution_selection_function, std::optional< moveit::planning_pipeline_interfaces::StoppingCriterionFunction > stopping_criterion_callback)
warehouse_ros::DatabaseConnection::Ptr loadDatabase(const rclcpp::Node::SharedPtr &node)
Load a database connection.
Main namespace for MoveIt.
Definition: exceptions.hpp:43
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
robot_trajectory::RobotTrajectoryPtr trajectory
Fuzzy-Matching Trajectory Cache.