Public Member Functions | Private Member Functions | Private Attributes
mongo_ros::MessageCollection< M > Class Template Reference

#include <message_collection.h>

List of all members.

Public Member Functions

unsigned count ()
 Count messages in collection.
MessageCollectionensureIndex (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_

Detailed Description

template<class M>
class mongo_ros::MessageCollection< M >

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.


Constructor & Destructor Documentation

template<class M>
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.

Parameters:
db_hostIf provided, will be used instead of looking up the warehouse_host ros parameter.
db_portIf provided, will be used instead of looking up the warehouse_port ros parameter.
timeoutThrow a DbConnectException if can't connect within this many seconds

Definition at line 58 of file message_collection_impl.hpp.


Member Function Documentation

template<class M >
unsigned mongo_ros::MessageCollection< M >::count ( )

Count messages in collection.

Definition at line 256 of file message_collection_impl.hpp.

template<class M>
MessageCollection< M > & mongo_ros::MessageCollection< M >::ensureIndex ( const std::string &  field)
Postcondition:
Ensure that there's an index on the given field. Note that index on _id and creation_time are always created.

Definition at line 123 of file message_collection_impl.hpp.

template<class M >
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.

Exceptions:
NoMatchingMessageException

Definition at line 205 of file message_collection_impl.hpp.

template<class M>
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.

template<class M>
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.

Exceptions:
mongo::DBExceptionif unable to insert
Parameters:
metadataMetadata 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.

template<class M >
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.

template<class M >
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.

template<class M>
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.

template<class M>
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
Return values:
Iteratorrange over matching messages
Parameters:
queryA metadata object representing a query.
metadata_onlyIf 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.

template<class M >
unsigned mongo_ros::MessageCollection< M >::removeMessages ( const mongo::Query &  query)

Remove messages matching query.

Definition at line 215 of file message_collection_impl.hpp.


Member Data Documentation

template<class M>
boost::shared_ptr<mongo::DBClientConnection> mongo_ros::MessageCollection< M >::conn_ [private]

Definition at line 129 of file message_collection.h.

template<class M>
boost::shared_ptr<mongo::GridFS> mongo_ros::MessageCollection< M >::gfs_ [private]

Definition at line 130 of file message_collection.h.

template<class M>
ros::Publisher mongo_ros::MessageCollection< M >::insertion_pub_ [private]

Definition at line 133 of file message_collection.h.

template<class M>
bool mongo_ros::MessageCollection< M >::md5sum_matches_ [private]

Definition at line 131 of file message_collection.h.

template<class M>
ros::NodeHandle mongo_ros::MessageCollection< M >::nh_ [private]

Definition at line 132 of file message_collection.h.

template<class M>
const std::string mongo_ros::MessageCollection< M >::ns_ [private]

Definition at line 128 of file message_collection.h.


The documentation for this class was generated from the following files:


warehouse_ros
Author(s): Bhaskara Marthi
autogenerated on Wed Aug 26 2015 16:44:56