#include <message_collection.h>
Public Member Functions | |
| unsigned | count () |
| Count messages in collection. | |
| MessageCollection & | ensureIndex (const std::string &field) |
| MessageWithMetadata< M >::ConstPtr | findOne (const Query &query, bool metadata_only=false) const |
| Convenience function that returns a single matching result for the query. | |
| void | insert (const M &msg, const Metadata &metadata=Metadata()) |
| Insert a ROS message, together with some optional metadata, into the db. | |
| bool | md5SumMatches () const |
| Check if the md5 sum of the messages previously stored in the database matches that of the compiled message. | |
| MessageCollection (const std::string &db_name, const std::string &collection_name, const std::string &db_host="", unsigned db_port=0, float timeout=300.0) | |
| Will connect to given database and collection. Collection is created if it doesn't exist. | |
| void | modifyMetadata (const Query &q, const Metadata &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't occur in m. | |
| std::vector< typename MessageWithMetadata< M > ::ConstPtr > | pullAllResults (const mongo::Query &query, bool metadata_only=false, const std::string &sort_by="", bool ascending=true) const |
| Convenience function that calls queryResult and puts the results into a vector. | |
| QueryResults< M >::range_t | queryResults (const mongo::Query &query, bool metadata_only=false, const std::string &sort_by="", bool ascending=true) const |
| unsigned | removeMessages (const mongo::Query &query) |
| Remove messages matching query. | |
Private Member Functions | |
| void | initialize (const std::string &db, const std::string &coll, const std::string &host, unsigned port, float timeout) |
Private Attributes | |
| boost::shared_ptr < mongo::DBClientConnection > | conn_ |
| boost::shared_ptr< mongo::GridFS > | gfs_ |
| ros::Publisher | insertion_pub_ |
| bool | md5sum_matches_ |
| ros::NodeHandle | nh_ |
| const std::string | ns_ |
Represents a collection of ROS Messages stored in a MongoDB database. Each stored message in the db has a unique id, a creation time, and optional additional metadata stored as a dictionary
Definition at line 52 of file message_collection.h.
| mongo_ros::MessageCollection< M >::MessageCollection | ( | const std::string & | db_name, |
| const std::string & | collection_name, | ||
| const std::string & | db_host = "", |
||
| unsigned | db_port = 0, |
||
| float | timeout = 300.0 |
||
| ) |
Will connect to given database and collection. Collection is created if it doesn't exist.
| db_host | If provided, will be used instead of looking up the warehouse_host ros parameter. |
| db_port | If provided, will be used instead of looking up the warehouse_port ros parameter. |
| timeout | Throw a DbConnectException if can't connect within this many seconds |
Definition at line 58 of file message_collection_impl.hpp.
| unsigned mongo_ros::MessageCollection< M >::count | ( | ) |
Count messages in collection.
Definition at line 256 of file message_collection_impl.hpp.
| MessageCollection< M > & mongo_ros::MessageCollection< M >::ensureIndex | ( | const std::string & | field | ) |
Definition at line 123 of file message_collection_impl.hpp.
| MessageWithMetadata< M >::ConstPtr mongo_ros::MessageCollection< M >::findOne | ( | const Query & | query, |
| bool | metadata_only = false |
||
| ) | const |
Convenience function that returns a single matching result for the query.
| NoMatchingMessageException |
Definition at line 205 of file message_collection_impl.hpp.
| void mongo_ros::MessageCollection< M >::initialize | ( | const std::string & | db, |
| const std::string & | coll, | ||
| const std::string & | host, | ||
| unsigned | port, | ||
| float | timeout | ||
| ) | [private] |
Definition at line 73 of file message_collection_impl.hpp.
| void mongo_ros::MessageCollection< M >::insert | ( | const M & | msg, |
| const Metadata & | metadata = Metadata() |
||
| ) |
Insert a ROS message, together with some optional metadata, into the db.
| mongo::DBException | if unable to insert |
| metadata | Metadata to insert. Note that a unique id field _id and a field creation_time will be autogenerated for all messages. |
As a secondary effect, publishes a notification message on the topic warehouse/db/collection/inserts
Get the BSON and id from the metadata
Serialize the message into a buffer
Definition at line 131 of file message_collection_impl.hpp.
| bool mongo_ros::MessageCollection< M >::md5SumMatches | ( | ) | const |
Check if the md5 sum of the messages previously stored in the database matches that of the compiled message.
Definition at line 262 of file message_collection_impl.hpp.
| void mongo_ros::MessageCollection< M >::modifyMetadata | ( | const Query & | q, |
| const Metadata & | 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't occur in m.
Definition at line 235 of file message_collection_impl.hpp.
| vector< typename MessageWithMetadata< M >::ConstPtr > mongo_ros::MessageCollection< M >::pullAllResults | ( | const mongo::Query & | query, |
| bool | metadata_only = false, |
||
| const std::string & | sort_by = "", |
||
| bool | ascending = true |
||
| ) | const |
Convenience function that calls queryResult and puts the results into a vector.
Definition at line 191 of file message_collection_impl.hpp.
| QueryResults< M >::range_t mongo_ros::MessageCollection< M >::queryResults | ( | const mongo::Query & | query, |
| bool | metadata_only = false, |
||
| const std::string & | sort_by = "", |
||
| bool | ascending = true |
||
| ) | const |
| Iterator | range over matching messages |
| query | A metadata object representing a query. |
| metadata_only | If this is true, only retrieve the metadata (returned message objects will just be default constructed) |
Definition at line 169 of file message_collection_impl.hpp.
| unsigned mongo_ros::MessageCollection< M >::removeMessages | ( | const mongo::Query & | query | ) |
Remove messages matching query.
Definition at line 215 of file message_collection_impl.hpp.
boost::shared_ptr<mongo::DBClientConnection> mongo_ros::MessageCollection< M >::conn_ [private] |
Definition at line 129 of file message_collection.h.
boost::shared_ptr<mongo::GridFS> mongo_ros::MessageCollection< M >::gfs_ [private] |
Definition at line 130 of file message_collection.h.
ros::Publisher mongo_ros::MessageCollection< M >::insertion_pub_ [private] |
Definition at line 133 of file message_collection.h.
bool mongo_ros::MessageCollection< M >::md5sum_matches_ [private] |
Definition at line 131 of file message_collection.h.
ros::NodeHandle mongo_ros::MessageCollection< M >::nh_ [private] |
Definition at line 132 of file message_collection.h.
const std::string mongo_ros::MessageCollection< M >::ns_ [private] |
Definition at line 128 of file message_collection.h.