moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_cache.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 
20 #pragma once
21 
22 #include <chrono>
23 #include <memory>
24 #include <vector>
25 
26 #include <rclcpp/rclcpp.hpp>
27 
28 #include <warehouse_ros/message_collection.h>
29 #include <warehouse_ros/database_connection.h>
30 
31 #include <geometry_msgs/msg/pose.hpp>
32 #include <geometry_msgs/msg/pose_stamped.hpp>
33 
34 // moveit modules
36 #include <moveit_msgs/msg/motion_plan_request.hpp>
37 #include <moveit_msgs/msg/robot_trajectory.hpp>
38 #include <moveit_msgs/srv/get_cartesian_path.hpp>
39 
42 
43 namespace moveit_ros
44 {
45 namespace trajectory_cache
46 {
47 
152 {
153 public:
162  static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>
163  getDefaultFeatures(double start_tolerance, double goal_tolerance);
164 
170  moveit_msgs::msg::RobotTrajectory>>
172 
176  static std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>
177  getDefaultCartesianFeatures(double start_tolerance, double goal_tolerance, double min_fraction);
178 
182  static std::unique_ptr<
183  CacheInsertPolicyInterface<moveit_msgs::srv::GetCartesianPath::Request,
184  moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory>>
186 
188  static std::string getDefaultSortFeature();
189 
206  explicit TrajectoryCache(const rclcpp::Node::SharedPtr& node);
207 
221  struct Options
222  {
223  std::string db_path = ":memory:";
224  uint32_t db_port = 0;
225 
226  double exact_match_precision = 1e-6;
228  };
229 
240  bool init(const Options& options);
241 
255  unsigned countTrajectories(const std::string& cache_namespace);
256 
263  unsigned countCartesianTrajectories(const std::string& cache_namespace);
264 
266  std::string getDbPath() const;
267 
269  uint32_t getDbPort() const;
270 
272  double getExactMatchPrecision() const;
273 
275  void setExactMatchPrecision(double exact_match_precision);
276 
279 
282  size_t num_additional_trajectories_to_preserve_when_pruning_worse);
283 
306  std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
308  const moveit::planning_interface::MoveGroupInterface& move_group, const std::string& cache_namespace,
309  const moveit_msgs::msg::MotionPlanRequest& plan_request,
310  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>& features,
311  const std::string& sort_by, bool ascending = true, bool metadata_only = false) const;
312 
327  warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr fetchBestMatchingTrajectory(
328  const moveit::planning_interface::MoveGroupInterface& move_group, const std::string& cache_namespace,
329  const moveit_msgs::msg::MotionPlanRequest& plan_request,
330  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>& features,
331  const std::string& sort_by, bool ascending = true, bool metadata_only = false) const;
332 
354  const std::string& cache_namespace, const moveit_msgs::msg::MotionPlanRequest& plan_request,
358  moveit_msgs::msg::RobotTrajectory>& cache_insert_policy,
359  bool prune_worse_trajectories = true,
360  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::msg::MotionPlanRequest>>>&
361  additional_features = {});
362 
385  std::vector<warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr>
387  const moveit::planning_interface::MoveGroupInterface& move_group, const std::string& cache_namespace,
388  const moveit_msgs::srv::GetCartesianPath::Request& plan_request,
389  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>& features,
390  const std::string& sort_by, bool ascending = true, bool metadata_only = false) const;
391 
406  warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr fetchBestMatchingCartesianTrajectory(
407  const moveit::planning_interface::MoveGroupInterface& move_group, const std::string& cache_namespace,
408  const moveit_msgs::srv::GetCartesianPath::Request& plan_request,
409  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>& features,
410  const std::string& sort_by, bool ascending = true, bool metadata_only = false) const;
411 
433  const moveit::planning_interface::MoveGroupInterface& move_group, const std::string& cache_namespace,
434  const moveit_msgs::srv::GetCartesianPath::Request& plan_request,
435  const moveit_msgs::srv::GetCartesianPath::Response& plan,
436  CacheInsertPolicyInterface<moveit_msgs::srv::GetCartesianPath::Request,
437  moveit_msgs::srv::GetCartesianPath::Response, moveit_msgs::msg::RobotTrajectory>&
438  cache_insert_policy,
439  bool prune_worse_trajectories = true,
440  const std::vector<std::unique_ptr<FeaturesInterface<moveit_msgs::srv::GetCartesianPath::Request>>>&
441  additional_features = {});
442 
445 private:
446  rclcpp::Node::SharedPtr node_;
447  rclcpp::Logger logger_;
448  warehouse_ros::DatabaseConnection::Ptr db_;
449 
450  Options options_;
451 };
452 
453 } // namespace trajectory_cache
454 } // namespace moveit_ros
Abstract template class for injecting logic for determining when to prune and insert a cache entry,...
Client class to conveniently use the ROS interfaces provided by the move_group node.
Trajectory Cache manager for MoveIt.
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.
Abstract template class for extracting features from some FeatureSourceT.
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)
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
The representation of a motion plan (as ROS messages)