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 #ifdef __APPLE__
00045 #include <malloc/malloc.h>
00046 #else
00047 #include <malloc.h>
00048 #endif
00049 #include <mongo_ros/config.h>
00050 #include <ros/ros.h>
00051 
00052 
00053 namespace mongo_ros
00054 {
00055 
00056 using mongo::LT;
00057 using mongo::LTE;
00058 using mongo::GT;
00059 using mongo::GTE;
00060 using mongo::BSONObj;
00061 using mongo::BSONObjBuilder;
00062 
00067 class WrappedBSON : public BSONObj
00068 {
00069 public:
00070   WrappedBSON () :
00071     BSONObj(), builder_(new BSONObjBuilder())
00072   {}
00073 
00074   WrappedBSON (const WrappedBSON& other) :
00075     BSONObj(), builder_(other.builder_)
00076   {
00077     update();
00078   }
00079 
00080   WrappedBSON (const std::string& json) :
00081     BSONObj(), builder_(new BSONObjBuilder())
00082   {
00083     builder_->appendElements(mongo::fromjson(json.c_str()));
00084     update();
00085   }
00086 
00087 protected:
00088 
00089   boost::shared_ptr<BSONObjBuilder> builder_;
00090 
00091   void update ()
00092   {
00093     BSONObj::operator=(builder_->asTempObj());
00094   }
00095 };
00096 
00097 
00107 class Query : public WrappedBSON
00108 {
00109 public:
00110   Query () : WrappedBSON ()
00111   {}
00112 
00113   Query (const Query& other) :
00114     WrappedBSON(other)
00115   {}
00116 
00117   template <class T>
00118   Query (const std::string& name, const T& val) :
00119     WrappedBSON ()
00120   {
00121     append(name, val);
00122   }
00123 
00124   template <class T, class S>
00125   Query (const std::string& name, const S& rel, const T& val) :
00126     WrappedBSON ()
00127   {
00128     append(name, rel, val);
00129   }
00130 
00131   template <class T>
00132   Query& append (const std::string& name,
00133                  const T& val)
00134   {
00135     *builder_ << name << val;
00136     update();
00137     return *this;
00138   }
00139 
00140   template <class T, class S>
00141   Query& append (const std::string& name,
00142                        const T& rel,
00143                        const S& val)
00144   {
00145     *builder_ << name << rel << val;
00146     update();
00147     return *this;
00148   }
00149 
00150 
00151 };
00152 
00153 
00154 
00165 class Metadata : public WrappedBSON
00166 {
00167 public:
00168   Metadata() :
00169     WrappedBSON ()
00170   {
00171     initialize();
00172   }
00173 
00174   Metadata(const std::string& json) :
00175     WrappedBSON (json)
00176   {
00177     update();
00178   }
00179 
00180   Metadata (const Metadata& other) :
00181     WrappedBSON(other)
00182   {
00183     update();
00184   }
00185 
00186   template <class T>
00187   Metadata (const std::string& name, const T& val) :
00188     WrappedBSON ()
00189   {
00190     initialize();
00191     append(name, val);
00192   }
00193 
00194   template <class T, class T2>
00195   Metadata (const std::string& n, const T& v,
00196             const std::string& n2, const T2& v2) :
00197     WrappedBSON ()
00198   {
00199     initialize();
00200     append(n, v);
00201     append(n2, v2);
00202   }
00203 
00204   template <class T1, class T2, class T3>
00205   Metadata (const std::string& n1, const T1& v1,
00206             const std::string& n2, const T2& v2,
00207             const std::string& n3, const T3& v3) :
00208     WrappedBSON ()
00209   {
00210     initialize();
00211     append(n1, v1);
00212     append(n2, v2);
00213     append(n3, v3);
00214   }
00215 
00216   template <class T1, class T2, class T3>
00217   Metadata (const std::string& n1, const T1& v1,
00218             const std::string& n2, const T2& v2,
00219             const std::string& n3, const T3& v3,
00220             const std::string& n4, const T3& v4) :
00221     WrappedBSON ()
00222   {
00223     initialize();
00224     append(n1, v1);
00225     append(n2, v2);
00226     append(n3, v3);
00227     append(n4, v4);
00228   }
00229 
00230   template <class T1, class T2, class T3>
00231   Metadata (const std::string& n1, const T1& v1,
00232             const std::string& n2, const T2& v2,
00233             const std::string& n3, const T3& v3,
00234             const std::string& n4, const T3& v4,
00235             const std::string& n5, const T3& v5) :
00236     WrappedBSON ()
00237   {
00238     initialize();
00239     append(n1, v1);
00240     append(n2, v2);
00241     append(n3, v3);
00242     append(n4, v4);
00243     append(n5, v5);
00244   }
00245 
00246   template <class T>
00247   Metadata& append (const std::string& name,
00248                  const T& val)
00249   {
00250     builder_->append(name, val);
00251     update();
00252     return *this;
00253   }
00254 
00255 private:
00256 
00257   void initialize()
00258   {
00259     builder_->genOID();
00260     builder_->append("creation_time", ros::Time::now().toSec());
00261     update();
00262   }
00263 };
00264 
00265 
00266 
00267 
00268 } // namespace
00269 
00270 #endif // include guard


warehouse_ros
Author(s): Bhaskara Marthi
autogenerated on Mon Oct 6 2014 08:51:55