70 void addPlanningScene(
const moveit_msgs::msg::PlanningScene& scene);
71 void addPlanningQuery(
const moveit_msgs::msg::MotionPlanRequest& planning_query,
const std::string& scene_name,
72 const std::string& query_name =
"");
73 void addPlanningResult(
const moveit_msgs::msg::MotionPlanRequest& planning_query,
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,
96 const moveit_msgs::msg::MotionPlanRequest& planning_query)
const;
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();
115 std::string getMotionPlanRequestName(
const moveit_msgs::msg::MotionPlanRequest& planning_query,
116 const std::string& scene_name)
const;
117 std::string addNewPlanningRequest(
const moveit_msgs::msg::MotionPlanRequest& planning_query,
118 const std::string& scene_name,
const std::string& query_name);
123 rclcpp::Logger logger_;