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/PlanningScene.h>
42 #include <moveit_msgs/MotionPlanRequest.h>
43 #include <moveit_msgs/RobotTrajectory.h>
44 
45 namespace moveit_warehouse
46 {
50 
54 
55 MOVEIT_CLASS_FORWARD(PlanningSceneStorage); // Defines PlanningSceneStoragePtr, ConstPtr, WeakPtr... etc
56 
57 class PlanningSceneStorage : public MoveItMessageStorage
58 {
59 public:
60  static const std::string DATABASE_NAME;
61 
62  static const std::string PLANNING_SCENE_ID_NAME;
63  static const std::string MOTION_PLAN_REQUEST_ID_NAME;
64 
66 
67  void addPlanningScene(const moveit_msgs::PlanningScene& scene);
68  void addPlanningQuery(const moveit_msgs::MotionPlanRequest& planning_query, const std::string& scene_name,
69  const std::string& query_name = "");
70  void addPlanningResult(const moveit_msgs::MotionPlanRequest& planning_query,
71  const moveit_msgs::RobotTrajectory& result, const std::string& scene_name);
72 
73  bool hasPlanningScene(const std::string& name) const;
74  void getPlanningSceneNames(std::vector<std::string>& names) const;
75  void getPlanningSceneNames(const std::string& regex, std::vector<std::string>& names) const;
76 
78  bool getPlanningScene(PlanningSceneWithMetadata& scene_m, const std::string& scene_name) const;
79  bool getPlanningSceneWorld(moveit_msgs::PlanningSceneWorld& world, const std::string& scene_name) const;
80 
81  bool hasPlanningQuery(const std::string& scene_name, const std::string& query_name) const;
82  bool getPlanningQuery(MotionPlanRequestWithMetadata& query_m, const std::string& scene_name,
83  const std::string& query_name);
84  void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
85  const std::string& scene_name) const;
86  void getPlanningQueriesNames(std::vector<std::string>& query_names, const std::string& scene_name) const;
87  void getPlanningQueriesNames(const std::string& regex, std::vector<std::string>& query_names,
88  const std::string& scene_name) const;
89  void getPlanningQueries(std::vector<MotionPlanRequestWithMetadata>& planning_queries,
90  std::vector<std::string>& query_names, const std::string& scene_name) const;
91 
92  void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
93  const moveit_msgs::MotionPlanRequest& planning_query) const;
94  void getPlanningResults(std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
95  const std::string& query_name) const;
96 
97  void renamePlanningScene(const std::string& old_scene_name, const std::string& new_scene_name);
98  void renamePlanningQuery(const std::string& scene_name, const std::string& old_query_name,
99  const std::string& new_query_name);
100 
101  void removePlanningScene(const std::string& scene_name);
102  void removePlanningQuery(const std::string& scene_name, const std::string& query_name);
103  void removePlanningQueries(const std::string& scene_name);
104  void removePlanningResults(const std::string& scene_name);
105  void removePlanningResults(const std::string& scene_name, const std::string& query_name);
106 
107  void reset();
108 
109 private:
110  void createCollections();
111 
112  std::string getMotionPlanRequestName(const moveit_msgs::MotionPlanRequest& planning_query,
113  const std::string& scene_name) const;
114  std::string addNewPlanningRequest(const moveit_msgs::MotionPlanRequest& planning_query, const std::string& scene_name,
115  const std::string& query_name);
116 
120 };
121 } // namespace moveit_warehouse
moveit_warehouse::PlanningSceneStorage::removePlanningScene
void removePlanningScene(const std::string &scene_name)
Definition: planning_scene_storage.cpp:368
moveit_message_storage.h
moveit_warehouse::PlanningSceneStorage::DATABASE_NAME
static const std::string DATABASE_NAME
Definition: planning_scene_storage.h:92
moveit_warehouse::PlanningSceneStorage::getPlanningScene
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_name.
Definition: planning_scene_storage.cpp:217
moveit_warehouse::PlanningSceneCollection
warehouse_ros::MessageCollection< moveit_msgs::PlanningScene >::Ptr PlanningSceneCollection
Definition: planning_scene_storage.h:83
moveit_warehouse::PlanningSceneStorage::getMotionPlanRequestName
std::string getMotionPlanRequestName(const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name) const
Definition: planning_scene_storage.cpp:96
moveit_warehouse::PlanningSceneStorage::removePlanningQuery
void removePlanningQuery(const std::string &scene_name, const std::string &query_name)
Definition: planning_scene_storage.cpp:386
boost::shared_ptr
moveit_warehouse::PlanningSceneStorage::MOTION_PLAN_REQUEST_ID_NAME
static const std::string MOTION_PLAN_REQUEST_ID_NAME
Definition: planning_scene_storage.h:95
moveit_warehouse::PlanningSceneStorage::addNewPlanningRequest
std::string addNewPlanningRequest(const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name)
Definition: planning_scene_storage.cpp:146
moveit_warehouse::PlanningSceneStorage::renamePlanningQuery
void renamePlanningQuery(const std::string &scene_name, const std::string &old_query_name, const std::string &new_query_name)
Definition: planning_scene_storage.cpp:354
moveit_warehouse::PlanningSceneStorage::addPlanningResult
void addPlanningResult(const moveit_msgs::MotionPlanRequest &planning_query, const moveit_msgs::RobotTrajectory &result, const std::string &scene_name)
Definition: planning_scene_storage.cpp:173
moveit_warehouse::PlanningSceneStorage::getPlanningSceneWorld
bool getPlanningSceneWorld(moveit_msgs::PlanningSceneWorld &world, const std::string &scene_name) const
Definition: planning_scene_storage.cpp:204
moveit_warehouse
Definition: constraints_storage.h:43
moveit_warehouse::PlanningSceneStorage::addPlanningScene
void addPlanningScene(const moveit_msgs::PlanningScene &scene)
Definition: planning_scene_storage.cpp:73
moveit_warehouse::PlanningSceneStorage::removePlanningResults
void removePlanningResults(const std::string &scene_name)
Definition: planning_scene_storage.cpp:398
moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage
PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
Definition: planning_scene_storage.cpp:49
moveit_warehouse::MotionPlanRequestCollection
warehouse_ros::MessageCollection< moveit_msgs::MotionPlanRequest >::Ptr MotionPlanRequestCollection
Definition: planning_scene_storage.h:84
moveit_warehouse::PlanningSceneStorage::addPlanningQuery
void addPlanningQuery(const moveit_msgs::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
Definition: planning_scene_storage.cpp:132
moveit_warehouse::PlanningSceneStorage::hasPlanningQuery
bool hasPlanningQuery(const std::string &scene_name, const std::string &query_name) const
Definition: planning_scene_storage.cpp:333
moveit_warehouse::PlanningSceneStorage::planning_scene_collection_
PlanningSceneCollection planning_scene_collection_
Definition: planning_scene_storage.h:149
moveit_warehouse::PlanningSceneStorage::robot_trajectory_collection_
RobotTrajectoryCollection robot_trajectory_collection_
Definition: planning_scene_storage.h:151
moveit_warehouse::PlanningSceneStorage::createCollections
void createCollections()
Definition: planning_scene_storage.cpp:55
moveit_warehouse::MOVEIT_CLASS_FORWARD
MOVEIT_CLASS_FORWARD(ConstraintsStorage)
moveit_warehouse::PlanningSceneStorage::motion_plan_request_collection_
MotionPlanRequestCollection motion_plan_request_collection_
Definition: planning_scene_storage.h:150
moveit_warehouse::PlanningSceneStorage::removePlanningQueries
void removePlanningQueries(const std::string &scene_name)
Definition: planning_scene_storage.cpp:377
moveit_warehouse::PlanningSceneStorage::renamePlanningScene
void renamePlanningScene(const std::string &old_scene_name, const std::string &new_scene_name)
Definition: planning_scene_storage.cpp:343
moveit_warehouse::MotionPlanRequestWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
Definition: planning_scene_storage.h:80
class_forward.h
moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames
void getPlanningQueriesNames(std::vector< std::string > &query_names, const std::string &scene_name) const
Definition: planning_scene_storage.cpp:263
moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames
void getPlanningSceneNames(std::vector< std::string > &names) const
Definition: planning_scene_storage.cpp:186
moveit_warehouse::PlanningSceneStorage::getPlanningQuery
bool getPlanningQuery(MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name)
Definition: planning_scene_storage.cpp:235
moveit_warehouse::RobotTrajectoryWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::RobotTrajectory >::ConstPtr RobotTrajectoryWithMetadata
Definition: planning_scene_storage.h:81
moveit_warehouse::RobotTrajectoryCollection
warehouse_ros::MessageCollection< moveit_msgs::RobotTrajectory >::Ptr RobotTrajectoryCollection
Definition: planning_scene_storage.h:85
moveit_warehouse::PlanningSceneStorage::reset
void reset()
Definition: planning_scene_storage.cpp:64
moveit_warehouse::PlanningSceneStorage::getPlanningQueries
void getPlanningQueries(std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const
Definition: planning_scene_storage.cpp:255
moveit_warehouse::PlanningSceneStorage::hasPlanningScene
bool hasPlanningScene(const std::string &name) const
Definition: planning_scene_storage.cpp:87
moveit_warehouse::PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::PlanningScene >::ConstPtr PlanningSceneWithMetadata
Definition: planning_scene_storage.h:79
moveit_warehouse::PlanningSceneStorage::getPlanningResults
void getPlanningResults(std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::MotionPlanRequest &planning_query) const
Definition: planning_scene_storage.cpp:312
moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME
static const std::string PLANNING_SCENE_ID_NAME
Definition: planning_scene_storage.h:94


warehouse
Author(s): Ioan Sucan
autogenerated on Thu Apr 18 2024 02:25:06