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 #include <moveit/utils/logger.hpp>
39 
40 #include <utility>
41 
42 const std::string moveit_warehouse::PlanningSceneWorldStorage::DATABASE_NAME = "moveit_planning_scene_worlds";
44 
45 using warehouse_ros::Metadata;
46 using warehouse_ros::Query;
47 
49  : MoveItMessageStorage(std::move(conn)), logger_(moveit::getLogger("moveit_warehouse_planning_scene_world_storage"))
50 {
51  createCollections();
52 }
53 
54 void moveit_warehouse::PlanningSceneWorldStorage::createCollections()
55 {
56  planning_scene_world_collection_ =
57  conn_->openCollectionPtr<moveit_msgs::msg::PlanningSceneWorld>(DATABASE_NAME, "planning_scene_worlds");
58 }
59 
61 {
62  planning_scene_world_collection_.reset();
63  conn_->dropDatabase(DATABASE_NAME);
64  createCollections();
65 }
66 
67 void moveit_warehouse::PlanningSceneWorldStorage::addPlanningSceneWorld(const moveit_msgs::msg::PlanningSceneWorld& msg,
68  const std::string& name)
69 {
70  bool replace = false;
71  if (hasPlanningSceneWorld(name))
72  {
73  removePlanningSceneWorld(name);
74  replace = true;
75  }
76  Metadata::Ptr metadata = planning_scene_world_collection_->createMetadata();
77  metadata->append(PLANNING_SCENE_WORLD_ID_NAME, name);
78  planning_scene_world_collection_->insert(msg, metadata);
79  RCLCPP_DEBUG(logger_, "%s planning scene world '%s'", replace ? "Replaced" : "Added", name.c_str());
80 }
81 
83 {
84  Query::Ptr q = planning_scene_world_collection_->createQuery();
85  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
86  std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q, true);
87  return !psw.empty();
88 }
89 
91  std::vector<std::string>& names) const
92 {
93  getKnownPlanningSceneWorlds(names);
94  filterNames(regex, names);
95 }
96 
98 {
99  names.clear();
100  Query::Ptr q = planning_scene_world_collection_->createQuery();
101  std::vector<PlanningSceneWorldWithMetadata> planning_scene_worlds =
102  planning_scene_world_collection_->queryList(q, true, PLANNING_SCENE_WORLD_ID_NAME, true);
103  for (PlanningSceneWorldWithMetadata& planning_scene_world : planning_scene_worlds)
104  {
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 }
109 
111  const std::string& name) const
112 {
113  Query::Ptr q = planning_scene_world_collection_->createQuery();
114  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
115  std::vector<PlanningSceneWorldWithMetadata> psw = planning_scene_world_collection_->queryList(q, false);
116  if (psw.empty())
117  {
118  return false;
119  }
120  else
121  {
122  msg_m = psw.front();
123  return true;
124  }
125 }
126 
128  const std::string& new_name)
129 {
130  Query::Ptr q = planning_scene_world_collection_->createQuery();
131  q->append(PLANNING_SCENE_WORLD_ID_NAME, old_name);
132  Metadata::Ptr m = planning_scene_world_collection_->createMetadata();
133  m->append(PLANNING_SCENE_WORLD_ID_NAME, new_name);
134  planning_scene_world_collection_->modifyMetadata(q, m);
135  RCLCPP_DEBUG(logger_, "Renamed planning scene world from '%s' to '%s'", old_name.c_str(), new_name.c_str());
136 }
137 
139 {
140  Query::Ptr q = planning_scene_world_collection_->createQuery();
141  q->append(PLANNING_SCENE_WORLD_ID_NAME, name);
142  unsigned int rem = planning_scene_world_collection_->removeMessages(q);
143  RCLCPP_DEBUG(logger_, "Removed %u PlanningSceneWorld messages (named '%s')", rem, name.c_str());
144 }
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
Main namespace for MoveIt.
Definition: exceptions.h:43
name
Definition: setup.py:7