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_COLLECTION_H
00040 #define WAREHOUSE_COLLECTION_H
00041
00042 #include <warehouse/UpdateNotification.h>
00043 #include <warehouse/result_iterator.h>
00044 #include <ros/ros.h>
00045 #include <ros/callback_queue.h>
00046 #include <boost/thread.hpp>
00047 #include <boost/shared_ptr.hpp>
00048 #include <boost/utility.hpp>
00049 #include <boost/scoped_ptr.hpp>
00050 #include <string>
00051
00052 namespace warehouse
00053 {
00054
00058 template <class M>
00059 class Collection
00060 {
00061 public:
00062
00064 Collection (const std::string& topic, const std::string& db,
00065 const std::string& collection, const ros::NodeHandle& nh);
00066
00069 Collection (const Collection& pub);
00070
00073 Collection ();
00074
00076 Collection<M>& operator= (const Collection<M>& c);
00077
00078
00084 std::string publish (const M& msg, const std::string& metadata = std::string());
00085
00099 typename QueryResults<M>::range_t
00100 queryResults (const std::vector<Condition>& conditions,
00101 bool metadata_only = false,
00102 const OrderingCriterion& order = OrderingCriterion()) const;
00103
00106 std::vector<typename MessageWithMetadata<M>::ConstPtr >
00107 pullAllResults (const std::vector<Condition>& conditions,
00108 bool metadata_only = false,
00109 const OrderingCriterion& order = OrderingCriterion()) const;
00110
00114 unsigned removeMessages (const std::vector<Condition>& conditions);
00115
00117 std::string collectionName () const;
00118
00119 private:
00120
00122 void addMetadata (const std::string& id, const std::string& metadata);
00123
00124
00125
00126 struct Impl : public boost::noncopyable
00127 {
00128 Impl (const string& topic, const string& db,
00129 const string& coll, const ros::NodeHandle& nh);
00130
00131 void connectCallback (const ros::SingleSubscriberPublisher& pub);
00132 void notificationCallback (const UpdateNotification& update);
00133 void setupConnections ();
00134
00135
00136 boost::mutex mutex_;
00137 boost::condition_variable cond_;
00138 ros::NodeHandle nh_;
00139 boost::scoped_ptr<ros::CallbackQueue> cb_queue_;
00140 ros::AsyncSpinner spinner_;
00141
00142 ros::Publisher pub_;
00143 ros::Subscriber sub_;
00144
00145
00146 mutable ros::ServiceClient query_client_, pull_client_, metadata_client_,
00147 remove_messages_client_;
00148
00149 std::string topic_, db_, collection_;
00150 bool initialized_;
00151
00152 std::string node_name_;
00153
00154
00155 bool warehouse_sub_connection_received_;
00156 boost::optional<std::string> last_id_;
00157 };
00158
00159 typedef boost::shared_ptr<Impl> ImplPtr;
00160 ImplPtr impl_;
00161 };
00162
00163
00164
00165 }
00166
00167
00168 #include "../../src/collection_impl.h"
00169
00170 #endif // include guard