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>
45 #include <moveit_warehouse_export.h>
69 void addPlanningScene(
const moveit_msgs::msg::PlanningScene&
scene);
71 const std::string& query_name =
"");
73 const moveit_msgs::msg::RobotTrajectory& result,
const std::string& scene_name);
75 bool hasPlanningScene(
const std::string&
name)
const;
76 void getPlanningSceneNames(std::vector<std::string>& names)
const;
77 void getPlanningSceneNames(
const std::string& regex, std::vector<std::string>& names)
const;
81 bool getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld& world,
const std::string& scene_name)
const;
83 bool hasPlanningQuery(
const std::string& scene_name,
const std::string& query_name)
const;
85 const std::string& query_name);
86 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
87 const std::string& scene_name)
const;
88 void getPlanningQueriesNames(std::vector<std::string>& query_names,
const std::string& scene_name)
const;
89 void getPlanningQueriesNames(
const std::string& regex, std::vector<std::string>& query_names,
90 const std::string& scene_name)
const;
91 void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
92 std::vector<std::string>& query_names,
const std::string& scene_name)
const;
94 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
96 void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results,
const std::string& scene_name,
97 const std::string& query_name)
const;
99 void renamePlanningScene(
const std::string& old_scene_name,
const std::string& new_scene_name);
100 void renamePlanningQuery(
const std::string& scene_name,
const std::string& old_query_name,
101 const std::string& new_query_name);
103 void removePlanningScene(
const std::string& scene_name);
104 void removePlanningQuery(
const std::string& scene_name,
const std::string& query_name);
105 void removePlanningQueries(
const std::string& scene_name);
106 void removePlanningResults(
const std::string& scene_name);
107 void removePlanningResults(
const std::string& scene_name,
const std::string& query_name);
112 void createCollections();
115 const std::string& scene_name)
const;
117 const std::string& scene_name,
const std::string& query_name);
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