moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_storage.h
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2012, Willow Garage, Inc.
5  * All rights reserved.
6  *
7  * Redistribution and use in source and binary forms, with or without
8  * modification, are permitted provided that the following conditions
9  * are met:
10  *
11  * * Redistributions of source code must retain the above copyright
12  * notice, this list of conditions and the following disclaimer.
13  * * Redistributions in binary form must reproduce the above
14  * copyright notice, this list of conditions and the following
15  * disclaimer in the documentation and/or other materials provided
16  * with the distribution.
17  * * Neither the name of Willow Garage nor the names of its
18  * contributors may be used to endorse or promote products derived
19  * from this software without specific prior written permission.
20  *
21  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32  * POSSIBILITY OF SUCH DAMAGE.
33  *********************************************************************/
34 
35 /* Author: Ioan Sucan */
36 
37 #pragma once
38 
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>
45 
46 #include <moveit_warehouse_export.h>
47 
48 namespace moveit_warehouse
49 {
50 typedef warehouse_ros::MessageWithMetadata<moveit_msgs::msg::PlanningScene>::ConstPtr PlanningSceneWithMetadata;
51 typedef warehouse_ros::MessageWithMetadata<moveit_msgs::msg::MotionPlanRequest>::ConstPtr MotionPlanRequestWithMetadata;
52 typedef warehouse_ros::MessageWithMetadata<moveit_msgs::msg::RobotTrajectory>::ConstPtr RobotTrajectoryWithMetadata;
53 
54 typedef warehouse_ros::MessageCollection<moveit_msgs::msg::PlanningScene>::Ptr PlanningSceneCollection;
55 typedef warehouse_ros::MessageCollection<moveit_msgs::msg::MotionPlanRequest>::Ptr MotionPlanRequestCollection;
56 typedef warehouse_ros::MessageCollection<moveit_msgs::msg::RobotTrajectory>::Ptr RobotTrajectoryCollection;
57 
58 MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc
59 
60 class MOVEIT_WAREHOUSE_EXPORT PlanningSceneStorage : public MoveItMessageStorage
61 {
62 public:
63  static const std::string DATABASE_NAME;
64 
65  static const std::string PLANNING_SCENE_ID_NAME;
66  static const std::string MOTION_PLAN_REQUEST_ID_NAME;
67 
68  PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn);
69 
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);
75 
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;
79 
81  bool getPlanningScene(PlanningSceneWithMetadata& scene_m, const std::string& scene_name) const;
82  bool getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld& world, const std::string& scene_name) const;
83 
84  bool hasPlanningQuery(const std::string& scene_name, const std::string& query_name) const;
85  bool getPlanningQuery(MotionPlanRequestWithMetadata& query_m, const std::string& scene_name,
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;
94 
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;
99 
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);
103 
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);
109 
110  void reset();
111 
112 private:
113  void createCollections();
114 
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);
119 
120  PlanningSceneCollection planning_scene_collection_;
121  MotionPlanRequestCollection motion_plan_request_collection_;
122  RobotTrajectoryCollection robot_trajectory_collection_;
123  rclcpp::Logger logger_;
124 };
125 } // namespace moveit_warehouse
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
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
name
Definition: setup.py:7