Go to the documentation of this file.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
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040 #ifndef PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_
00041 #define PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_
00042
00043
00044 #include <vector>
00045 #include <string>
00046
00047 #include <pcl/outofcore/boost.h>
00048 #include <pcl/outofcore/octree_abstract_node_container.h>
00049 #include <pcl/io/pcd_io.h>
00050 #include <pcl/PCLPointCloud2.h>
00051
00052
00053 #if !defined WIN32
00054 #define _fseeki64 fseeko
00055 #elif defined __MINGW32__
00056 #define _fseeki64 fseeko64
00057 #endif
00058
00059 namespace pcl
00060 {
00061 namespace outofcore
00062 {
00072 template<typename PointT = pcl::PointXYZ>
00073 class OutofcoreOctreeDiskContainer : public OutofcoreAbstractNodeContainer<PointT>
00074 {
00075
00076 public:
00077 typedef typename OutofcoreAbstractNodeContainer<PointT>::AlignedPointTVector AlignedPointTVector;
00078
00080 OutofcoreOctreeDiskContainer ();
00081
00091 OutofcoreOctreeDiskContainer (const boost::filesystem::path &dir);
00092
00094 ~OutofcoreOctreeDiskContainer ();
00095
00098 inline PointT
00099 operator[] (uint64_t idx) const;
00100
00102 inline void
00103 push_back (const PointT& p);
00104
00106 void
00107 insertRange (const AlignedPointTVector& src);
00108
00110 void
00111 insertRange (const pcl::PCLPointCloud2::Ptr &input_cloud);
00112
00113 void
00114 insertRange (const PointT* const * start, const uint64_t count);
00115
00124 void
00125 insertRange (const PointT* start, const uint64_t count);
00126
00135 void
00136 readRange (const uint64_t start, const uint64_t count, AlignedPointTVector &dst);
00137
00138 void
00139 readRange (const uint64_t, const uint64_t, pcl::PCLPointCloud2::Ptr &dst);
00140
00144 int
00145 read (pcl::PCLPointCloud2::Ptr &output_cloud);
00146
00157 void
00158 readRangeSubSample (const uint64_t start, const uint64_t count, const double percent,
00159 AlignedPointTVector &dst);
00160
00170 void
00171 readRangeSubSample_bernoulli (const uint64_t start, const uint64_t count,
00172 const double percent, AlignedPointTVector& dst);
00173
00176 uint64_t
00177 size () const
00178 {
00179 return (filelen_ + writebuff_.size ());
00180 }
00181
00184 inline bool
00185 empty () const
00186 {
00187 return ((filelen_ == 0) && writebuff_.empty ());
00188 }
00189
00191 void
00192 flush (const bool force_cache_dealloc)
00193 {
00194 flushWritebuff (force_cache_dealloc);
00195 }
00196
00198 inline std::string&
00199 path ()
00200 {
00201 return (*disk_storage_filename_);
00202 }
00203
00204 inline void
00205 clear ()
00206 {
00207
00208 writebuff_.clear ();
00209
00210 PCL_DEBUG ("[Octree Disk Container] Removing the point data from disk, in file %s\n",disk_storage_filename_->c_str ());
00211 boost::filesystem::remove (boost::filesystem::path (disk_storage_filename_->c_str ()));
00212
00213 filelen_ = 0;
00214 }
00215
00220 void
00221 convertToXYZ (const boost::filesystem::path &path)
00222 {
00223 if (boost::filesystem::exists (*disk_storage_filename_))
00224 {
00225 FILE* fxyz = fopen (path.string ().c_str (), "w");
00226
00227 FILE* f = fopen (disk_storage_filename_->c_str (), "rb");
00228 assert (f != NULL);
00229
00230 uint64_t num = size ();
00231 PointT p;
00232 char* loc = reinterpret_cast<char*> ( &p );
00233
00234 for (uint64_t i = 0; i < num; i++)
00235 {
00236 int seekret = _fseeki64 (f, i * sizeof (PointT), SEEK_SET);
00237 (void)seekret;
00238 assert (seekret == 0);
00239 size_t readlen = fread (loc, sizeof (PointT), 1, f);
00240 (void)readlen;
00241 assert (readlen == 1);
00242
00243
00244 std::stringstream ss;
00245 ss << std::fixed;
00246 ss.precision (16);
00247 ss << p.x << "\t" << p.y << "\t" << p.z << "\n";
00248
00249 fwrite (ss.str ().c_str (), 1, ss.str ().size (), fxyz);
00250 }
00251 int res = fclose (f);
00252 (void)res;
00253 assert (res == 0);
00254 res = fclose (fxyz);
00255 assert (res == 0);
00256 }
00257 }
00258
00264 static void
00265 getRandomUUIDString (std::string &s);
00266
00268 boost::uint64_t
00269 getDataSize () const;
00270
00271 private:
00272
00273 OutofcoreOctreeDiskContainer (const OutofcoreOctreeDiskContainer &rval) { }
00274
00275
00276 OutofcoreOctreeDiskContainer&
00277 operator= (const OutofcoreOctreeDiskContainer &rval) { }
00278
00279 void
00280 flushWritebuff (const bool force_cache_dealloc);
00281
00283 boost::shared_ptr<std::string> disk_storage_filename_;
00284
00285
00286
00287
00288 uint64_t filelen_;
00289
00291 AlignedPointTVector writebuff_;
00292
00293 const static uint64_t READ_BLOCK_SIZE_;
00294
00295 static const uint64_t WRITE_BUFF_MAX_;
00296
00297 static boost::mutex rng_mutex_;
00298 static boost::mt19937 rand_gen_;
00299 static boost::uuids::random_generator uuid_gen_;
00300
00301 };
00302 }
00303 }
00304
00305 #endif //PCL_OUTOFCORE_OCTREE_DISK_CONTAINER_H_