database_mesh.h
Go to the documentation of this file.
00001 /*********************************************************************
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Copyright (c) 2009, Willow Garage, Inc.
00005  *  All rights reserved.
00006  *
00007  *  Redistribution and use in source and binary forms, with or without
00008  *  modification, are permitted provided that the following conditions
00009  *  are met:
00010  *
00011  *   * Redistributions of source code must retain the above copyright
00012  *     notice, this list of conditions and the following disclaimer.
00013  *   * Redistributions in binary form must reproduce the above
00014  *     copyright notice, this list of conditions and the following
00015  *     disclaimer in the documentation and/or other materials provided
00016  *     with the distribution.
00017  *   * Neither the name of the Willow Garage nor the names of its
00018  *     contributors may be used to endorse or promote products derived
00019  *     from this software without specific prior written permission.
00020  *
00021  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032  *  POSSIBILITY OF SUCH DAMAGE.
00033  *********************************************************************/
00034 
00035 // Author(s): Matei Ciocarlie
00036 
00037 #ifndef _DATABASE_MESH_H_
00038 #define _DATABASE_MESH_H_
00039 
00040 #include <database_interface/db_class.h>
00041 
00042 namespace database_interface {
00043 
00045 template <>
00046 class DBField< std::vector<int> > : public DBFieldData< std::vector<int> >
00047 {
00048  public:
00049   DBField(Type type, DBClass *owner, std::string name, std::string table_name, bool write_permission) : 
00050     DBFieldData< std::vector<int> >(type, owner, name, table_name, write_permission) {}
00051 
00052  DBField(DBClass *owner, const DBField< std::vector<int> > *other) : DBFieldData< std::vector<int> >(owner, other) 
00053       {
00054         this->copy(other);
00055       }
00056   
00057   virtual bool fromBinary(const char* binary, size_t length) 
00058   {
00059     //recall that the size given here is in bytes
00060     if (!length)
00061     {
00062       data_.clear();
00063       return true;
00064     }
00065     //check if this is indeed a multiple of a number of integers
00066     if ( length % sizeof(int) != 0)
00067     {
00068       std::cerr << "Binary conversion of " << length << " bytes to vector<int> failed\n";
00069       return false;
00070     }
00071     data_.resize(length / sizeof(int));
00072     memcpy(&(data_[0]), binary, length);
00073     return true;
00074   }
00075 
00076   virtual bool toBinary(const char* &binary, size_t &length) const 
00077   {
00078     length = sizeof(int) * data_.size();
00079     if (!data_.empty())
00080     {
00081       binary = reinterpret_cast<const char*>(&(data_[0]));
00082     }
00083     return true;
00084   }
00085 };
00086 
00088 template <>
00089 class DBField< std::vector<double> > : public DBFieldData< std::vector<double> >
00090 {
00091  public:
00092   DBField(Type type, DBClass *owner, std::string name, std::string table_name, bool write_permission) : 
00093     DBFieldData< std::vector<double> >(type, owner, name, table_name, write_permission) {}
00094 
00095  DBField(DBClass *owner, const DBField< std::vector<double> > *other) : 
00096     DBFieldData< std::vector<double> >(owner, other) 
00097       {
00098         this->copy(other);
00099       }
00100   
00101   virtual bool fromBinary(const char* binary, size_t length) 
00102   {
00103     //recall that the size given here is in bytes
00104     if (!length)
00105     {
00106       data_.clear();
00107       return true;
00108     }
00109     //check if this is indeed a multiple of a number of doubles
00110     if ( length % sizeof(double) != 0)
00111     {
00112       std::cerr << "Binary conversion of " << length << " bytes to vector<double> failed\n";
00113       return false;
00114     }
00115     data_.resize(length / sizeof(double));
00116     memcpy(&(data_[0]), binary, length);
00117     return true;
00118   }
00119 
00120   virtual bool toBinary(const char* &binary, size_t &length) const 
00121   {
00122     length = sizeof(double) * data_.size();
00123     if (!data_.empty())
00124     {
00125       binary = reinterpret_cast<const char*>(&(data_[0]));
00126     }
00127     return true;
00128   }
00129 };
00130 
00131 }
00132 
00133 namespace household_objects_database {
00134 
00135 class DatabaseMesh : public database_interface::DBClass
00136 {
00137  private:
00138 
00139  public:
00141   database_interface::DBField<int> id_;
00143   database_interface::DBField< std::vector<double> > vertices_;
00145   database_interface::DBField< std::vector<int> > triangles_;
00146 
00147  DatabaseMesh() :
00148   id_(database_interface::DBFieldBase::TEXT, this, "original_model_id", "mesh", true),
00149   vertices_(database_interface::DBFieldBase::BINARY, this, "mesh_vertex_list", "mesh", true),
00150   triangles_(database_interface::DBFieldBase::BINARY, this, "mesh_triangle_list", "mesh", true)
00151     {
00152       primary_key_field_ = &id_;
00153       fields_.push_back(&vertices_);
00154       fields_.push_back(&triangles_);
00155 
00156       setAllFieldsWriteToDatabase(false);
00157       setAllFieldsReadFromDatabase(false);
00158       id_.setWriteToDatabase(true);
00159       id_.setReadFromDatabase(true);
00160     }
00161   ~DatabaseMesh(){}
00162 };
00163 
00164 } //namespace
00165 
00166 #endif


household_objects_database
Author(s): Matei Ciocarlie, except for source files individually marked otherwise
autogenerated on Thu Jan 2 2014 11:40:12