message_collection.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2008, Willow Garage, Inc.
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the Willow Garage, Inc. nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  *
29  */
30 
39 #include <std_msgs/String.h>
41 #include <boost/foreach.hpp>
42 #ifdef WAREHOUSE_ROS_MONGO_HAVE_MONGO_VERSION_H
43 #include <mongo/version.h>
44 #endif
45 
46 namespace warehouse_ros_mongo
47 {
48 using std::string;
49 
50 MongoMessageCollection::MongoMessageCollection(const std::shared_ptr<mongo::DBClientConnection>& conn, const string& db,
51  const string& coll)
52  : conn_(conn), gfs_(new mongo::GridFS(*conn, db)), ns_(db + "." + coll), db_(db), coll_(coll)
53 {
54 }
55 
56 bool MongoMessageCollection::initialize(const std::string& datatype, const std::string& md5)
57 {
58  ensureIndex("creation_time");
59 
60  // Add to the metatable
61  const string meta_ns = db_ + ".ros_message_collections";
62  if (!conn_->count(meta_ns, BSON("name" << coll_)))
63  {
64  ROS_DEBUG_NAMED("create_collection", "Inserting info for %s into metatable", coll_.c_str());
65  conn_->insert(meta_ns, BSON("name" << coll_ << "type" << datatype << "md5sum" << md5));
66  }
67  else if (!conn_->count(meta_ns, BSON("name" << coll_ << "md5sum" << md5)))
68  {
69  ROS_ERROR("The md5 sum for message %s changed to %s. Only reading metadata.", datatype.c_str(), md5.c_str());
70  return false;
71  }
72  return true;
73 }
74 
75 void MongoMessageCollection::ensureIndex(const string& field)
76 {
77 #if (MONGOCLIENT_VERSION_MAJOR >= 1)
78  conn_->createIndex(ns_, BSON(field << 1));
79 #else
80  conn_->ensureIndex(ns_, BSON(field << 1));
81 #endif
82 }
83 
84 void MongoMessageCollection::insert(char* msg, size_t msg_size, Metadata::ConstPtr metadata)
85 {
87  mongo::BSONObj bson = downcastMetadata(metadata);
88  mongo::OID id;
89  bson["_id"].Val(id);
90 
91  // Store in message in grid fs
92  mongo::BSONObj file_obj = gfs_->storeFile(msg, msg_size, id.toString());
93 
94  // Add blob id to metadata and store it in the message collection
95  mongo::BSONObjBuilder builder;
96  builder.appendElements(bson);
97  mongo::OID blob_id;
98  file_obj["_id"].Val(blob_id);
99  builder.append("blob_id", blob_id);
100  mongo::BSONObj entry = builder.obj();
101  ROS_DEBUG_NAMED("insert", "Inserting %s into %s", entry.toString().c_str(), ns_.c_str());
102  conn_->insert(ns_, entry);
103 }
104 
106  bool ascending) const
107 {
108  mongo::Query mquery(downcastQuery(query));
109  if (!sort_by.empty())
110  mquery.sort(sort_by, ascending ? 1 : -1);
111  ROS_DEBUG_NAMED("query", "Sending query %s to %s", mquery.toString().c_str(), ns_.c_str());
112  return typename ResultIteratorHelper::Ptr(new MongoResultIterator(conn_, gfs_, ns_, mquery));
113 }
114 
115 void MongoMessageCollection::listMetadata(mongo::Query& mquery, std::vector<mongo::BSONObj>& metas)
116 {
117  MongoResultIterator iter(conn_, gfs_, ns_, mquery);
118  while (iter.hasData())
119  {
120  metas.push_back(iter.metadataRaw());
121  iter.next();
122  }
123 }
124 
126 {
127  mongo::Query mquery(downcastQuery(query));
128 
129  std::vector<mongo::BSONObj> metas;
130  listMetadata(mquery, metas);
131 
132  // Remove messages from db
133  conn_->remove(ns_, mquery);
134 
135  unsigned num_removed = 0;
136  // Also remove the raw messages from gridfs
137  for (const mongo::BSONObj& meta : metas)
138  {
139  mongo::OID id;
140  meta["blob_id"].Val(id);
141  gfs_->removeFile(id.toString());
142  ++num_removed;
143  }
144  return num_removed;
145 }
146 
148 {
149  mongo::BSONObj bson = downcastMetadata(m);
150  mongo::Query query(downcastQuery(q));
151 
152  std::vector<mongo::BSONObj> metas;
153  listMetadata(query, metas);
154  if (metas.empty())
156  mongo::BSONObj orig = metas.front();
157  mongo::BSONObjBuilder new_meta_builder;
158 
159  std::set<std::string> fields;
160  bson.getFieldNames(fields);
161 
162  BOOST_FOREACH (const string& f, fields)
163  {
164  if ((f != "_id") && (f != "creation_time"))
165  new_meta_builder.append(BSON("$set" << BSON(f << bson.getField(f))).getField("$set"));
166  }
167 
168  mongo::BSONObj new_meta = new_meta_builder.obj().copy();
169  conn_->update(ns_, query, new_meta);
170 }
171 
173 {
174  return conn_->count(ns_);
175 }
176 
178 {
179  return coll_;
180 }
181 
182 } // namespace warehouse_ros_mongo
MongoMessageCollection(const std::shared_ptr< mongo::DBClientConnection > &conn, const std::string &db_name, const std::string &collection_name)
std::shared_ptr< mongo::GridFS > gfs_
void modifyMetadata(Query::ConstPtr q, Metadata::ConstPtr m)
Modify metadata Find message matching q and update its metadata using m In other words, overwrite keys in the message using m, but keep keys that don&#39;t occur in m.
MongoMetadata & downcastMetadata(Metadata::ConstPtr metadata) const
f
unsigned removeMessages(Query::ConstPtr query)
Remove messages matching query.
bool initialize(const std::string &datatype, const std::string &md5)
void insert(char *msg, size_t msg_size, Metadata::ConstPtr metadata)
Insert a ROS message, together with some optional metadata, into the db.
#define ROS_DEBUG_NAMED(name,...)
void listMetadata(mongo::Query &mquery, std::vector< mongo::BSONObj > &metas)
boost::shared_ptr< ResultIteratorHelper > Ptr
std::shared_ptr< mongo::DBClientConnection > conn_
std::string collectionName() const
Return name of collection.
MongoQuery & downcastQuery(Query::ConstPtr query) const
unsigned count()
Count messages in collection.
#define ROS_ERROR(...)
ResultIteratorHelper::Ptr query(Query::ConstPtr query, const std::string &sort_by, bool ascending) const
void ensureIndex(const std::string &field)


warehouse_ros_mongo
Author(s): Bhaskara Marthi , Connor Brew
autogenerated on Sat Apr 2 2022 02:29:13