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 const std::string moveit_warehouse::TrajectoryConstraintsStorage::DATABASE_NAME = "moveit_trajectory_constraints";
40 
44 
47 
50  : MoveItMessageStorage(conn)
51 {
53 }
54 
56 {
58  conn_->openCollectionPtr<moveit_msgs::TrajectoryConstraints>(DATABASE_NAME, "trajectory_constraints");
59 }
60 
62 {
64  conn_->dropDatabase(DATABASE_NAME);
66 }
67 
69  const moveit_msgs::TrajectoryConstraints& msg, const std::string& name, const std::string& robot,
70  const std::string& group)
71 {
72  bool replace = false;
73  if (hasTrajectoryConstraints(name, robot, group))
74  {
75  removeTrajectoryConstraints(name, robot, group);
76  replace = true;
77  }
78  Metadata::Ptr metadata = constraints_collection_->createMetadata();
79  metadata->append(CONSTRAINTS_ID_NAME, name);
80  metadata->append(ROBOT_NAME, robot);
81  metadata->append(CONSTRAINTS_GROUP_NAME, group);
82  constraints_collection_->insert(msg, metadata);
83  ROS_DEBUG("%s constraints '%s'", replace ? "Replaced" : "Added", name.c_str());
84 }
85 
87  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<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q, true);
97  return !constr.empty();
98 }
99 
101  std::vector<std::string>& names,
102  const std::string& robot,
103  const std::string& group) const
104 {
105  getKnownTrajectoryConstraints(names, robot, group);
106  filterNames(regex, names);
107 }
108 
110  const std::string& robot,
111  const std::string& group) const
112 {
113  names.clear();
114  Query::Ptr q = constraints_collection_->createQuery();
115  if (!robot.empty())
116  q->append(ROBOT_NAME, robot);
117  if (!group.empty())
118  q->append(CONSTRAINTS_GROUP_NAME, group);
119  std::vector<TrajectoryConstraintsWithMetadata> constr =
120  constraints_collection_->queryList(q, true, CONSTRAINTS_ID_NAME, true);
121  for (std::size_t i = 0; i < constr.size(); ++i)
122  if (constr[i]->lookupField(CONSTRAINTS_ID_NAME))
123  names.push_back(constr[i]->lookupString(CONSTRAINTS_ID_NAME));
124 }
125 
127  const std::string& name,
128  const std::string& robot,
129  const std::string& group) const
130 {
131  Query::Ptr q = constraints_collection_->createQuery();
132  q->append(CONSTRAINTS_ID_NAME, name);
133  if (!robot.empty())
134  q->append(ROBOT_NAME, robot);
135  if (!group.empty())
136  q->append(CONSTRAINTS_GROUP_NAME, group);
137  std::vector<TrajectoryConstraintsWithMetadata> constr = constraints_collection_->queryList(q, false);
138  if (constr.empty())
139  return false;
140  else
141  {
142  msg_m = constr.back();
143  return true;
144  }
145 }
146 
148  const std::string& new_name,
149  const std::string& robot,
150  const std::string& group)
151 {
152  Query::Ptr q = constraints_collection_->createQuery();
153  q->append(CONSTRAINTS_ID_NAME, old_name);
154  if (!robot.empty())
155  q->append(ROBOT_NAME, robot);
156  if (!group.empty())
157  q->append(CONSTRAINTS_GROUP_NAME, group);
158  Metadata::Ptr m = constraints_collection_->createMetadata();
159  m->append(CONSTRAINTS_ID_NAME, new_name);
160  constraints_collection_->modifyMetadata(q, m);
161  ROS_DEBUG("Renamed constraints from '%s' to '%s'", old_name.c_str(), new_name.c_str());
162 }
163 
165  const std::string& robot,
166  const std::string& group)
167 {
168  Query::Ptr q = constraints_collection_->createQuery();
169  q->append(CONSTRAINTS_ID_NAME, name);
170  if (!robot.empty())
171  q->append(ROBOT_NAME, robot);
172  if (!group.empty())
173  q->append(CONSTRAINTS_GROUP_NAME, group);
174  unsigned int rem = constraints_collection_->removeMessages(q);
175  ROS_DEBUG("Removed %u TrajectoryConstraints messages (named '%s')", rem, name.c_str());
176 }
void filterNames(const std::string &regex, std::vector< std::string > &names) const
Keep only the names that match regex.
warehouse_ros::DatabaseConnection::Ptr conn_
void addTrajectoryConstraints(const moveit_msgs::TrajectoryConstraints &msg, const std::string &name, const std::string &robot="", const std::string &group="")
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
TrajectoryConstraintsStorage(warehouse_ros::DatabaseConnection::Ptr conn)
void getKnownTrajectoryConstraints(std::vector< std::string > &names, const std::string &robot="", const std::string &group="") const
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.
void removeTrajectoryConstraints(const std::string &name, const std::string &robot="", const std::string &group="")
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="")
#define ROS_DEBUG(...)


warehouse
Author(s): Ioan Sucan
autogenerated on Sun Oct 18 2020 13:18:38