moveit2
The MoveIt Motion Planning Framework for ROS 2.
trajectory_constraints_storage.cpp
Go to the documentation of this file.
1 /*********************************************************************
2  * Software License Agreement (BSD License)
3  *
4  * Copyright (c) 2013, 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: Mario Prats, Ioan Sucan */
36 
38 
39 #include <utility>
40 
41 const std::string moveit_warehouse::TrajectoryConstraintsStorage::DATABASE_NAME = "moveit_trajectory_constraints";
42 
46 
47 static const rclcpp::Logger LOGGER = rclcpp::get_logger("moveit.ros.warehouse.trajectory_constraints_storage");
48 
49 using warehouse_ros::Metadata;
50 using warehouse_ros::Query;
51 
53  : MoveItMessageStorage(std::move(conn))
54 {
55  createCollections();
56 }
57 
58 void moveit_warehouse::TrajectoryConstraintsStorage::createCollections()
59 {
60  constraints_collection_ =
61  conn_->openCollectionPtr<moveit_msgs::msg::TrajectoryConstraints>(DATABASE_NAME, "trajectory_constraints");
62 }
63 
65 {
66  constraints_collection_.reset();
67  conn_->dropDatabase(DATABASE_NAME);
68  createCollections();
69 }
70 
72  const moveit_msgs::msg::TrajectoryConstraints& msg, const std::string& name, const std::string& robot,
73  const std::string& group)
74 {
75  bool replace = false;
76  if (hasTrajectoryConstraints(name, robot, group))
77  {
78  removeTrajectoryConstraints(name, robot, group);
79  replace = true;
80  }
81  Metadata::Ptr metadata = constraints_collection_->createMetadata();
82  metadata->append(CONSTRAINTS_ID_NAME, name);
83  metadata->append(ROBOT_NAME, robot);
84  metadata->append(CONSTRAINTS_GROUP_NAME, group);
85  constraints_collection_->insert(msg, metadata);
86  RCLCPP_DEBUG(LOGGER, "%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
87 }
88 
90  const std::string& robot,
91  const std::string& group) const
92 {
93  Query::Ptr q = constraints_collection_->createQuery();
94  q->append(CONSTRAINTS_ID_NAME, name);
95  if (!robot.empty())
96  q->append(ROBOT_NAME, robot);
97  if (!group.empty())
98  q->append(CONSTRAINTS_GROUP_NAME, group);
99  std::vector<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true);
100  return !constr.empty();
101 }
102 
104  std::vector<std::string>& names,
105  const std::string& robot,
106  const std::string& group) const
107 {
108  getKnownTrajectoryConstraints(names, robot, group);
109  filterNames(regex, names);
110 }
111 
113  const std::string& robot,
114  const std::string& group) const
115 {
116  names.clear();
117  Query::Ptr q = constraints_collection_->createQuery();
118  if (!robot.empty())
119  q->append(ROBOT_NAME, robot);
120  if (!group.empty())
121  q->append(CONSTRAINTS_GROUP_NAME, group);
122  std::vector<TrajectoryConstraintsWithMetadata> constr =
123  constraints_collection_->queryList(q, true, CONSTRAINTS_ID_NAME, true);
124  for (TrajectoryConstraintsWithMetadata& traj_constraint : constr)
125  if (traj_constraint->lookupField(CONSTRAINTS_ID_NAME))
126  names.push_back(traj_constraint->lookupString(CONSTRAINTS_ID_NAME));
127 }
128 
130  const std::string& name,
131  const std::string& robot,
132  const std::string& group) const
133 {
134  Query::Ptr q = constraints_collection_->createQuery();
135  q->append(CONSTRAINTS_ID_NAME, name);
136  if (!robot.empty())
137  q->append(ROBOT_NAME, robot);
138  if (!group.empty())
139  q->append(CONSTRAINTS_GROUP_NAME, group);
140  std::vector<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q, false);
141  if (constr.empty())
142  return false;
143  else
144  {
145  msg_m = constr.back();
146  return true;
147  }
148 }
149 
151  const std::string& new_name,
152  const std::string& robot,
153  const std::string& group)
154 {
155  Query::Ptr q = constraints_collection_->createQuery();
156  q->append(CONSTRAINTS_ID_NAME, old_name);
157  if (!robot.empty())
158  q->append(ROBOT_NAME, robot);
159  if (!group.empty())
160  q->append(CONSTRAINTS_GROUP_NAME, group);
161  Metadata::Ptr m = constraints_collection_->createMetadata();
162  m->append(CONSTRAINTS_ID_NAME, new_name);
163  constraints_collection_->modifyMetadata(q, m);
164  RCLCPP_DEBUG(LOGGER, "Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
165 }
166 
168  const std::string& robot,
169  const std::string& group)
170 {
171  Query::Ptr q = constraints_collection_->createQuery();
172  q->append(CONSTRAINTS_ID_NAME, name);
173  if (!robot.empty())
174  q->append(ROBOT_NAME, robot);
175  if (!group.empty())
176  q->append(CONSTRAINTS_GROUP_NAME, group);
177  unsigned int rem = constraints_collection_->removeMessages(q);
178  RCLCPP_DEBUG(LOGGER, "Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
179 }
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
TrajectoryConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
bool hasTrajectoryConstraints(const std::string &name, const std::string &robot="", const std::string &group="") const
void renameTrajectoryConstraints(const std::string &old_name, const std::string &new_name, const std::string &robot="", const std::string &group="")
void getKnownTrajectoryConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
void removeTrajectoryConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
void addTrajectoryConstraints(const moveit_msgs::msg::TrajectoryConstraints &msg, const std::string &name, const std::string &robot="", const std::string &group="")
bool getTrajectoryConstraints(TrajectoryConstraintsWithMetadata &msg_m, const std::string &name, const std::string &robot="", const std::string &group="") const
Get the constraints named name. Return false on failure.
warehouse_ros::MessageWithMetadata< moveit_msgs::msg::TrajectoryConstraints >::ConstPtr TrajectoryConstraintsWithMetadata
robot
Definition: pick.py:53
name
Definition: setup.py:7
const rclcpp::Logger LOGGER
Definition: async_test.h:31