metadata.h
Go to the documentation of this file.
00001 /*
00002  * Copyright (c) 2008, Willow Garage, Inc.
00003  * All rights reserved.
00004  *
00005  * Redistribution and use in source and binary forms, with or without
00006  * modification, are permitted provided that the following conditions are met:
00007  *
00008  *     * Redistributions of source code must retain the above copyright
00009  *       notice, this list of conditions and the following disclaimer.
00010  *     * Redistributions in binary form must reproduce the above copyright
00011  *       notice, this list of conditions and the following disclaimer in the
00012  *       documentation and/or other materials provided with the distribution.
00013  *     * Neither the name of the Willow Garage, Inc. nor the names of its
00014  *       contributors may be used to endorse or promote products derived from
00015  *       this software without specific prior written permission.
00016  *
00017  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00018  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00019  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
00020  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
00021  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
00022  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
00023  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
00024  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
00025  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
00026  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00027  * POSSIBILITY OF SUCH DAMAGE.
00028  *
00029  */
00030 
00039 #ifndef MONGO_ROS_METADATA_H
00040 #define MONGO_ROS_METADATA_H
00041 
00042 // We have to include this top-level include here because
00043 // the mongo c++ library is not robust to reincludes
00044 #include <mongo/client/gridfs.h>
00045 #include <ros/ros.h>
00046 
00047 
00048 namespace mongo_ros
00049 {
00050 
00051 using mongo::LT;
00052 using mongo::LTE;
00053 using mongo::GT;
00054 using mongo::GTE;
00055 using mongo::BSONObj;
00056 using mongo::BSONObjBuilder;
00057 
00062 class WrappedBSON : public BSONObj
00063 {
00064 public:
00065   WrappedBSON () :
00066     BSONObj(), builder_(new BSONObjBuilder())
00067   {}
00068 
00069   WrappedBSON (const WrappedBSON& other) :
00070     BSONObj(), builder_(other.builder_)
00071   {
00072     update();
00073   }
00074 
00075   WrappedBSON (const std::string& json) :
00076     BSONObj(), builder_(new BSONObjBuilder())
00077   {
00078     builder_->appendElements(mongo::fromjson(json.c_str()));
00079     update();
00080   }
00081 
00082 protected:
00083 
00084   boost::shared_ptr<BSONObjBuilder> builder_;
00085 
00086   void update ()
00087   {
00088     BSONObj::operator=(builder_->asTempObj());
00089   }
00090 };
00091 
00092 
00102 class Query : public WrappedBSON
00103 {
00104 public:
00105   Query () : WrappedBSON ()
00106   {}
00107 
00108   Query (const Query& other) :
00109     WrappedBSON(other)
00110   {}
00111 
00112   template <class T>
00113   Query (const std::string& name, const T& val) :
00114     WrappedBSON ()
00115   {
00116     append(name, val);
00117   }
00118 
00119   template <class T, class S>
00120   Query (const std::string& name, const S& rel, const T& val) :
00121     WrappedBSON ()
00122   {
00123     append(name, rel, val);
00124   }
00125 
00126   template <class T>
00127   Query& append (const std::string& name,
00128                  const T& val)
00129   {
00130     *builder_ << name << val;
00131     update();
00132     return *this;
00133   }
00134 
00135   template <class T, class S>
00136   Query& append (const std::string& name,
00137                        const T& rel,
00138                        const S& val)
00139   {
00140     *builder_ << name << rel << val;
00141     update();
00142     return *this;
00143   }
00144 
00145 
00146 };
00147 
00148 
00149 
00160 class Metadata : public WrappedBSON
00161 {
00162 public:
00163   Metadata() :
00164     WrappedBSON ()
00165   {
00166     initialize();
00167   }
00168 
00169   Metadata(const std::string& json) :
00170     WrappedBSON (json)
00171   {
00172     update();
00173   }
00174 
00175   Metadata (const Metadata& other) :
00176     WrappedBSON(other)
00177   {
00178     update();
00179   }
00180 
00181   template <class T>
00182   Metadata (const std::string& name, const T& val) :
00183     WrappedBSON ()
00184   {
00185     initialize();
00186     append(name, val);
00187   }
00188 
00189   template <class T, class T2>
00190   Metadata (const std::string& n, const T& v,
00191             const std::string& n2, const T2& v2) :
00192     WrappedBSON ()
00193   {
00194     initialize();
00195     append(n, v);
00196     append(n2, v2);
00197   }
00198 
00199   template <class T1, class T2, class T3>
00200   Metadata (const std::string& n1, const T1& v1,
00201             const std::string& n2, const T2& v2,
00202             const std::string& n3, const T3& v3) :
00203     WrappedBSON ()
00204   {
00205     initialize();
00206     append(n1, v1);
00207     append(n2, v2);
00208     append(n3, v3);
00209   }
00210 
00211   template <class T1, class T2, class T3>
00212   Metadata (const std::string& n1, const T1& v1,
00213             const std::string& n2, const T2& v2,
00214             const std::string& n3, const T3& v3,
00215             const std::string& n4, const T3& v4) :
00216     WrappedBSON ()
00217   {
00218     initialize();
00219     append(n1, v1);
00220     append(n2, v2);
00221     append(n3, v3);
00222     append(n4, v4);
00223   }
00224 
00225   template <class T1, class T2, class T3>
00226   Metadata (const std::string& n1, const T1& v1,
00227             const std::string& n2, const T2& v2,
00228             const std::string& n3, const T3& v3,
00229             const std::string& n4, const T3& v4,
00230             const std::string& n5, const T3& v5) :
00231     WrappedBSON ()
00232   {
00233     initialize();
00234     append(n1, v1);
00235     append(n2, v2);
00236     append(n3, v3);
00237     append(n4, v4);
00238     append(n5, v5);
00239   }
00240 
00241   template <class T>
00242   Metadata& append (const std::string& name,
00243                  const T& val)
00244   {
00245     builder_->append(name, val);
00246     update();
00247     return *this;
00248   }
00249 
00250 private:
00251 
00252   void initialize()
00253   {
00254     builder_->genOID();
00255     builder_->append("creation_time", ros::Time::now().toSec());
00256     update();
00257   }
00258 };
00259 
00260 
00261 
00262 
00263 } // namespace
00264 
00265 #endif // include guard
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Friends


mongo_ros
Author(s): Bhaskara Marthi
autogenerated on Mon Sep 2 2013 11:11:08