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