41 #include <moveit_msgs/msg/planning_scene.hpp>
42 #include <moveit_msgs/msg/motion_plan_request.hpp>
43 #include <moveit_msgs/msg/robot_trajectory.hpp>
44 #include <rclcpp/logger.hpp>
46 #include <moveit_warehouse_export.h>
70 void addPlanningScene(
const moveit_msgs::msg::PlanningScene& scene);
72 const std::string& query_name =
"");
74 const moveit_msgs::msg::RobotTrajectory& result,
const std::string& scene_name);
76 bool hasPlanningScene(
const std::string&
name)
const;
77 void getPlanningSceneNames(std::vector<std::string>& names)
const;
78 void getPlanningSceneNames(
const std::string& regex, std::vector<std::string>& names)
const;
82 bool getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld& world,
const std::string& scene_name)
const;
84 bool hasPlanningQuery(
const std::string& scene_name,
const std::string& query_name)
const;
86 const std::string& query_name);
87 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
88 const std::string& scene_name)
const;
89 void getPlanningQueriesNames(std::vector<std::string>& query_names,
const std::string& scene_name)
const;
90 void getPlanningQueriesNames(
const std::string& regex, std::vector<std::string>& query_names,
91 const std::string& scene_name)
const;
92 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
93 std::vector<std::string>& query_names,
const std::string& scene_name)
const;
95 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
97 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
98 const std::string& query_name)
const;
100 void renamePlanningScene(
const std::string& old_scene_name,
const std::string& new_scene_name);
101 void renamePlanningQuery(
const std::string& scene_name,
const std::string& old_query_name,
102 const std::string& new_query_name);
104 void removePlanningScene(
const std::string& scene_name);
105 void removePlanningQuery(
const std::string& scene_name,
const std::string& query_name);
106 void removePlanningQueries(
const std::string& scene_name);
107 void removePlanningResults(
const std::string& scene_name);
108 void removePlanningResults(
const std::string& scene_name,
const std::string& query_name);
113 void createCollections();
116 const std::string& scene_name)
const;
118 const std::string& scene_name,
const std::string& query_name);
123 rclcpp::Logger logger_;
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
static const std::string PLANNING_SCENE_ID_NAME
static const std::string DATABASE_NAME
static const std::string MOTION_PLAN_REQUEST_ID_NAME
warehouse_ros::MessageCollection< moveit_msgs::msg::PlanningScene >::Ptr PlanningSceneCollection
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::RobotTrajectory >::ConstPtr RobotTrajectoryWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
MOVEIT_CLASS_FORWARD(PlanningSceneStorage)
warehouse_ros::MessageCollection< moveit_msgs::msg::MotionPlanRequest >::Ptr MotionPlanRequestCollection
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
warehouse_ros::MessageCollection< moveit_msgs::msg::RobotTrajectory >::Ptr RobotTrajectoryCollection
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest