moveit2
The MoveIt Motion Planning Framework for ROS 2.
constraints_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::ConstraintsStorage::DATABASE_NAME = "moveit_constraints";
42 
43 const std::string moveit_warehouse::ConstraintsStorage::CONSTRAINTS_ID_NAME = "constraints_id";
45 const std::string moveit_warehouse::ConstraintsStorage::ROBOT_NAME = "robot_id";
46 
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.constraints_storage");
48 
49 using warehouse_ros::Metadata;
50 using warehouse_ros::Query;
51 
52 moveit_warehouse::ConstraintsStorage::ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
53  : MoveItMessageStorage(std::move(conn))
54 {
55  createCollections();
56 }
57 
58 void moveit_warehouse::ConstraintsStorage::createCollections()
59 {
60  constraints_collection_ = conn_->openCollectionPtr<moveit_msgs::msg::Constraints>(DATABASE_NAME, "constraints");
61 }
62 
64 {
65  constraints_collection_.reset();
66  conn_->dropDatabase(DATABASE_NAME);
67  createCollections();
68 }
69 
70 void moveit_warehouse::ConstraintsStorage::addConstraints(const moveit_msgs::msg::Constraints& msg,
71  const std::string& robot, const std::string& group)
72 {
73  bool replace = false;
74  if (hasConstraints(msg.name, robot, group))
75  {
76  removeConstraints(msg.name, robot, group);
77  replace = true;
78  }
79  Metadata::Ptr metadata = constraints_collection_->createMetadata();
80  metadata->append(CONSTRAINTS_ID_NAME, msg.name);
81  metadata->append(ROBOT_NAME, robot);
82  metadata->append(CONSTRAINTS_GROUP_NAME, group);
83  constraints_collection_->insert(msg, metadata);
84  RCLCPP_DEBUG(LOGGER, "%s constraints '%s'", replace ? "Replaced" : "Added", msg.name.c_str());
85 }
86 
87 bool moveit_warehouse::ConstraintsStorage::hasConstraints(const std::string& name, const std::string& robot,
88  const std::string& group) const
89 {
90  Query::Ptr q = constraints_collection_->createQuery();
91  q->append(CONSTRAINTS_ID_NAME, name);
92  if (!robot.empty())
93  q->append(ROBOT_NAME, robot);
94  if (!group.empty())
95  q->append(CONSTRAINTS_GROUP_NAME, group);
96  std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true);
97  return !constr.empty();
98 }
99 
101  std::vector<std::string>& names,
102  const std::string& robot, const std::string& group) const
103 {
104  getKnownConstraints(names, robot, group);
105  filterNames(regex, names);
106 }
107 
109  const std::string& robot, const std::string& group) const
110 {
111  names.clear();
112  Query::Ptr q = constraints_collection_->createQuery();
113  if (!robot.empty())
114  q->append(ROBOT_NAME, robot);
115  if (!group.empty())
116  q->append(CONSTRAINTS_GROUP_NAME, group);
117  std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true, CONSTRAINTS_ID_NAME, true);
118  for (const ConstraintsWithMetadata& it : constr)
119  if (it->lookupField(CONSTRAINTS_ID_NAME))
120  names.push_back(it->lookupString(CONSTRAINTS_ID_NAME));
121 }
122 
124  const std::string& robot, const std::string& group) const
125 {
126  Query::Ptr q = constraints_collection_->createQuery();
127  q->append(CONSTRAINTS_ID_NAME, name);
128  if (!robot.empty())
129  q->append(ROBOT_NAME, robot);
130  if (!group.empty())
131  q->append(CONSTRAINTS_GROUP_NAME, group);
132  std::vector<ConstraintsWithMetadata> constr = constraints_collection_->queryList(q, false);
133  if (constr.empty())
134  return false;
135  else
136  {
137  msg_m = constr.back();
138  // in case the constraints were renamed, the name in the message may be out of date
139  const_cast<moveit_msgs::msg::Constraints*>(static_cast<const moveit_msgs::msg::Constraints*>(msg_m.get()))->name =
140  name;
141  return true;
142  }
143 }
144 
145 void moveit_warehouse::ConstraintsStorage::renameConstraints(const std::string& old_name, const std::string& new_name,
146  const std::string& robot, const std::string& group)
147 {
148  Query::Ptr q = constraints_collection_->createQuery();
149  q->append(CONSTRAINTS_ID_NAME, old_name);
150  if (!robot.empty())
151  q->append(ROBOT_NAME, robot);
152  if (!group.empty())
153  q->append(CONSTRAINTS_GROUP_NAME, group);
154  Metadata::Ptr m = constraints_collection_->createMetadata();
155  m->append(CONSTRAINTS_ID_NAME, new_name);
156  constraints_collection_->modifyMetadata(q, m);
157  RCLCPP_DEBUG(LOGGER, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
158 }
159 
160 void moveit_warehouse::ConstraintsStorage::removeConstraints(const std::string& name, const std::string& robot,
161  const std::string& group)
162 {
163  Query::Ptr q = constraints_collection_->createQuery();
164  q->append(CONSTRAINTS_ID_NAME, name);
165  if (!robot.empty())
166  q->append(ROBOT_NAME, robot);
167  if (!group.empty())
168  q->append(CONSTRAINTS_GROUP_NAME, group);
169  unsigned int rem = constraints_collection_->removeMessages(q);
170  RCLCPP_DEBUG(LOGGER, "Removed %u Constraints messages (named '%s')", rem, name.c_str());
171 }
void removeConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
ConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
bool hasConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
static const std::string DATABASE_NAME
bool getConstraints(ConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
void renameConstraints(const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="")
void getKnownConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
static const std::string CONSTRAINTS_ID_NAME
void addConstraints(const moveit_msgs::msg::Constraints &msg, const std::string &robot="", const std::string &group="")
static const std::string CONSTRAINTS_GROUP_NAME
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::Constraints >::ConstPtr ConstraintsWithMetadata
robot
Definition: pick.py:53
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31