outofcore_node_data.cpp
Go to the documentation of this file.
00001 /*
00002  * Software License Agreement (BSD License)
00003  *
00004  *  Point Cloud Library (PCL) - www.pointclouds.org
00005  *  Copyright (c) 2010-2012, Willow Garage, Inc.
00006  *
00007  *  All rights reserved.
00008  *
00009  *  Redistribution and use in source and binary forms, with or without
00010  *  modification, are permitted provided that the following conditions
00011  *  are met:
00012  *
00013  *   * Redistributions of source code must retain the above copyright
00014  *     notice, this list of conditions and the following disclaimer.
00015  *   * Redistributions in binary form must reproduce the above
00016  *     copyright notice, this list of conditions and the following
00017  *     disclaimer in the documentation and/or other materials provided
00018  *     with the distribution.
00019  *   * Neither the name of Willow Garage, Inc. nor the names of its
00020  *     contributors may be used to endorse or promote products derived
00021  *     from this software without specific prior written permission.
00022  *
00023  *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00024  *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00025  *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00026  *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00027  *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00028  *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00029  *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00030  *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00031  *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00032  *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00033  *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00034  *  POSSIBILITY OF SUCH DAMAGE.
00035  *
00036  *  $Id$
00037  *
00038  */
00039 
00040 #include <pcl/outofcore/outofcore_node_data.h>
00041 
00042 #include <pcl/console/print.h>
00043 
00044 #include <pcl/pcl_macros.h>
00045 #include <pcl/common/io.h>
00046 
00047 #include <iostream>
00048 #include <fstream>
00049 #include <sstream>
00050 
00051 namespace pcl
00052 {
00053   namespace outofcore
00054   {
00055     
00056     OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata () 
00057       : min_bb_ (),
00058         max_bb_ (),
00059         binary_point_filename_ (),
00060         midpoint_xyz_ (),
00061         directory_ (),
00062         metadata_filename_ (),
00063         outofcore_version_ ()
00064     {
00065     }
00066 
00068 
00069     OutofcoreOctreeNodeMetadata::~OutofcoreOctreeNodeMetadata ()
00070     {
00071     }
00072 
00074 
00075     OutofcoreOctreeNodeMetadata::OutofcoreOctreeNodeMetadata (const OutofcoreOctreeNodeMetadata& orig)
00076     {
00077       this->min_bb_ = orig.min_bb_;
00078       this->max_bb_ = orig.max_bb_;
00079       this->binary_point_filename_ = orig.binary_point_filename_;
00080       this->midpoint_xyz_ = orig.midpoint_xyz_;
00081       this->directory_ = orig.directory_;
00082       this->metadata_filename_ = orig.metadata_filename_;
00083       this->outofcore_version_ = orig.outofcore_version_;
00084 
00085       this->updateVoxelCenter ();
00086     }
00087     
00089 
00090     const Eigen::Vector3d&
00091     OutofcoreOctreeNodeMetadata::getBoundingBoxMin () const
00092     {
00093       return (min_bb_);
00094     }
00095 
00097 
00098     void 
00099     OutofcoreOctreeNodeMetadata::setBoundingBoxMin (const Eigen::Vector3d& min_bb)
00100     {
00101       min_bb_ = min_bb;
00102       this->updateVoxelCenter ();
00103     }
00104 
00106 
00107     const Eigen::Vector3d&
00108     OutofcoreOctreeNodeMetadata::getBoundingBoxMax () const
00109     {
00110       return (max_bb_);
00111     }
00112 
00114 
00115     void 
00116     OutofcoreOctreeNodeMetadata::setBoundingBoxMax (const Eigen::Vector3d& max_bb)
00117     {
00118       max_bb_ = max_bb;
00119       this->updateVoxelCenter ();
00120     }
00121     
00123 
00124     void 
00125     OutofcoreOctreeNodeMetadata::getBoundingBox (Eigen::Vector3d &min_bb, Eigen::Vector3d &max_bb) const
00126     {
00127       min_bb = min_bb_;
00128       max_bb = max_bb_;
00129     }
00130 
00132 
00133     void 
00134     OutofcoreOctreeNodeMetadata::setBoundingBox (const Eigen::Vector3d& min_bb, const Eigen::Vector3d& max_bb)
00135     {
00136       min_bb_ = min_bb;
00137       max_bb_ = max_bb;
00138       this->updateVoxelCenter ();
00139     }
00140     
00142 
00143     const boost::filesystem::path&
00144     OutofcoreOctreeNodeMetadata::getDirectoryPathname () const
00145     {
00146       return (directory_);
00147     }
00148 
00150     void
00151     OutofcoreOctreeNodeMetadata::setDirectoryPathname (const boost::filesystem::path& directory_pathname)
00152     {
00153       directory_ = directory_pathname;
00154     }
00155 
00157 
00158     const boost::filesystem::path&
00159     OutofcoreOctreeNodeMetadata::getPCDFilename () const
00160     {
00161       return (binary_point_filename_);
00162     }
00163     
00165 
00166     void 
00167     OutofcoreOctreeNodeMetadata::setPCDFilename (const boost::filesystem::path& point_filename)
00168     {
00169       binary_point_filename_ = point_filename;
00170     }
00171     
00172 
00174 
00175     int 
00176     OutofcoreOctreeNodeMetadata::getOutofcoreVersion () const
00177     {
00178       return (outofcore_version_);
00179     }
00180     
00182 
00183     void 
00184     OutofcoreOctreeNodeMetadata::setOutofcoreVersion (const int version)
00185     {
00186       outofcore_version_ = version;
00187     }
00188 
00190 
00191     const boost::filesystem::path&
00192     OutofcoreOctreeNodeMetadata::getMetadataFilename () const
00193     {
00194       return (metadata_filename_);
00195     }
00196     
00198 
00199     void 
00200     OutofcoreOctreeNodeMetadata::setMetadataFilename (const boost::filesystem::path& path_to_metadata)
00201     {
00202       directory_ = path_to_metadata.parent_path ();
00203       metadata_filename_ = path_to_metadata;
00204     }
00205 
00207 
00208     const Eigen::Vector3d&
00209     OutofcoreOctreeNodeMetadata::getVoxelCenter () const
00210     {
00211       return (midpoint_xyz_);
00212     }
00213 
00215 
00216     void 
00217     OutofcoreOctreeNodeMetadata::serializeMetadataToDisk ()
00218     {
00219       boost::shared_ptr<cJSON> idx (cJSON_CreateObject (), cJSON_Delete);
00220 
00221       cJSON* cjson_outofcore_version = cJSON_CreateNumber (outofcore_version_);
00222   
00223       double min_array[3];
00224       double max_array[3];
00225 
00226       for(int i=0; i<3; i++)
00227       {
00228         min_array[i] = min_bb_[i];
00229         max_array[i] = max_bb_[i];
00230       }
00231       
00232       cJSON* cjson_bb_min = cJSON_CreateDoubleArray (min_array, 3);
00233       cJSON* cjson_bb_max = cJSON_CreateDoubleArray (max_array, 3);
00234 
00235       std::string binary_point_filename_string = binary_point_filename_.filename ().generic_string ();
00236       cJSON* cjson_bin_point_filename = cJSON_CreateString (binary_point_filename_string.c_str ());
00237 
00238       cJSON_AddItemToObject (idx.get (), "version", cjson_outofcore_version);
00239       cJSON_AddItemToObject (idx.get (), "bb_min", cjson_bb_min);
00240       cJSON_AddItemToObject (idx.get (), "bb_max", cjson_bb_max);
00241       cJSON_AddItemToObject (idx.get (), "bin", cjson_bin_point_filename);
00242 
00243       char* idx_txt = cJSON_Print (idx.get ());
00244 
00245       std::ofstream f (metadata_filename_.string ().c_str (), std::ios::out | std::ios::trunc);
00246       f << idx_txt;
00247       f.close ();
00248 
00249       free (idx_txt);
00250     }
00251 
00253 
00254     int 
00255     OutofcoreOctreeNodeMetadata::loadMetadataFromDisk ()
00256     {
00257       if(directory_ != metadata_filename_.parent_path ())
00258       {
00259         PCL_ERROR ("directory_ is not set correctly\n");
00260       }
00261       
00262       //if the file to load doesn't exist, return failure
00263       if (!boost::filesystem::exists (metadata_filename_))
00264       {
00265         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata] Can not find index metadata at %s.\n", metadata_filename_.c_str ());
00266         return (0);
00267       }
00268       else if(boost::filesystem::is_directory (metadata_filename_))
00269       {
00270         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata] Got a directory, but no oct_idx metadata?\n");
00271         return (0);
00272       }
00273 
00274       //load CJSON
00275       std::vector<char> idx_input;
00276       boost::uintmax_t len = boost::filesystem::file_size (metadata_filename_);
00277       idx_input.resize (len + 1);
00278       
00279       std::ifstream f (metadata_filename_.string ().c_str (), std::ios::in);
00280       f.read (&(idx_input.front ()), len);
00281       idx_input.back () = '\0';
00282       
00283       //Parse
00284       boost::shared_ptr<cJSON> idx (cJSON_Parse (&(idx_input.front ())), cJSON_Delete);
00285 
00286       cJSON* cjson_outofcore_version = cJSON_GetObjectItem (idx.get (), "version");
00287       cJSON* cjson_bb_min = cJSON_GetObjectItem (idx.get (), "bb_min");
00288       cJSON* cjson_bb_max = cJSON_GetObjectItem (idx.get (), "bb_max");
00289       cJSON* cjson_bin_point_filename = cJSON_GetObjectItem (idx.get (), "bin");
00290 
00291       bool parse_failure = false;
00292       
00293       //Sanitize
00294       if (!cjson_outofcore_version)
00295       {
00296         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata::%s] Failed to parse \"version\" field of node metadata %s\n", __FUNCTION__, metadata_filename_.c_str ());
00297         parse_failure = true;
00298       }
00299       if (!cjson_bb_min)
00300       {
00301         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata::%s] Failed to parse \"bb_min\" field of node metadata %s\n", __FUNCTION__, metadata_filename_.c_str ());        
00302         parse_failure = true;
00303       }
00304       if (!cjson_bb_max)
00305       {
00306         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata::%s] Failed to parse \"bb_max\" field of node metadata %s\n", __FUNCTION__, metadata_filename_.c_str ());
00307         parse_failure = true;
00308       }
00309       if (!cjson_bin_point_filename)
00310       {
00311         PCL_ERROR ("[pcl::outofcore::OutofcoreOctreeNodeMetadata::%s] Failed to parse \"bin\" field of node metadata %s\n", __FUNCTION__, metadata_filename_.c_str ());
00312         parse_failure = true;
00313       }
00314       
00315       if (parse_failure)
00316       {
00317         PCL_THROW_EXCEPTION (PCLException, "[pcl::outofcore::OutofcoreOctreeNodeMetadata::%s] Outofcore node metadata parse error\n");
00318       }
00319       
00320       for (int i = 0; i < 3; i++)
00321       {
00322         min_bb_[i] = cJSON_GetArrayItem (cjson_bb_min, i)->valuedouble;
00323         max_bb_[i] = cJSON_GetArrayItem (cjson_bb_max, i)->valuedouble;
00324       }
00325       outofcore_version_ = cjson_outofcore_version->valueint;
00326 
00327       binary_point_filename_= directory_ / cjson_bin_point_filename->valuestring;
00328       midpoint_xyz_ = (max_bb_+min_bb_)/static_cast<double>(2.0);
00329       
00330       //return success
00331       return (1);
00332     }
00334 
00335     int 
00336     OutofcoreOctreeNodeMetadata::loadMetadataFromDisk (const boost::filesystem::path& path_to_metadata)
00337     {
00338       this->setMetadataFilename (path_to_metadata);
00339       this->setDirectoryPathname (path_to_metadata.parent_path ());
00340       return (this->loadMetadataFromDisk ());
00341     }
00342 
00344 
00345     std::ostream& 
00346     operator<<(std::ostream&, const OutofcoreOctreeNodeMetadata&)
00347     {
00348       //todo: implement me
00349       PCL_THROW_EXCEPTION (PCLException, "Not implemented\n");
00350     }
00351     
00353 
00354 
00355   }//namespace outofcore
00356 }//namespace pcl
00357 
00358   
00359     
00360     


pcl
Author(s): Open Perception
autogenerated on Wed Aug 26 2015 15:27:30