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 WAREHOUSE_ROS_MESSAGE_COLLECTION_H
00040 #define WAREHOUSE_ROS_MESSAGE_COLLECTION_H
00041
00042 #include <warehouse_ros/query_results.h>
00043
00044 namespace warehouse_ros
00045 {
00046
00047 class MessageCollectionHelper
00048 {
00049 public:
00050 virtual bool initialize(const std::string& datatype, const std::string& md5) = 0;
00051 virtual void insert(char* msg, size_t msg_size, Metadata::ConstPtr metadata) = 0;
00052 virtual ResultIteratorHelper::Ptr query(Query::ConstPtr query, const std::string& sort_by = "",
00053 bool ascending = true) const = 0;
00054 virtual unsigned removeMessages(Query::ConstPtr query) = 0;
00055 virtual void modifyMetadata(Query::ConstPtr q, Metadata::ConstPtr m) = 0;
00056 virtual unsigned count() = 0;
00057 virtual Query::Ptr createQuery() const = 0;
00058 virtual Metadata::Ptr createMetadata() const = 0;
00059 virtual std::string collectionName() const = 0;
00060
00061 typedef boost::shared_ptr<MessageCollectionHelper> Ptr;
00062 };
00063
00067 template<class M>
00068 class MessageCollection
00069 {
00070 public:
00073 MessageCollection(MessageCollectionHelper::Ptr collection);
00074
00076 MessageCollection(const MessageCollection& rhs);
00077
00079 ~MessageCollection();
00080
00081 MessageCollection& operator=(const MessageCollection& other);
00082
00088 void insert(const M& msg, Metadata::Ptr metadata);
00089
00094 typename QueryResults<M>::range_t
00095 query(Query::ConstPtr query, bool metadata_only = false, const std::string& sort_by = "",
00096 bool ascending = true) const;
00097
00100 std::vector<typename MessageWithMetadata<M>::ConstPtr>
00101 queryList(Query::ConstPtr query, bool metadata_only = false, const std::string& sort_by = "",
00102 bool ascending = true) const;
00103
00107 typename MessageWithMetadata<M>::ConstPtr
00108 findOne(Query::ConstPtr query, bool metadata_only = false) const;
00109
00111 unsigned removeMessages(Query::ConstPtr query);
00112
00117 void modifyMetadata(Query::ConstPtr q, Metadata::ConstPtr m);
00118
00120 unsigned count();
00121
00124 bool md5SumMatches() const;
00125
00126 Query::Ptr createQuery() const;
00127
00128 Metadata::Ptr createMetadata() const;
00129
00130 typedef boost::shared_ptr<MessageCollection<M> > Ptr;
00131 typedef M message_type;
00132
00133 private:
00134 MessageCollectionHelper::Ptr collection_;
00135 bool md5sum_matches_;
00136 };
00137
00138 }
00139
00140 #include "impl/message_collection_impl.hpp"
00141
00142 #endif // include guard