moveit2
The MoveIt Motion Planning Framework for ROS 2.
planning_scene_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 <utility>
39 #include <rclcpp/serialization.hpp>
40 #include <regex>
41 
42 const std::string moveit_warehouse::PlanningSceneStorage::DATABASE_NAME = "moveit_planning_scenes";
43 
44 const std::string moveit_warehouse::PlanningSceneStorage::PLANNING_SCENE_ID_NAME = "planning_scene_id";
45 const std::string moveit_warehouse::PlanningSceneStorage::MOTION_PLAN_REQUEST_ID_NAME = "motion_request_id";
46 
47 using warehouse_ros::Metadata;
48 using warehouse_ros::Query;
49 
50 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.planning_scene_storage");
51 
52 moveit_warehouse::PlanningSceneStorage::PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
53  : MoveItMessageStorage(std::move(conn))
54 {
55  createCollections();
56 }
57 
58 void moveit_warehouse::PlanningSceneStorage::createCollections()
59 {
60  planning_scene_collection_ =
61  conn_->openCollectionPtr<moveit_msgs::msg::PlanningScene>(DATABASE_NAME, "planning_scene");
62  motion_plan_request_collection_ =
63  conn_->openCollectionPtr<moveit_msgs::msg::MotionPlanRequest>(DATABASE_NAME, "motion_plan_request");
64  robot_trajectory_collection_ =
65  conn_->openCollectionPtr<moveit_msgs::msg::RobotTrajectory>(DATABASE_NAME, "robot_trajectory");
66 }
67 
69 {
70  planning_scene_collection_.reset();
71  motion_plan_request_collection_.reset();
72  robot_trajectory_collection_.reset();
73  conn_->dropDatabase(DATABASE_NAME);
74  createCollections();
75 }
76 
77 void moveit_warehouse::PlanningSceneStorage::addPlanningScene(const moveit_msgs::msg::PlanningScene& scene)
78 {
79  bool replace = false;
80  if (hasPlanningScene(scene.name))
81  {
82  removePlanningScene(scene.name);
83  replace = true;
84  }
85  Metadata::Ptr metadata = planning_scene_collection_->createMetadata();
86  metadata->append(PLANNING_SCENE_ID_NAME, scene.name);
87  planning_scene_collection_->insert(scene, metadata);
88  RCLCPP_DEBUG(LOGGER, "%s scene '%s'", replace ? "Replaced" : "Added", scene.name.c_str());
89 }
90 
92 {
93  Query::Ptr q = planning_scene_collection_->createQuery();
94  q->append(PLANNING_SCENE_ID_NAME, name);
95  std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q, true);
96  return !planning_scenes.empty();
97 }
98 
99 std::string moveit_warehouse::PlanningSceneStorage::getMotionPlanRequestName(
100  const moveit_msgs::msg::MotionPlanRequest& planning_query, const std::string& scene_name) const
101 {
102  // get all existing motion planning requests for this planning scene
103  Query::Ptr q = motion_plan_request_collection_->createQuery();
104  q->append(PLANNING_SCENE_ID_NAME, scene_name);
105  std::vector<MotionPlanRequestWithMetadata> existing_requests = motion_plan_request_collection_->queryList(q, false);
106 
107  // if there are no requests stored, we are done
108  if (existing_requests.empty())
109  return "";
110 
111  // compute the serialization of the message passed as argument
112  rclcpp::Serialization<moveit_msgs::msg::MotionPlanRequest> serializer;
113  rclcpp::SerializedMessage serialized_msg_arg;
114  serializer.serialize_message(&planning_query, &serialized_msg_arg);
115  const size_t serial_size_arg = serialized_msg_arg.size();
116  const void* data_arg = serialized_msg_arg.get_rcl_serialized_message().buffer;
117 
118  for (MotionPlanRequestWithMetadata& existing_request : existing_requests)
119  {
120  auto msg = static_cast<const moveit_msgs::msg::MotionPlanRequest&>(*existing_request);
121  rclcpp::SerializedMessage serialized_msg;
122  serializer.serialize_message(&msg, &serialized_msg);
123  const size_t serial_size = serialized_msg.size();
124  const void* data = serialized_msg.get_rcl_serialized_message().buffer;
125 
126  if (serial_size != serial_size_arg)
127  continue;
128  if (memcmp(data_arg, data, serial_size) == 0)
129  // we found the same message twice
130  return existing_request->lookupString(MOTION_PLAN_REQUEST_ID_NAME);
131  }
132  return "";
133 }
134 
136  const std::string& scene_name,
137  const std::string& query_name)
138 {
139  std::string id = getMotionPlanRequestName(planning_query, scene_name);
140 
141  // if we are trying to overwrite, we remove the old query first (if it exists).
142  if (!query_name.empty() && id.empty())
143  removePlanningQuery(scene_name, query_name);
144 
145  if (id != query_name || id.empty())
146  addNewPlanningRequest(planning_query, scene_name, query_name);
147 }
148 
149 std::string
150 moveit_warehouse::PlanningSceneStorage::addNewPlanningRequest(const moveit_msgs::msg::MotionPlanRequest& planning_query,
151  const std::string& scene_name,
152  const std::string& query_name)
153 {
154  std::string id = query_name;
155  if (id.empty())
156  {
157  std::set<std::string> used;
158  Query::Ptr q = motion_plan_request_collection_->createQuery();
159  q->append(PLANNING_SCENE_ID_NAME, scene_name);
160  std::vector<MotionPlanRequestWithMetadata> existing_requests = motion_plan_request_collection_->queryList(q, true);
161  for (MotionPlanRequestWithMetadata& existing_request : existing_requests)
162  used.insert(existing_request->lookupString(MOTION_PLAN_REQUEST_ID_NAME));
163  std::size_t index = existing_requests.size();
164  do
165  {
166  id = "Motion Plan Request " + std::to_string(index);
167  index++;
168  } while (used.find(id) != used.end());
169  }
170  Metadata::Ptr metadata = motion_plan_request_collection_->createMetadata();
171  metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
172  metadata->append(MOTION_PLAN_REQUEST_ID_NAME, id);
173  motion_plan_request_collection_->insert(planning_query, metadata);
174  RCLCPP_DEBUG(LOGGER, "Saved planning query '%s' for scene '%s'", id.c_str(), scene_name.c_str());
175  return id;
176 }
177 
179  const moveit_msgs::msg::RobotTrajectory& result,
180  const std::string& scene_name)
181 {
182  std::string id = getMotionPlanRequestName(planning_query, scene_name);
183  if (id.empty())
184  id = addNewPlanningRequest(planning_query, scene_name, "");
185  Metadata::Ptr metadata = robot_trajectory_collection_->createMetadata();
186  metadata->append(PLANNING_SCENE_ID_NAME, scene_name);
187  metadata->append(MOTION_PLAN_REQUEST_ID_NAME, id);
188  robot_trajectory_collection_->insert(result, metadata);
189 }
190 
191 void moveit_warehouse::PlanningSceneStorage::getPlanningSceneNames(std::vector<std::string>& names) const
192 {
193  names.clear();
194  Query::Ptr q = planning_scene_collection_->createQuery();
195  std::vector<PlanningSceneWithMetadata> planning_scenes =
196  planning_scene_collection_->queryList(q, true, PLANNING_SCENE_ID_NAME, true);
197  for (PlanningSceneWithMetadata& planning_scene : planning_scenes)
198  if (planning_scene->lookupField(PLANNING_SCENE_ID_NAME))
199  names.push_back(planning_scene->lookupString(PLANNING_SCENE_ID_NAME));
200 }
201 
203  std::vector<std::string>& names) const
204 {
205  getPlanningSceneNames(names);
206  filterNames(regex, names);
207 }
208 
209 bool moveit_warehouse::PlanningSceneStorage::getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld& world,
210  const std::string& scene_name) const
211 {
213  if (getPlanningScene(scene_m, scene_name))
214  {
215  world = scene_m->world;
216  return true;
217  }
218  else
219  return false;
220 }
221 
223  const std::string& scene_name) const
224 {
225  Query::Ptr q = planning_scene_collection_->createQuery();
226  q->append(PLANNING_SCENE_ID_NAME, scene_name);
227  std::vector<PlanningSceneWithMetadata> planning_scenes = planning_scene_collection_->queryList(q, false);
228  if (planning_scenes.empty())
229  {
230  RCLCPP_WARN(LOGGER, "Planning scene '%s' was not found in the database", scene_name.c_str());
231  return false;
232  }
233  scene_m = planning_scenes.back();
234  // in case the scene was renamed, the name in the message may be out of date
235  const_cast<moveit_msgs::msg::PlanningScene*>(static_cast<const moveit_msgs::msg::PlanningScene*>(scene_m.get()))->name =
236  scene_name;
237  return true;
238 }
239 
241  const std::string& scene_name,
242  const std::string& query_name)
243 {
244  Query::Ptr q = motion_plan_request_collection_->createQuery();
245  q->append(PLANNING_SCENE_ID_NAME, scene_name);
246  q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
247  std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q, false);
248  if (planning_queries.empty())
249  {
250  RCLCPP_ERROR(LOGGER, "Planning query '%s' not found for scene '%s'", query_name.c_str(), scene_name.c_str());
251  return false;
252  }
253  else
254  {
255  query_m = planning_queries.front();
256  return true;
257  }
258 }
259 
261  std::vector<MotionPlanRequestWithMetadata>& planning_queries, const std::string& scene_name) const
262 {
263  Query::Ptr q = motion_plan_request_collection_->createQuery();
264  q->append(PLANNING_SCENE_ID_NAME, scene_name);
265  planning_queries = motion_plan_request_collection_->queryList(q, false);
266 }
267 
268 void moveit_warehouse::PlanningSceneStorage::getPlanningQueriesNames(std::vector<std::string>& query_names,
269  const std::string& scene_name) const
270 {
271  Query::Ptr q = motion_plan_request_collection_->createQuery();
272  q->append(PLANNING_SCENE_ID_NAME, scene_name);
273  std::vector<MotionPlanRequestWithMetadata> planning_queries = motion_plan_request_collection_->queryList(q, true);
274  query_names.clear();
275  for (MotionPlanRequestWithMetadata& planning_query : planning_queries)
276  if (planning_query->lookupField(MOTION_PLAN_REQUEST_ID_NAME))
277  query_names.push_back(planning_query->lookupString(MOTION_PLAN_REQUEST_ID_NAME));
278 }
279 
281  std::vector<std::string>& query_names,
282  const std::string& scene_name) const
283 {
284  getPlanningQueriesNames(query_names, scene_name);
285 
286  if (!regex.empty())
287  {
288  std::vector<std::string> fnames;
289  std::regex r(regex);
290  for (const std::string& query_name : query_names)
291  {
292  std::smatch match;
293  if (std::regex_match(query_name, match, r))
294  {
295  fnames.push_back(query_name);
296  }
297  }
298  query_names.swap(fnames);
299  }
300 }
301 
303  std::vector<MotionPlanRequestWithMetadata>& planning_queries, std::vector<std::string>& query_names,
304  const std::string& scene_name) const
305 {
306  Query::Ptr q = motion_plan_request_collection_->createQuery();
307  q->append(PLANNING_SCENE_ID_NAME, scene_name);
308  planning_queries = motion_plan_request_collection_->queryList(q, false);
309  query_names.resize(planning_queries.size());
310  for (std::size_t i = 0; i < planning_queries.size(); ++i)
311  if (planning_queries[i]->lookupField(MOTION_PLAN_REQUEST_ID_NAME))
312  query_names[i] = planning_queries[i]->lookupString(MOTION_PLAN_REQUEST_ID_NAME);
313  else
314  query_names[i].clear();
315 }
316 
318  std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
319  const moveit_msgs::msg::MotionPlanRequest& planning_query) const
320 {
321  std::string id = getMotionPlanRequestName(planning_query, scene_name);
322  if (id.empty())
323  planning_results.clear();
324  else
325  getPlanningResults(planning_results, id, scene_name);
326 }
327 
329  std::vector<RobotTrajectoryWithMetadata>& planning_results, const std::string& scene_name,
330  const std::string& planning_query) const
331 {
332  Query::Ptr q = robot_trajectory_collection_->createQuery();
333  q->append(PLANNING_SCENE_ID_NAME, scene_name);
334  q->append(MOTION_PLAN_REQUEST_ID_NAME, planning_query);
335  planning_results = robot_trajectory_collection_->queryList(q, false);
336 }
337 
339  const std::string& query_name) const
340 {
341  Query::Ptr q = motion_plan_request_collection_->createQuery();
342  q->append(PLANNING_SCENE_ID_NAME, scene_name);
343  q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
344  std::vector<MotionPlanRequestWithMetadata> queries = motion_plan_request_collection_->queryList(q, true);
345  return !queries.empty();
346 }
347 
348 void moveit_warehouse::PlanningSceneStorage::renamePlanningScene(const std::string& old_scene_name,
349  const std::string& new_scene_name)
350 {
351  Query::Ptr q = planning_scene_collection_->createQuery();
352  q->append(PLANNING_SCENE_ID_NAME, old_scene_name);
353  Metadata::Ptr m = planning_scene_collection_->createMetadata();
354  m->append(PLANNING_SCENE_ID_NAME, new_scene_name);
355  planning_scene_collection_->modifyMetadata(q, m);
356  RCLCPP_DEBUG(LOGGER, "Renamed planning scene from '%s' to '%s'", old_scene_name.c_str(), new_scene_name.c_str());
357 }
358 
360  const std::string& old_query_name,
361  const std::string& new_query_name)
362 {
363  Query::Ptr q = motion_plan_request_collection_->createQuery();
364  q->append(PLANNING_SCENE_ID_NAME, scene_name);
365  q->append(MOTION_PLAN_REQUEST_ID_NAME, old_query_name);
366  Metadata::Ptr m = motion_plan_request_collection_->createMetadata();
367  m->append(MOTION_PLAN_REQUEST_ID_NAME, new_query_name);
368  motion_plan_request_collection_->modifyMetadata(q, m);
369  RCLCPP_DEBUG(LOGGER, "Renamed planning query for scene '%s' from '%s' to '%s'", scene_name.c_str(),
370  old_query_name.c_str(), new_query_name.c_str());
371 }
372 
374 {
375  removePlanningQueries(scene_name);
376  Query::Ptr q = planning_scene_collection_->createQuery();
377  q->append(PLANNING_SCENE_ID_NAME, scene_name);
378  unsigned int rem = planning_scene_collection_->removeMessages(q);
379  RCLCPP_DEBUG(LOGGER, "Removed %u PlanningScene messages (named '%s')", rem, scene_name.c_str());
380 }
381 
383 {
384  removePlanningResults(scene_name);
385  Query::Ptr q = motion_plan_request_collection_->createQuery();
386  q->append(PLANNING_SCENE_ID_NAME, scene_name);
387  unsigned int rem = motion_plan_request_collection_->removeMessages(q);
388  RCLCPP_DEBUG(LOGGER, "Removed %u MotionPlanRequest messages for scene '%s'", rem, scene_name.c_str());
389 }
390 
392  const std::string& query_name)
393 {
394  removePlanningResults(scene_name, query_name);
395  Query::Ptr q = motion_plan_request_collection_->createQuery();
396  q->append(PLANNING_SCENE_ID_NAME, scene_name);
397  q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
398  unsigned int rem = motion_plan_request_collection_->removeMessages(q);
399  RCLCPP_DEBUG(LOGGER, "Removed %u MotionPlanRequest messages for scene '%s', query '%s'", rem, scene_name.c_str(),
400  query_name.c_str());
401 }
402 
404 {
405  Query::Ptr q = robot_trajectory_collection_->createQuery();
406  q->append(PLANNING_SCENE_ID_NAME, scene_name);
407  unsigned int rem = robot_trajectory_collection_->removeMessages(q);
408  RCLCPP_DEBUG(LOGGER, "Removed %u RobotTrajectory messages for scene '%s'", rem, scene_name.c_str());
409 }
410 
412  const std::string& query_name)
413 {
414  Query::Ptr q = robot_trajectory_collection_->createQuery();
415  q->append(PLANNING_SCENE_ID_NAME, scene_name);
416  q->append(MOTION_PLAN_REQUEST_ID_NAME, query_name);
417  unsigned int rem = robot_trajectory_collection_->removeMessages(q);
418  RCLCPP_DEBUG(LOGGER, "Removed %u RobotTrajectory messages for scene '%s', query '%s'", rem, scene_name.c_str(),
419  query_name.c_str());
420 }
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
bool getPlanningSceneWorld(moveit_msgs::msg::PlanningSceneWorld &world, const std::string &scene_name) const
void removePlanningScene(const std::string &scene_name)
void addPlanningQuery(const moveit_msgs::msg::MotionPlanRequest &planning_query, const std::string &scene_name, const std::string &query_name="")
void removePlanningQuery(const std::string &scene_name, const std::string &query_name)
void getPlanningResults(std::vector< RobotTrajectoryWithMetadata > &planning_results, const std::string &scene_name, const moveit_msgs::msg::MotionPlanRequest &planning_query) const
void removePlanningQueries(const std::string &scene_name)
PlanningSceneStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void addPlanningResult(const moveit_msgs::msg::MotionPlanRequest &planning_query, const moveit_msgs::msg::RobotTrajectory &result, const std::string &scene_name)
void renamePlanningQuery(const std::string &scene_name, const std::string &old_query_name, const std::string &new_query_name)
bool hasPlanningQuery(const std::string &scene_name, const std::string &query_name) const
void getPlanningQueries(std::vector< MotionPlanRequestWithMetadata > &planning_queries, const std::string &scene_name) const
void removePlanningResults(const std::string &scene_name)
void addPlanningScene(const moveit_msgs::msg::PlanningScene &scene)
bool getPlanningQuery(MotionPlanRequestWithMetadata &query_m, const std::string &scene_name, const std::string &query_name)
void renamePlanningScene(const std::string &old_scene_name, const std::string &new_scene_name)
void getPlanningSceneNames(std::vector< std::string > &names) const
void getPlanningQueriesNames(std::vector< std::string > &query_names, const std::string &scene_name) const
bool hasPlanningScene(const std::string &name) const
static const std::string MOTION_PLAN_REQUEST_ID_NAME
bool getPlanningScene(PlanningSceneWithMetadata &scene_m, const std::string &scene_name) const
Get the latest planning scene named scene_name.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::PlanningScene >::ConstPtr PlanningSceneWithMetadata
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::MotionPlanRequest >::ConstPtr MotionPlanRequestWithMetadata
scene
Definition: pick.py:52
r
Definition: plan.py:56
moveit_msgs::msg::MotionPlanRequest MotionPlanRequest
This namespace includes the central class for representing planning contexts.
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31