moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_world_storage.cpp
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 
38 
39 #include <utility>
40 
41 const std::string moveit_warehouse::PlanningSceneWorldStorage::DATABASE_NAME = "moveit_planning_scene_worlds";
43 
44 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.planning_scene_world_storage");
45 
46 using warehouse_ros::Metadata;
47 using warehouse_ros::Query;
48 
50  : MoveItMessageStorage(std::move(conn))
51 {
52  createCollections();
53 }
54 
55 void moveit_warehouse::PlanningSceneWorldStorage::createCollections()
56 {
57  planning_scene_world_collection_ =
58  conn_->openCollectionPtr<moveit_msgs::msg::PlanningSceneWorld>(DATABASE_NAME, "planning_scene_worlds");
59 }
60 
62 {
63  planning_scene_world_collection_.reset();
64  conn_->dropDatabase(DATABASE_NAME);
65  createCollections();
66 }
67 
68 void moveit_warehouse::PlanningSceneWorldStorage::addPlanningSceneWorld(const moveit_msgs::msg::PlanningSceneWorld& msg,
69  const std::string& name)
70 {
71  bool replace = false;
72  if (hasPlanningSceneWorld(name))
73  {
74  removePlanningSceneWorld(name);
75  replace = true;
76  }
77  Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
78  metadata->append(PLANNING_SCENE_WORLD_ID_NAME, name);
79  planning_scene_world_collection_->insert(msg, metadata);
80  RCLCPP_DEBUG(LOGGER, "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
81 }
82 
84 {
85  Query::Ptr q = planning_scene_world_collection_->createQuery();
86  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
87  std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q, true);
88  return !psw.empty();
89 }
90 
92  std::vector<std::string>& names) const
93 {
94  getKnownPlanningSceneWorlds(names);
95  filterNames(regex, names);
96 }
97 
99 {
100  names.clear();
101  Query::Ptr q = planning_scene_world_collection_->createQuery();
102  std::vector<PlanningSceneWorldWithMetadata> planning_scene_worlds =
103  planning_scene_world_collection_->queryList(q, true, PLANNING_SCENE_WORLD_ID_NAME, true);
104  for (PlanningSceneWorldWithMetadata& planning_scene_world : planning_scene_worlds)
105  if (planning_scene_world->lookupField(PLANNING_SCENE_WORLD_ID_NAME))
106  names.push_back(planning_scene_world->lookupString(PLANNING_SCENE_WORLD_ID_NAME));
107 }
108 
110  const std::string& name) const
111 {
112  Query::Ptr q = planning_scene_world_collection_->createQuery();
113  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
114  std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q, false);
115  if (psw.empty())
116  return false;
117  else
118  {
119  msg_m = psw.front();
120  return true;
121  }
122 }
123 
125  const std::string& new_name)
126 {
127  Query::Ptr q = planning_scene_world_collection_->createQuery();
128  q->append(PLANNING_SCENE_WORLD_ID_NAME, old_name);
129  Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
130  m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
131  planning_scene_world_collection_->modifyMetadata(q, m);
132  RCLCPP_DEBUG(LOGGER, "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
133 }
134 
136 {
137  Query::Ptr q = planning_scene_world_collection_->createQuery();
138  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
139  unsigned int rem = planning_scene_world_collection_->removeMessages(q);
140  RCLCPP_DEBUG(LOGGER, "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
141 }
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
void getKnownPlanningSceneWorlds(std::vector< std::string > &names) const
bool hasPlanningSceneWorld(const std::string &name) const
void renamePlanningSceneWorld(const std::string &old_name, const std::string &new_name)
bool getPlanningSceneWorld(PlanningSceneWorldWithMetadata &msg_m, const std::string &name) const
Get the constraints named name. Return false on failure.
PlanningSceneWorldStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addPlanningSceneWorld(const moveit_msgs::msg::PlanningSceneWorld &msg, const std::string &name)
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningSceneWorld >::ConstPtr PlanningSceneWorldWithMetadata
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31