Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00039 #ifndef MONGO_ROS_MESSAGE_COLLECTION_H
00040 #define MONGO_ROS_MESSAGE_COLLECTION_H
00041
00042 #include <mongo_ros/query_results.h>
00043 #include <ros/ros.h>
00044
00045 namespace mongo_ros
00046 {
00047
00051 template <class M>
00052 class MessageCollection
00053 {
00054 public:
00055
00064 MessageCollection (const std::string& db_name,
00065 const std::string& collection_name,
00066 const std::string& db_host="",
00067 unsigned db_port=0,
00068 float timeout=300.0);
00069
00078 void insert (const M& msg, const Metadata& metadata = Metadata());
00079
00084 typename QueryResults<M>::range_t
00085 queryResults (const mongo::Query& query, bool metadata_only = false,
00086 const std::string& sort_by = "", bool ascending=true) const;
00087
00090 std::vector<typename MessageWithMetadata<M>::ConstPtr >
00091 pullAllResults (const mongo::Query& query, bool metadata_only = false,
00092 const std::string& sort_by = "", bool ascending=true) const;
00093
00094
00098 typename MessageWithMetadata<M>::ConstPtr
00099 findOne (const Query& query, bool metadata_only = false) const;
00100
00102 unsigned removeMessages (const mongo::Query& query);
00103
00106 MessageCollection& ensureIndex (const std::string& field);
00107
00112 void modifyMetadata (const Query& q, const Metadata& m);
00113
00115 unsigned count ();
00116
00117 private:
00118
00119
00120 void initialize (const std::string& db, const std::string& coll,
00121 const std::string& host, unsigned port,
00122 float timeout);
00123
00124 const std::string ns_;
00125 boost::shared_ptr<mongo::DBClientConnection> conn_;
00126 boost::shared_ptr<mongo::GridFS> gfs_;
00127 ros::NodeHandle nh_;
00128 ros::Publisher insertion_pub_;
00129 };
00130
00131
00132 }
00133
00134 #include "../../src/message_collection_impl.h"
00135
00136 #endif // include guard