state_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::RobotStateStorage::DATABASE_NAME = "moveit_robot_states";
42 
43 const std::string moveit_warehouse::RobotStateStorage::STATE_NAME = "state_id";
44 const std::string moveit_warehouse::RobotStateStorage::ROBOT_NAME = "robot_id";
45 
48 
50  : MoveItMessageStorage(std::move(conn))
51 {
53 }
54 
56 {
57  state_collection_ = conn_->openCollectionPtr<moveit_msgs::RobotState>(DATABASE_NAME, "robot_states");
58 }
59 
61 {
62  state_collection_.reset();
63  conn_->dropDatabase(DATABASE_NAME);
64  createCollections();
65 }
66 
67 void moveit_warehouse::RobotStateStorage::addRobotState(const moveit_msgs::RobotState& msg, const std::string& name,
68  const std::string& robot)
69 {
70  bool replace = false;
71  if (hasRobotState(name, robot))
72  {
73  removeRobotState(name, robot);
74  replace = true;
75  }
76  Metadata::Ptr metadata = state_collection_->createMetadata();
77  metadata->append(STATE_NAME, name);
78  metadata->append(ROBOT_NAME, robot);
79  state_collection_->insert(msg, metadata);
80  ROS_DEBUG("%s robot state '%s'", replace ? "Replaced" : "Added", name.c_str());
81 }
82 
83 bool moveit_warehouse::RobotStateStorage::hasRobotState(const std::string& name, const std::string& robot) const
84 {
85  Query::Ptr q = state_collection_->createQuery();
86  q->append(STATE_NAME, name);
87  if (!robot.empty())
88  q->append(ROBOT_NAME, robot);
89  std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true);
90  return !constr.empty();
91 }
92 
93 void moveit_warehouse::RobotStateStorage::getKnownRobotStates(const std::string& regex, std::vector<std::string>& names,
94  const std::string& robot) const
95 {
96  getKnownRobotStates(names, robot);
97  filterNames(regex, names);
98 }
99 
100 void moveit_warehouse::RobotStateStorage::getKnownRobotStates(std::vector<std::string>& names,
101  const std::string& robot) const
102 {
103  names.clear();
104  Query::Ptr q = state_collection_->createQuery();
105  if (!robot.empty())
106  q->append(ROBOT_NAME, robot);
107  std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, true, STATE_NAME, true);
108  for (RobotStateWithMetadata& state : constr)
109  if (state->lookupField(STATE_NAME))
110  names.push_back(state->lookupString(STATE_NAME));
111 }
112 
114  const std::string& robot) const
115 {
116  Query::Ptr q = state_collection_->createQuery();
117  q->append(STATE_NAME, name);
118  if (!robot.empty())
119  q->append(ROBOT_NAME, robot);
120  std::vector<RobotStateWithMetadata> constr = state_collection_->queryList(q, false);
121  if (constr.empty())
122  return false;
123  else
124  {
125  msg_m = constr.front();
126  return true;
127  }
128 }
129 
130 void moveit_warehouse::RobotStateStorage::renameRobotState(const std::string& old_name, const std::string& new_name,
131  const std::string& robot)
132 {
133  Query::Ptr q = state_collection_->createQuery();
134  q->append(STATE_NAME, old_name);
135  if (!robot.empty())
136  q->append(ROBOT_NAME, robot);
137  Metadata::Ptr m = state_collection_->createMetadata();
138  m->append(STATE_NAME, new_name);
139  state_collection_->modifyMetadata(q, m);
140  ROS_DEBUG("Renamed robot state from '%s' to '%s'", old_name.c_str(), new_name.c_str());
141 }
142 
143 void moveit_warehouse::RobotStateStorage::removeRobotState(const std::string& name, const std::string& robot)
144 {
145  Query::Ptr q = state_collection_->createQuery();
146  q->append(STATE_NAME, name);
147  if (!robot.empty())
148  q->append(ROBOT_NAME, robot);
149  unsigned int rem = state_collection_->removeMessages(q);
150  ROS_DEBUG("Removed %u RobotState messages (named '%s')", rem, name.c_str());
151 }
boost::shared_ptr< DatabaseConnection >
moveit_warehouse::RobotStateStorage::addRobotState
void addRobotState(const moveit_msgs::RobotState &msg, const std::string &name, const std::string &robot="")
Definition: state_storage.cpp:67
moveit_warehouse::RobotStateStorage::hasRobotState
bool hasRobotState(const std::string &name, const std::string &robot="") const
Definition: state_storage.cpp:83
state_storage.h
warehouse_ros::Metadata
moveit_warehouse::RobotStateStorage::ROBOT_NAME
static const std::string ROBOT_NAME
Definition: state_storage.h:88
ROS_DEBUG
#define ROS_DEBUG(...)
moveit_warehouse::RobotStateStorage::renameRobotState
void renameRobotState(const std::string &old_name, const std::string &new_name, const std::string &robot="")
Definition: state_storage.cpp:130
moveit_warehouse::RobotStateStorage::DATABASE_NAME
static const std::string DATABASE_NAME
Definition: state_storage.h:85
name
std::string name
moveit_warehouse::RobotStateStorage::getKnownRobotStates
void getKnownRobotStates(std::vector< std::string > &names, const std::string &robot="") const
Definition: state_storage.cpp:100
moveit_warehouse::RobotStateStorage::STATE_NAME
static const std::string STATE_NAME
Definition: state_storage.h:87
moveit_warehouse::MoveItMessageStorage
This class provides the mechanism to connect to a database and reads needed ROS parameters when appro...
Definition: moveit_message_storage.h:79
std
moveit_warehouse::RobotStateStorage::removeRobotState
void removeRobotState(const std::string &name, const std::string &robot="")
Definition: state_storage.cpp:143
moveit_warehouse::RobotStateStorage::reset
void reset()
Definition: state_storage.cpp:60
warehouse_ros::Query
moveit_warehouse::RobotStateStorage::getRobotState
bool getRobotState(RobotStateWithMetadata &msg_m, const std::string &name, const std::string &robot="") const
Get the constraints named name. Return false on failure.
Definition: state_storage.cpp:113
moveit_warehouse::RobotStateStorage::RobotStateStorage
RobotStateStorage(warehouse_ros::DatabaseConnection::Ptr conn)
Definition: state_storage.cpp:49
moveit_warehouse::RobotStateStorage::createCollections
void createCollections()
Definition: state_storage.cpp:55


warehouse
Author(s): Ioan Sucan
autogenerated on Fri May 3 2024 02:30:09